Skip to content

Commit b1ad78a

Browse files
committed
Expose the vertical beam reduction value + rename arg + Better handling of deprecated topic names
1 parent 34b84de commit b1ad78a

File tree

10 files changed

+55
-14
lines changed

10 files changed

+55
-14
lines changed

CHANGELOG.rst

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,8 @@ Changelog
1919
* Add a padding-free point type of ``PointXYZI`` under ``ouster_ros`` namespace contrary to the pcl
2020
version ``pcl::PointXYZI`` for bandwith sensitive applications.
2121
* [BUGFIX]: Use the node clock to ensure messages report sim time in replay mode.
22+
* Introduce a new param ``v_reduction`` that allows reducing the number of beams count of the published
23+
point cloud
2224

2325

2426
ouster_ros v0.13.2

ouster-ros/config/driver_params.yaml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -117,6 +117,8 @@ ouster/os_driver:
117117
min_range: 0.0
118118
# max_range[optional]: maximum lidar range to consider (meters).
119119
max_range: 1000.0
120+
# v_reduction[optional]: vertical beam reduction; available options: {1, 2, 4, 8, 16}.
121+
v_reduction: 1
120122
# min_scan_valid_columns_ratio[optional]: The minimum ratio of valid columns for
121123
# processing the LidarScan [0, 1]. default is 0%
122124
min_scan_valid_columns_ratio: 0.0

ouster-ros/config/metadata-qos-override.yaml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,3 +3,9 @@
33
depth: 1
44
reliability: reliable
55
durability: transient_local
6+
7+
/os_node/metadata:
8+
history: keep_last
9+
depth: 1
10+
reliability: reliable
11+
durability: transient_local

ouster-ros/launch/record.composite.launch.xml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -115,6 +115,9 @@
115115
<arg name="min_scan_valid_columns_ratio" default="0.0"
116116
description="The minimum ratio of valid columns for processing the LidarScan [0, 1]"/>
117117

118+
<arg name="v_reduction" default="1" description="vertical beam reduction;
119+
available options: {1, 2, 4, 8, 16}"/>
120+
118121
<group>
119122
<push-ros-namespace namespace="$(var ouster_ns)"/>
120123
<node_container pkg="rclcpp_components" exec="component_container_mt" name="os_container" output="screen" namespace="">
@@ -156,6 +159,7 @@
156159
<param name="destagger" value="$(var destagger)"/>
157160
<param name="min_range" value="$(var min_range)"/>
158161
<param name="max_range" value="$(var max_range)"/>
162+
<param name="v_reduction" value="$(var v_reduction)"/>
159163
<param name="min_scan_valid_columns_ratio" value="$(var min_scan_valid_columns_ratio)"/>
160164
</composable_node>
161165
<composable_node pkg="ouster_ros" plugin="ouster_ros::OusterImage" name="os_image">

ouster-ros/launch/replay.composite.launch.xml

Lines changed: 12 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -80,6 +80,9 @@
8080
<arg name="min_scan_valid_columns_ratio" default="0.0"
8181
description="The minimum ratio of valid columns for processing the LidarScan [0, 1]"/>
8282

