From 2a7b90d6fb5c2803793fba02512d1f90b503b8b3 Mon Sep 17 00:00:00 2001 From: Leonard Date: Sun, 6 Jun 2021 12:24:02 +0200 Subject: [PATCH] Fixes segmentation fault for empty pointclouds See issue #1405 This small change fixes the issue where cartographer_rosbag_validate segfaults if the ros bag contains PointCloud2 messages without any points in them. --- cartographer_ros/cartographer_ros/rosbag_validate_main.cc | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/cartographer_ros/cartographer_ros/rosbag_validate_main.cc b/cartographer_ros/cartographer_ros/rosbag_validate_main.cc index c52c70049..d14388246 100644 --- a/cartographer_ros/cartographer_ros/rosbag_validate_main.cc +++ b/cartographer_ros/cartographer_ros/rosbag_validate_main.cc @@ -219,7 +219,10 @@ class RangeDataChecker { const cartographer::sensor::TimedPointCloud& point_cloud = std::get<0>(point_cloud_time).points; *to = std::get<1>(point_cloud_time); - *from = *to + cartographer::common::FromSeconds(point_cloud[0].time); + *from = *to; + if (point_cloud.size() > 0) { + *from += cartographer::common::FromSeconds(point_cloud[0].time); + } Eigen::Vector4f points_sum = Eigen::Vector4f::Zero(); for (const auto& point : point_cloud) { points_sum.head<3>() += point.position;