From 83b201a4c5a457ce37d5e0ec59f26a80018b0325 Mon Sep 17 00:00:00 2001 From: Bernardo Taveira Date: Sat, 22 Jan 2022 01:37:43 +0100 Subject: [PATCH 1/3] fix crash indexing for laser scan creation --- ros2_ouster/include/ros2_ouster/conversions.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ros2_ouster/include/ros2_ouster/conversions.hpp b/ros2_ouster/include/ros2_ouster/conversions.hpp index b8e5e9a..a37401e 100644 --- a/ros2_ouster/include/ros2_ouster/conversions.hpp +++ b/ros2_ouster/include/ros2_ouster/conversions.hpp @@ -231,6 +231,7 @@ inline sensor_msgs::msg::LaserScan toMsg( msg.intensities.push_back( static_cast((ls.field(ouster::LidarScan::INTENSITY)(i))) ); + if (i == 0) break; // Fix #90 } return msg; From f35c14c23507fa589774ae687af6cf476c0c9c65 Mon Sep 17 00:00:00 2001 From: Bernardo Taveira Date: Tue, 25 Jan 2022 00:50:30 +0100 Subject: [PATCH 2/3] Another solution --- ros2_ouster/include/ros2_ouster/conversions.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ros2_ouster/include/ros2_ouster/conversions.hpp b/ros2_ouster/include/ros2_ouster/conversions.hpp index a37401e..5954352 100644 --- a/ros2_ouster/include/ros2_ouster/conversions.hpp +++ b/ros2_ouster/include/ros2_ouster/conversions.hpp @@ -224,14 +224,13 @@ inline sensor_msgs::msg::LaserScan toMsg( ouster::sensor::n_cols_of_lidar_mode(mdata.mode); msg.angle_increment = 2 * M_PI / ouster::sensor::n_cols_of_lidar_mode(mdata.mode); - for (size_t i = ls.w * ring_to_use + ls.w - 1; i >= ls.w * ring_to_use; i--) { + for (size_t i = ls.w * ring_to_use + ls.w; i-- > ls.w * ring_to_use;) { msg.ranges.push_back( static_cast((ls.field(ouster::LidarScan::RANGE)(i) * ouster::sensor::range_unit)) ); msg.intensities.push_back( static_cast((ls.field(ouster::LidarScan::INTENSITY)(i))) ); - if (i == 0) break; // Fix #90 } return msg; From 3d81924ea02747560701a00e3e848d33a5cb477b Mon Sep 17 00:00:00 2001 From: Bernardo Taveira Date: Wed, 26 Jan 2022 22:02:52 +0100 Subject: [PATCH 3/3] Add comment explaining fix --- ros2_ouster/include/ros2_ouster/conversions.hpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ros2_ouster/include/ros2_ouster/conversions.hpp b/ros2_ouster/include/ros2_ouster/conversions.hpp index 5954352..62192fe 100644 --- a/ros2_ouster/include/ros2_ouster/conversions.hpp +++ b/ros2_ouster/include/ros2_ouster/conversions.hpp @@ -224,6 +224,9 @@ inline sensor_msgs::msg::LaserScan toMsg( ouster::sensor::n_cols_of_lidar_mode(mdata.mode); msg.angle_increment = 2 * M_PI / ouster::sensor::n_cols_of_lidar_mode(mdata.mode); + // Fix #90 (PR #92) - The iterator is in the loop condition to prevent overflow by + // decrementing unsigned variable 'i' bellow 0. This happened when ring 0 was selected + // due to the condition being reduced to i >= 0 for (size_t i = ls.w * ring_to_use + ls.w; i-- > ls.w * ring_to_use;) { msg.ranges.push_back( static_cast((ls.field(ouster::LidarScan::RANGE)(i) * ouster::sensor::range_unit))