83+
<arg name="v_reduction" default="1" description="vertical beam reduction;
84+
available options: {1, 2, 4, 8, 16}"/>
85+
8386
<group>
8487
<push-ros-namespace namespace="$(var ouster_ns)"/>
8588
<node if="$(var _use_metadata_file)" pkg="ouster_ros" exec="os_replay" name="os_replay" output="screen">
@@ -88,9 +91,6 @@
8891
</node>
8992
<node_container pkg="rclcpp_components" exec="component_container_mt" name="os_container" output="screen" namespace="">
9093
<composable_node pkg="ouster_ros" plugin="ouster_ros::OusterCloud" name="os_cloud">
91-
<remap from="/os_node/metadata" to="/ouster/metadata"/>
92-
<remap from="/os_node/imu_packets" to="/ouster/imu_packets"/>
93-
<remap from="/os_node/lidar_packets" to="/ouster/lidar_packets"/>
9494
<param name="sensor_frame" value="$(var sensor_frame)"/>
9595
<param name="lidar_frame" value="$(var lidar_frame)"/>
9696
<param name="imu_frame" value="$(var imu_frame)"/>
@@ -106,11 +106,10 @@
106106
<param name="destagger" value="$(var destagger)"/>
107107
<param name="min_range" value="$(var min_range)"/>
108108
<param name="max_range" value="$(var max_range)"/>
109+
<param name="v_reduction" value="$(var v_reduction)"/>
109110
<param name="min_scan_valid_columns_ratio" value="$(var min_scan_valid_columns_ratio)"/>
110111
</composable_node>
111112
<composable_node pkg="ouster_ros" plugin="ouster_ros::OusterImage" name="os_image">
112-
<remap from="/os_node/metadata" to="/ouster/metadata"/>
113-
<remap from="/os_node/lidar_packets" to="/ouster/lidar_packets"/>
114113
<param name="use_system_default_qos" value="$(var use_system_default_qos)"/>
115114
<param name="proc_mask" value="$(var proc_mask)"/>
116115
</composable_node>
@@ -127,7 +126,13 @@
127126
<executable if="$(var _use_bag_file_name)" output="screen"
128127
launch-prefix="bash -c 'sleep $(var play_delay); $0 $@'"
129128
cmd="ros2 bag play $(var bag_file) --clock $(var _loop)
130-
--rate $(var play_rate) --qos-profile-overrides-path
131-
$(find-pkg-share ouster_ros)/config/metadata-qos-override.yaml"/>
129+
--rate $(var play_rate)
130+
--remap
131+
/os_node/metadata:=/ouster/metadata
132+
/os_node/imu_packets:=/ouster/imu_packets
133+
/os_node/lidar_packets:=/ouster/lidar_packets
134+
--qos-profile-overrides-path
135+
$(find-pkg-share ouster_ros)/config/metadata-qos-override.yaml
136+
"/>
132137

133138
</launch>

ouster-ros/launch/replay_pcap.launch.xml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,9 @@
7676
<arg name="min_scan_valid_columns_ratio" default="0.0"
7777
description="The minimum ratio of valid columns for processing the LidarScan [0, 1]"/>
7878

79+
<arg name="v_reduction" default="1" description="vertical beam reduction;
80+
available options: {1, 2, 4, 8, 16}"/>
81+
7982
<group>
8083
<push-ros-namespace namespace="$(var ouster_ns)"/>
8184
<node if="$(var _use_metadata_file)" pkg="ouster_ros" exec="os_pcap" name="os_pcap"
@@ -103,6 +106,7 @@
103106
<param name="destagger" value="$(var destagger)"/>
104107
<param name="min_range" value="$(var min_range)"/>
105108
<param name="max_range" value="$(var max_range)"/>
109+
<param name="v_reduction" value="$(var v_reduction)"/>
106110
<param name="min_scan_valid_columns_ratio" value="$(var min_scan_valid_columns_ratio)"/>
107111
</composable_node>
108112
<composable_node pkg="ouster_ros" plugin="ouster_ros::OusterImage" name="os_image">

ouster-ros/launch/sensor.composite.launch.xml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -111,6 +111,9 @@
111111
<arg name="min_scan_valid_columns_ratio" default="0.0"
112112
description="The minimum ratio of valid columns for processing the LidarScan [0, 1]"/>
113113

114+
<arg name="v_reduction" default="1" description="vertical beam reduction;
115+
available options: {1, 2, 4, 8, 16}"/>
116+
114117
<group>
115118
<push-ros-namespace namespace="$(var ouster_ns)"/>
116119
<node pkg="ouster_ros" exec="os_driver" name="os_driver" output="screen">
@@ -147,6 +150,7 @@
147150
<param name="destagger" value="$(var destagger)"/>
148151
<param name="min_range" value="$(var min_range)"/>
149152
<param name="max_range" value="$(var max_range)"/>
153+
<param name="v_reduction" value="$(var v_reduction)"/>
150154
<param name="min_scan_valid_columns_ratio"
151155
value="$(var min_scan_valid_columns_ratio)"/>
152156
</node>

