Skip to content

Commit c39f875

Browse files
authored
Expose the v_reduction param (#445)
1 parent 80b37a0 commit c39f875

File tree

11 files changed

+45
-5
lines changed

11 files changed

+45
-5
lines changed

CHANGELOG.rst

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@ Changelog
1616
ratio of valid columns in a scan for it to be processed. Default value is ``0.0``.
1717
* Add a padding-free point type of ``PointXYZI`` under ``ouster_ros`` namespace contrary to the pcl
1818
version ``pcl::PointXYZI`` for bandwith sensitive applications.
19+
* Introduce a new param ``v_reduction`` that allows reducing the number of beams count of the published
20+
point cloud.
1921

2022

2123
ouster_ros v0.13.0

launch/common.launch

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,8 @@
5555
<arg name="min_scan_valid_columns_ratio"
5656
doc="The minimum ratio of valid columns for processing the LidarScan [0, 1]"/>
5757

58+
<arg name="v_reduction" doc="vertical beam reduction; available options: {1, 2, 4, 8, 16}"/>
59+
5860
<group ns="$(arg ouster_ns)">
5961
<node pkg="nodelet" type="nodelet" name="os_cloud_node"
6062
output="screen" required="true"
@@ -78,6 +80,7 @@
7880
<param name="~/destagger" value="$(arg destagger)"/>
7981
<param name="~/min_range" value="$(arg min_range)"/>
8082
<param name="~/max_range" value="$(arg max_range)"/>
83+
<param name="~/v_reduction" value="$(arg v_reduction)"/>
8184
<param name="~/min_scan_valid_columns_ratio"
8285
value="$(arg min_scan_valid_columns_ratio)"/>
8386
</node>

launch/driver.launch

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

106+
<arg name="v_reduction" default="1"
107+
doc="vertical beam reduction; available options: {1, 2, 4, 8, 16}"/>
108+
106109
<group ns="$(arg ouster_ns)">
107110
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
108111
output="screen" required="true" args="manager"/>
@@ -143,6 +146,7 @@
143146
<param name="~/destagger" value="$(arg destagger)"/>
144147
<param name="~/min_range" value="$(arg min_range)"/>
145148
<param name="~/max_range" value="$(arg max_range)"/>
149+
<param name="~/v_reduction" value="$(arg v_reduction)"/>
146150
<param name="~/min_scan_valid_columns_ratio"
147151
value="$(arg min_scan_valid_columns_ratio)"/>
148152
</node>

launch/record.launch

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

106+
<arg name="v_reduction" default="1"
107+
doc="vertical beam reduction; available options: {1, 2, 4, 8, 16}"/>
108+
106109
<group ns="$(arg ouster_ns)">
107110
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
108111
output="screen" required="true" args="manager"/>
@@ -158,6 +161,7 @@
158161
<arg name="destagger" value="$(arg destagger)"/>
159162
<arg name="min_range" value="$(arg min_range)"/>
160163
<arg name="max_range" value="$(arg max_range)"/>
164+
<arg name="v_reduction" value="$(arg v_reduction)"/>
161165
<arg name="min_scan_valid_columns_ratio"
162166
value="$(arg min_scan_valid_columns_ratio)"/>
163167
</include>

launch/replay.launch

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

84+
<arg name="v_reduction" default="1"
85+
doc="vertical beam reduction; available options: {1, 2, 4, 8, 16}"/>
86+
8487
<group ns="$(arg ouster_ns)">
8588
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
8689
output="screen" required="true" args="manager"/>
@@ -120,6 +123,7 @@
120123
<arg name="destagger" value="$(arg destagger)"/>
121124
<arg name="min_range" value="$(arg min_range)"/>
122125
<arg name="max_range" value="$(arg max_range)"/>
126+
<are name="v_reduction" value="$(arg v_reduction)"/>
123127
<arg name="min_scan_valid_columns_ratio"
124128
value="$(arg min_scan_valid_columns_ratio)"/>
125129
</include>

launch/replay_pcap.launch

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

78+
<arg name="v_reduction" default="1"
79+
doc="vertical beam reduction; available options: {1, 2, 4, 8, 16}"/>
80+
7881
<group ns="$(arg ouster_ns)">
7982
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
8083
output="screen" required="true" args="manager"/>
@@ -115,6 +118,7 @@
115118
<arg name="destagger" value="$(arg destagger)"/>
116119
<arg name="min_range" value="$(arg min_range)"/>
117120
<arg name="max_range" value="$(arg max_range)"/>
121+
<arg name="v_reduction" value="$(arg v_reduction)"/>
118122
<arg name="min_scan_valid_columns_ratio"
119123
value="$(arg min_scan_valid_columns_ratio)"/>
120124
</include>

launch/sensor.launch

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
doc="The minimum ratio of valid columns for processing the LidarScan [0, 1]"/>
113113

114+
<arg name="v_reduction" default="1"
115+
doc="vertical beam reduction; available options: {1, 2, 4, 8, 16}"/>
116+
114117
<group ns="$(arg ouster_ns)">
115118
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
116119
output="screen" required="true" args="manager"/>
@@ -166,6 +169,7 @@
166169
<arg name="destagger" value="$(arg destagger)"/>
167170
<arg name="min_range" value="$(arg min_range)"/>
168171
<arg name="max_range" value="$(arg max_range)"/>
172+
<arg name="v_reduction" value="$(arg v_reduction)"/>
169173
<arg name="min_scan_valid_columns_ratio"
170174
value="$(arg min_scan_valid_columns_ratio)"/>
171175
</include>

launch/sensor_mtp.launch

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
doc="The minimum ratio of valid columns for processing the LidarScan [0, 1]"/>
117117

118+
<arg name="v_reduction" default="1"
119+
doc="vertical beam reduction; available options: {1, 2, 4, 8, 16}"/>
120+
118121
<group ns="$(arg ouster_ns)">
119122
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
120123
output="screen" required="true" args="manager"/>
@@ -172,6 +175,7 @@
172175
<arg name="destagger" value="$(arg destagger)"/>
173176
<arg name="min_range" value="$(arg min_range)"/>
174177
<arg name="max_range" value="$(arg max_range)"/>
178+
<arg name="v_reduction" value="$(arg v_reduction)"/>
175179
<arg name="min_scan_valid_columns_ratio"
176180
value="$(arg min_scan_valid_columns_ratio)"/>
177181
</include>

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="3">
33
<name>ouster_ros</name>
4-
<version>0.13.5</version>
4+
<version>0.13.6</version>
55
<description>Ouster ROS driver</description>
66
<maintainer email="oss@ouster.io">ouster developers</maintainer>
77
<license file="LICENSE">BSD</license>

src/os_cloud_nodelet.cpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -206,13 +206,18 @@ class OusterCloud : public nodelet::Nodelet {
206206
// convert to millimeters
207207
uint32_t min_range = impl::ulround(min_range_m * 1000);
208208
uint32_t max_range = impl::ulround(max_range_m * 1000);
209-
auto rows_step = pnh.param("rows_step", 1);
209+
auto v_reduction = pnh.param("v_reduction", 1);
210+
auto valid_values = std::vector<int>{1, 2, 4, 8, 16};
211+
if (std::find(valid_values.begin(), valid_values.end(), v_reduction) == valid_values.end()) {
212+
NODELET_FATAL("v_reduction needs to be one of the values: {1, 2, 4, 8, 16}");
213+
throw std::runtime_error("invalid v_reduction value!");
214+
}
210215

211216
processors.push_back(
212217
PointCloudProcessorFactory::create_point_cloud_processor(
213218
point_type, info, tf_bcast.point_cloud_frame_id(),
214219
tf_bcast.apply_lidar_to_sensor_transform(), organized,
215-
destagger, min_range, max_range, rows_step,
220+
destagger, min_range, max_range, v_reduction,
216221
[this](PointCloudProcessor_OutputType msgs) {
217222
for (size_t i = 0; i < msgs.size(); ++i) {
218223
if (msgs[i]->header.stamp > last_msg_ts)

0 commit comments

Comments
 (0)