Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ROS-227: Set LIDAR FOV on startup and add an option to persist the config [FOXY] #358

Merged
merged 1 commit into from
Aug 21, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,11 @@ Changelog
* [BREAKING]: Set xyz values of individual points in the PointCloud to NaNs when range is zero.
* Added support to replay pcap format direclty from ouster-ros. The feature needs to be enabled
explicitly by turning on the ``BUILD_PCAP`` cmake option and having ``libpcap-dev`` installed.
* [BREAKING] Added new launch files args ``azimuth_window_start`` and ``azimuth_window_end`` to
allow users to set LIDAR FOV on startup. The new options will reset the current azimuth window
to the default
* Added a new launch ``persist_config`` option to request the sensor persist the current config
* Added a new ``loop`` option to the ``replay.launch.xml`` file.

ouster_ros v0.12.0
==================
Expand Down
8 changes: 7 additions & 1 deletion ouster-ros/config/driver_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -86,4 +86,10 @@ ouster/os_driver:
# - ouster_ros/os_point.h
# - ouster_ros/sensor_point_types.h
# - ouster_ros/common_point_types.h.
point_type: original
point_type: original
# azimuth window start[optional]: values range [0, 360000] millidegrees
azimuth_window_start: 0
# azimuth_window_end[optional]: values range [0, 360000] millidegrees
azimuth_window_end: 360000
# persist_config[optional]: request the sensor to persist settings
persist_config: false
3 changes: 3 additions & 0 deletions ouster-ros/config/os_sensor_cloud_image_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,9 @@ ouster/os_sensor:
lidar_port: 0
imu_port: 0
use_system_default_qos: False
azimuth_window_start: 0
azimuth_window_end: 360000
persist_config: false
ouster/os_cloud:
ros__parameters:
sensor_frame: os_sensor
Expand Down
21 changes: 21 additions & 0 deletions ouster-ros/launch/record.independent.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,23 @@
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"/>

<arg name="point_type" default="original" description="point type for the generated point cloud;
available options: {
original,
native,
xyz,
xyzi,
xyzir
}"/>

<arg name="azimuth_window_start" default="0" description="azimuth window start;
values range [0, 360000] millidegrees"/>
<arg name="azimuth_window_end" default="360000" description="azimuth window end;
values range [0, 360000] millidegrees"/>

<arg name="persist_config" default="false"
description="request the sensor to persist settings"/>

<group>
<push-ros-namespace namespace="$(var ouster_ns)"/>
<node pkg="ouster_ros" exec="os_sensor" name="os_sensor" output="screen">
Expand All @@ -82,6 +99,9 @@
<param name="timestamp_mode" value="$(var timestamp_mode)"/>
<param name="metadata" value="$(var metadata)"/>
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
<param name="azimuth_window_start" value="$(var azimuth_window_start)"/>
<param name="azimuth_window_end" value="$(var azimuth_window_end)"/>
<param name="persist_config" value="$(var persist_config)"/>
</node>
<node pkg="ouster_ros" exec="os_cloud" name="os_cloud" output="screen">
<param name="sensor_frame" value="$(var sensor_frame)"/>
Expand All @@ -93,6 +113,7 @@
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
<param name="proc_mask" value="$(var proc_mask)"/>
<param name="scan_ring" value="$(var scan_ring)"/>
<param name="point_type" value="$(var point_type)"/>
</node>
<node pkg="ouster_ros" exec="os_image" name="os_image" output="screen">
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
Expand Down
11 changes: 9 additions & 2 deletions ouster-ros/launch/replay.independent.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,13 @@

<set_parameter name="use_sim_time" value="true" />

<arg name="loop" default="false" description="request loop playback"/>
<arg if="$(arg loop)" name="_loop" value="--loop"/>
<arg unless="$(arg loop)" name="_loop" value=" "/>

<remap from="/os_node/imu_packets" to="/ouster/imu_packets"/>
<remap from="/os_node/lidar_packets" to="/ouster/lidar_packets"/>

<arg name="ouster_ns" default="ouster"
description="Override the default namespace of all ouster nodes"/>
<!-- TODO: revisit the proper behaviour of allowing users override the default timestamp_mode during replay -->
Expand Down Expand Up @@ -97,8 +104,8 @@

