From d10abbf5888e42dd05cf14e7facdca3285f0575c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Sch=C3=BCtte?= Date: Wed, 10 Jan 2018 19:39:33 +0100 Subject: [PATCH] Follow googlecartographer/cartographer#801 (#657) --- cartographer_ros/cartographer_ros/map_builder_bridge.cc | 3 ++- cartographer_ros/cartographer_ros/map_builder_bridge.h | 5 +++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/cartographer_ros/cartographer_ros/map_builder_bridge.cc b/cartographer_ros/cartographer_ros/map_builder_bridge.cc index 7968065..b73fb3e 100644 --- a/cartographer_ros/cartographer_ros/map_builder_bridge.cc +++ b/cartographer_ros/cartographer_ros/map_builder_bridge.cc @@ -332,7 +332,8 @@ void MapBuilderBridge::OnLocalSlamResult( const int trajectory_id, const ::cartographer::common::Time time, const ::cartographer::transform::Rigid3d local_pose, ::cartographer::sensor::RangeData range_data_in_local, - const std::unique_ptr) { + const std::unique_ptr) { std::shared_ptr local_slam_data = std::make_shared( TrajectoryState::LocalSlamData{time, local_pose, diff --git a/cartographer_ros/cartographer_ros/map_builder_bridge.h b/cartographer_ros/cartographer_ros/map_builder_bridge.h index 13f373c..73314a8 100644 --- a/cartographer_ros/cartographer_ros/map_builder_bridge.h +++ b/cartographer_ros/cartographer_ros/map_builder_bridge.h @@ -86,8 +86,9 @@ class MapBuilderBridge { const int trajectory_id, const ::cartographer::common::Time time, const ::cartographer::transform::Rigid3d local_pose, ::cartographer::sensor::RangeData range_data_in_local, - const std::unique_ptr) - EXCLUDES(mutex_); + const std::unique_ptr + insertion_result) EXCLUDES(mutex_); cartographer::common::Mutex mutex_; const NodeOptions node_options_;