From 8d8a86790a9915884ade50d948a8f73c23925962 Mon Sep 17 00:00:00 2001 From: gaschler Date: Thu, 25 Jan 2018 14:37:16 +0100 Subject: [PATCH] Fix segfault in rosbag_validate (#685) --- cartographer_ros/cartographer_ros/rosbag_validate_main.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/cartographer_ros/cartographer_ros/rosbag_validate_main.cc b/cartographer_ros/cartographer_ros/rosbag_validate_main.cc index 572dcb6..91c4f34 100644 --- a/cartographer_ros/cartographer_ros/rosbag_validate_main.cc +++ b/cartographer_ros/cartographer_ros/rosbag_validate_main.cc @@ -173,8 +173,9 @@ class RangeDataChecker { template RangeChecksum ComputeRangeChecksum(const MessageType& message) { + auto point_cloud_with_intensities = ToPointCloudWithIntensities(message); const cartographer::sensor::TimedPointCloud& point_cloud = - std::get<0>(ToPointCloudWithIntensities(message)).points; + std::get<0>(point_cloud_with_intensities).points; Eigen::Vector4f points_sum = Eigen::Vector4f::Zero(); for (const auto& point : point_cloud) { points_sum += point;