<executable if="$(var _use_bag_file_name)" output="screen"
launch-prefix="bash -c 'sleep 3; $0 $@'"
cmd="ros2 bag play $(var bag_file)
--qos-profile-overrides-path
cmd="ros2 bag play $(var bag_file) --clock $(arg _loop)
--qos-profile-overrides-path
$(find-pkg-share ouster_ros)/config/metadata-qos-override.yaml"/>

</launch>
11 changes: 11 additions & 0 deletions ouster-ros/launch/sensor.composite.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,14 @@
xyzir
}"/>

<arg name="azimuth_window_start" default="0" description="azimuth window start;
values range [0, 360000] millidegrees"/>
<arg name="azimuth_window_end" default="360000" description="azimuth window end;
values range [0, 360000] millidegrees"/>

<arg name="persist_config" default="false"
description="request the sensor to persist settings"/>

<group>
<push-ros-namespace namespace="$(var ouster_ns)"/>
<node pkg="ouster_ros" exec="os_driver" name="os_driver" output="screen">
Expand All @@ -95,6 +103,9 @@
<param name="proc_mask" value="$(var proc_mask)"/>
<param name="scan_ring" value="$(var scan_ring)"/>
<param name="point_type" value="$(var point_type)"/>
<param name="azimuth_window_start" value="$(var azimuth_window_start)"/>
<param name="azimuth_window_end" value="$(var azimuth_window_end)"/>
<param name="persist_config" value="$(var persist_config)"/>
</node>
</group>

Expand Down
11 changes: 11 additions & 0 deletions ouster-ros/launch/sensor.independent.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,14 @@
xyzir
}"/>

<arg name="azimuth_window_start" default="0" description="azimuth window start;
values range [0, 360000] millidegrees"/>
<arg name="azimuth_window_end" default="360000" description="azimuth window end;
values range [0, 360000] millidegrees"/>

<arg name="persist_config" default="false"
description="request the sensor to persist settings"/>

<group>
<push-ros-namespace namespace="$(var ouster_ns)"/>
<node pkg="ouster_ros" exec="os_sensor" name="os_sensor" output="screen">
Expand All @@ -89,6 +97,9 @@
<param name="timestamp_mode" value="$(var timestamp_mode)"/>
<param name="metadata" value="$(var metadata)"/>
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
<param name="azimuth_window_start" value="$(var azimuth_window_start)"/>
<param name="azimuth_window_end" value="$(var azimuth_window_end)"/>
<param name="persist_config" value="$(var persist_config)"/>
</node>
<node pkg="ouster_ros" exec="os_cloud" name="os_cloud" output="screen">
<param name="sensor_frame" value="$(var sensor_frame)"/>
Expand Down
11 changes: 11 additions & 0 deletions ouster-ros/launch/sensor_mtp.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,14 @@
xyzir
}"/>

<arg name="azimuth_window_start" default="0" description="azimuth window start;
values range [0, 360000] millidegrees"/>
<arg name="azimuth_window_end" default="360000" description="azimuth window end;
values range [0, 360000] millidegrees"/>

<arg name="persist_config" default="false"
description="request the sensor to persist settings"/>

<group>
<push-ros-namespace namespace="$(var ouster_ns)"/>
<node pkg="ouster_ros" exec="os_driver" name="os_driver" output="screen">
Expand All @@ -103,6 +111,9 @@
<param name="proc_mask" value="$(var proc_mask)"/>
<param name="scan_ring" value="$(var scan_ring)"/>
<param name="point_type" value="$(var point_type)"/>
<param name="azimuth_window_start" value="$(var azimuth_window_start)"/>
<param name="azimuth_window_end" value="$(var azimuth_window_end)"/>
<param name="persist_config" value="$(var persist_config)"/>
</node>
</group>

Expand Down
2 changes: 1 addition & 1 deletion ouster-ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ouster_ros</name>
<version>0.12.5</version>
<version>0.12.6</version>
<description>Ouster ROS2 driver</description>
<maintainer email="[email protected]">ouster developers</maintainer>
<license file="LICENSE">BSD</license>
Expand Down
31 changes: 29 additions & 2 deletions ouster-ros/src/os_sensor_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ using ouster_sensor_msgs::srv::SetConfig;

using namespace std::chrono_literals;
using namespace std::string_literals;
using std::to_string;