ouster-ros/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>ouster_ros</name>
5-
<version>0.13.8</version>
5+
<version>0.13.9</version>
66
<description>Ouster ROS2 driver</description>
77
<maintainer email="oss@ouster.io">ouster developers</maintainer>
88
<license file="LICENSE">BSD</license>

ouster-ros/src/os_cloud_node.cpp

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ class OusterCloud : public OusterProcessingNodeBase {
6565
declare_parameter("destagger", true);
6666
declare_parameter("min_range", 0.0);
6767
declare_parameter("max_range", 1000.0);
68-
declare_parameter("rows_step", 1);
68+
declare_parameter("v_reduction", 1);
6969
declare_parameter("min_scan_valid_columns_ratio", 0.0);
7070
}
7171

@@ -149,12 +149,19 @@ class OusterCloud : public OusterProcessingNodeBase {
149149
// convert to millimeters
150150
uint32_t min_range = impl::ulround(min_range_m * 1000);
151151
uint32_t max_range = impl::ulround(max_range_m * 1000);
152-
auto rows_step = get_parameter("rows_step").as_int();
152+
auto v_reduction = get_parameter("v_reduction").as_int();
153+
auto valid_values = std::vector<int>{1, 2, 4, 8, 16};
154+
if (std::find(valid_values.begin(), valid_values.end(), v_reduction) == valid_values.end()) {
155+
RCLCPP_FATAL_STREAM(get_logger(),
156+
"v_reduction needs to be one of the values: " << valid_values);
157+
throw std::runtime_error("invalid v_reduction value!");
158+
}
159+
153160
processors.push_back(
154161
PointCloudProcessorFactory::create_point_cloud_processor(point_type,
155162
info, tf_bcast.point_cloud_frame_id(),
156163
tf_bcast.apply_lidar_to_sensor_transform(),
157-
organized, destagger, min_range, max_range, rows_step,
164+
organized, destagger, min_range, max_range, v_reduction,
158165
[this](PointCloudProcessor_OutputType msgs) {
159166
for (size_t i = 0; i < msgs.size(); ++i)
160167
lidar_pubs[i]->publish(*msgs[i]);

ouster-ros/src/os_driver_node.cpp

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ class OusterDriver : public OusterSensor {
4646
declare_parameter("destagger", true);
4747
declare_parameter("min_range", 0.0);
4848
declare_parameter("max_range", 1000.0);
49-
declare_parameter("rows_step", 1);
49+
declare_parameter("v_reduction", 1);
5050
declare_parameter("min_scan_valid_columns_ratio", 0.0);
5151
}
5252

@@ -117,12 +117,19 @@ class OusterDriver : public OusterSensor {
117117
// convert to millimeters
118118
uint32_t min_range = impl::ulround(min_range_m * 1000);
119119
uint32_t max_range = impl::ulround(max_range_m * 1000);
120-
auto rows_step = get_parameter("rows_step").as_int();
120+
auto v_reduction = get_parameter("v_reduction").as_int();
121+
auto valid_values = std::vector<int>{1, 2, 4, 8, 16};
122+
if (std::find(valid_values.begin(), valid_values.end(), v_reduction) == valid_values.end()) {
123+
RCLCPP_FATAL_STREAM(get_logger(),
124+
"v_reduction needs to be one of the values: " << valid_values);
125+
throw std::runtime_error("invalid v_reduction value!");
126+
}
127+
121128
processors.push_back(
122129
PointCloudProcessorFactory::create_point_cloud_processor(point_type,
123130
info, tf_bcast.point_cloud_frame_id(),
124131
tf_bcast.apply_lidar_to_sensor_transform(),
125-
organized, destagger, min_range, max_range, rows_step,
132+
organized, destagger, min_range, max_range, v_reduction,
126133
[this](PointCloudProcessor_OutputType msgs) {
127134
for (size_t i = 0; i < msgs.size(); ++i)
128135
lidar_pubs[i]->publish(*msgs[i]);

0 commit comments

Comments
 (0)