@@ -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]);
0 commit comments