From fb947f5c7e91dbf925e2ebd16e7d37e9f6a4e4d4 Mon Sep 17 00:00:00 2001 From: gaschler Date: Mon, 19 Feb 2018 14:40:13 +0100 Subject: [PATCH] Avoid auto for Eigen expressiongs. (#719) While harmless in most cases, auto can delay evaluation of expressions in unexpected ways. So it is better to avoid auto for Eigen expressions. https://eigen.tuxfamily.org/dox/TopicPitfalls.html --- cartographer_ros/cartographer_ros/msg_conversion.cc | 4 ++-- cartographer_ros/cartographer_ros/rosbag_validate_main.cc | 2 +- cartographer_ros/cartographer_ros/sensor_bridge.cc | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/cartographer_ros/cartographer_ros/msg_conversion.cc b/cartographer_ros/cartographer_ros/msg_conversion.cc index 22b183a..448c4aa 100644 --- a/cartographer_ros/cartographer_ros/msg_conversion.cc +++ b/cartographer_ros/cartographer_ros/msg_conversion.cc @@ -133,7 +133,7 @@ LaserScanToPointCloudWithIntensities(const LaserMessageType& msg) { if (!point_cloud.points.empty()) { const double duration = point_cloud.points.back()[3]; timestamp += cartographer::common::FromSeconds(duration); - for (auto& point : point_cloud.points) { + for (Eigen::Vector4f& point : point_cloud.points) { point[3] -= duration; } } @@ -157,7 +157,7 @@ sensor_msgs::PointCloud2 ToPointCloud2Message( const ::cartographer::sensor::TimedPointCloud& point_cloud) { auto msg = PreparePointCloud2Message(timestamp, frame_id, point_cloud.size()); ::ros::serialization::OStream stream(msg.data.data(), msg.data.size()); - for (const auto& point : point_cloud) { + for (const Eigen::Vector4f& point : point_cloud) { stream.next(point.x()); stream.next(point.y()); stream.next(point.z()); diff --git a/cartographer_ros/cartographer_ros/rosbag_validate_main.cc b/cartographer_ros/cartographer_ros/rosbag_validate_main.cc index 91c4f34..627b661 100644 --- a/cartographer_ros/cartographer_ros/rosbag_validate_main.cc +++ b/cartographer_ros/cartographer_ros/rosbag_validate_main.cc @@ -177,7 +177,7 @@ class RangeDataChecker { const cartographer::sensor::TimedPointCloud& point_cloud = std::get<0>(point_cloud_with_intensities).points; Eigen::Vector4f points_sum = Eigen::Vector4f::Zero(); - for (const auto& point : point_cloud) { + for (const Eigen::Vector4f& point : point_cloud) { points_sum += point; } return {point_cloud.size(), points_sum}; diff --git a/cartographer_ros/cartographer_ros/sensor_bridge.cc b/cartographer_ros/cartographer_ros/sensor_bridge.cc index ad10674..204a829 100644 --- a/cartographer_ros/cartographer_ros/sensor_bridge.cc +++ b/cartographer_ros/cartographer_ros/sensor_bridge.cc @@ -192,7 +192,7 @@ void SensorBridge::HandleLaserScan( // send all other sensor data first. const carto::common::Time subdivision_time = time + carto::common::FromSeconds(time_to_subdivision_end); - for (auto& point : subdivision) { + for (Eigen::Vector4f& point : subdivision) { point[3] -= time_to_subdivision_end; } CHECK_EQ(subdivision.back()[3], 0);