@@ -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