Fix segfault in rosbag_validate (#685)

master
gaschler 2018-01-25 14:37:16 +01:00 committed by Wally B. Feed
parent 7cf570d19e
commit 8d8a86790a
1 changed files with 2 additions and 1 deletions

View File

@ -173,8 +173,9 @@ class RangeDataChecker {
template <typename MessageType> template <typename MessageType>
RangeChecksum ComputeRangeChecksum(const MessageType& message) { RangeChecksum ComputeRangeChecksum(const MessageType& message) {
auto point_cloud_with_intensities = ToPointCloudWithIntensities(message);
const cartographer::sensor::TimedPointCloud& point_cloud = 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(); Eigen::Vector4f points_sum = Eigen::Vector4f::Zero();
for (const auto& point : point_cloud) { for (const auto& point : point_cloud) {
points_sum += point; points_sum += point;