Commit 7c0c855 1 parent cb04f79 commit 7c0c855 Copy full SHA for 7c0c855
File tree 2 files changed +6
-0
lines changed
nebula_decoders/src/nebula_decoders_velodyne/decoders
2 files changed +6
-0
lines changed Original file line number Diff line number Diff line change @@ -300,6 +300,9 @@ void Vlp32Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_pa
300
300
current_point.return_type = static_cast <uint8_t >(return_type);
301
301
current_point.channel = corrections.laser_ring ;
302
302
current_point.azimuth = rotation_radians_[block.rotation ];
303
+
304
+ if (check_invalid_point (corrections.laser_ring , block.rotation )) continue ;
305
+
303
306
current_point.elevation = sin_vert_angle;
304
307
auto point_ts = block_timestamp - scan_timestamp_ + point_time_offset;
305
308
if (point_ts < 0 )
Original file line number Diff line number Diff line change @@ -294,6 +294,9 @@ void Vls128Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_p
294
294
current_point.return_type = return_type;
295
295
current_point.channel = corrections.laser_ring ;
296
296
current_point.azimuth = rotation_radians_[azimuth_corrected];
297
+
298
+ if (check_invalid_point (corrections.laser_ring , azimuth_corrected)) continue ;
299
+
297
300
current_point.elevation = sin_vert_angle;
298
301
current_point.distance = distance;
299
302
auto point_ts = block_timestamp - scan_timestamp_ + point_time_offset;
You can’t perform that action at this time.
0 commit comments