@@ -19,6 +19,7 @@ Preprocess::Preprocess() : feature_enabled(0), lidar_type(AVIA), blind(0.01), po
1919{
2020 inf_bound = 10 ;
2121 N_SCANS = 6 ;
22+ SCAN_RATE = 10 ;
2223 group_size = 8 ;
2324 disA = 0.01 ;
2425 disA = 0.1 ; // B?
@@ -347,15 +348,16 @@ void Preprocess::velodyne_handler(const sensor_msgs::msg::PointCloud2::ConstShar
347348 pcl::PointCloud<velodyne_ros::Point> pl_orig;
348349 pcl::fromROSMsg (*msg, pl_orig);
349350 int plsize = pl_orig.points .size ();
351+ if (plsize == 0 ) return ;
350352 pl_surf.reserve (plsize);
351353
352354 bool is_first[MAX_LINE_NUM];
353355 double yaw_fp[MAX_LINE_NUM] = {0 }; // yaw of first scan point
354- double omega_l = 3.61 ; // scan angular velocity
356+ double omega_l = 0.361 * SCAN_RATE; // scan angular velocity
355357 float yaw_last[MAX_LINE_NUM] = {0.0 }; // yaw of last scan point
356358 float time_last[MAX_LINE_NUM] = {0.0 }; // last offset time
357359
358- if (pl_orig.points [plsize - 1 ].t > 0 ) { given_offset_time = true ; }
360+ if (pl_orig.points [plsize - 1 ].time > 0 ) { given_offset_time = true ; }
359361 else
360362 {
361363 given_offset_time = false ;
@@ -393,7 +395,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::msg::PointCloud2::ConstShar
393395 added_pt.y = pl_orig.points [i].y ;
394396 added_pt.z = pl_orig.points [i].z ;
395397 added_pt.intensity = pl_orig.points [i].intensity ;
396- added_pt.curvature = pl_orig.points [i].t / 1000.0 ; // units: ms
398+ added_pt.curvature = pl_orig.points [i].time / 1000.0 ; // units: ms
397399
398400 if (!given_offset_time)
399401 {
@@ -456,7 +458,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::msg::PointCloud2::ConstShar
456458 added_pt.y = pl_orig.points [i].y ;
457459 added_pt.z = pl_orig.points [i].z ;
458460 added_pt.intensity = pl_orig.points [i].intensity ;
459- added_pt.curvature = pl_orig.points [i].t / 1000.0 ;
461+ added_pt.curvature = pl_orig.points [i].time / 1000.0 ;
460462
461463 if (!given_offset_time)
462464 {
0 commit comments