namespace ouster_ros {

Expand Down Expand Up @@ -60,6 +61,9 @@ void OusterSensor::declare_parameters() {
declare_parameter("timestamp_mode", "");
declare_parameter("udp_profile_lidar", "");
declare_parameter("use_system_default_qos", false);
declare_parameter("azimuth_window_start", MIN_AZW);
declare_parameter("azimuth_window_end", MAX_AZW);
declare_parameter("persist_config", false);
}

LifecycleNodeInterface::CallbackReturn OusterSensor::on_configure(
Expand Down Expand Up @@ -445,6 +449,8 @@ sensor::sensor_config OusterSensor::parse_config_from_ros_parameters() {
auto lidar_mode_arg = get_parameter("lidar_mode").as_string();
auto timestamp_mode_arg = get_parameter("timestamp_mode").as_string();
auto udp_profile_lidar_arg = get_parameter("udp_profile_lidar").as_string();
auto azimuth_window_start = get_parameter("azimuth_window_start").as_int();
auto azimuth_window_end = get_parameter("azimuth_window_end").as_int();

if (lidar_port < 0 || lidar_port > 65535) {
auto error_msg =
Expand Down Expand Up @@ -527,6 +533,13 @@ sensor::sensor_config OusterSensor::parse_config_from_ros_parameters() {
config.udp_port_imu = imu_port;
}

persist_config = get_parameter("persist_config").as_bool();
if (persist_config && (lidar_port == 0 || imu_port == 0)) {
RCLCPP_WARN(get_logger(), "When using persist_config it is recommended "
" to not use 0 for port values as this currently will trigger sensor "
" reinit event each time");
}

config.udp_profile_lidar = udp_profile_lidar;
config.operating_mode = sensor::OPERATING_NORMAL;
if (lidar_mode) config.ld_mode = lidar_mode;
Expand All @@ -539,6 +552,16 @@ sensor::sensor_config OusterSensor::parse_config_from_ros_parameters() {
}
}

if (azimuth_window_start < MIN_AZW || azimuth_window_start > MAX_AZW ||
azimuth_window_end < MIN_AZW || azimuth_window_end > MAX_AZW) {
auto error_msg = "azimuth window values must be between " +
to_string(MIN_AZW) + " and " + to_string(MAX_AZW);
RCLCPP_ERROR_STREAM(get_logger(), error_msg);
throw std::runtime_error(error_msg);
}

config.azimuth_window = {azimuth_window_start, azimuth_window_end};

return config;
}

Expand Down Expand Up @@ -578,6 +601,11 @@ uint8_t OusterSensor::compose_config_flags(
config_flags |= ouster::sensor::CONFIG_FORCE_REINIT;
}

if (persist_config) {
RCLCPP_INFO(get_logger(), "Configuration will be persisted");
config_flags |= ouster::sensor::CONFIG_PERSIST;
}

return config_flags;
}

Expand Down Expand Up @@ -675,9 +703,8 @@ void OusterSensor::allocate_buffers() {
bool OusterSensor::init_id_changed(const sensor::packet_format& pf,
const uint8_t* lidar_buf) {
uint32_t current_init_id = pf.init_id(lidar_buf);
if (!last_init_id_initialized) {
if (!last_init_id) {
last_init_id = current_init_id + 1;
last_init_id_initialized = true;
}
if (reset_last_init_id && last_init_id != current_init_id) {
last_init_id = current_init_id;
Expand Down
7 changes: 5 additions & 2 deletions ouster-ros/src/os_sensor_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -172,11 +172,11 @@ class OusterSensor : public OusterSensorNodeBase {
std::atomic<bool> lidar_packets_processing_thread_active = {false};
std::unique_ptr<std::thread> lidar_packets_processing_thread;

bool persist_config = false;
bool force_sensor_reinit = false;
bool reset_last_init_id = true;

bool last_init_id_initialized = false;
uint32_t last_init_id;
nonstd::optional<uint32_t> last_init_id;

// TODO: add as a ros parameter
const int max_poll_client_error_count = 10;
Expand All @@ -187,6 +187,9 @@ class OusterSensor : public OusterSensorNodeBase {
// TODO: add as a ros parameter
const int max_read_imu_packet_errors = 60;
int read_imu_packet_errors = 0;

const int MIN_AZW = 0;
const int MAX_AZW = 360000;
};

} // namespace ouster_ros
Loading