From 4dac7c3ebe3fd6538f4d839038088c55d4413ffc Mon Sep 17 00:00:00 2001 From: gaschler Date: Mon, 4 Dec 2017 23:32:34 +0100 Subject: [PATCH] Follow googlecartographer/cartographer/pull/724. (#616) --- .../cartographer_ros/map_builder_bridge.cc | 40 +++++++++---------- .../cartographer_ros/map_builder_bridge.h | 7 ++++ 2 files changed, 26 insertions(+), 21 deletions(-) diff --git a/cartographer_ros/cartographer_ros/map_builder_bridge.cc b/cartographer_ros/cartographer_ros/map_builder_bridge.cc index ebfef81..4b6239f 100644 --- a/cartographer_ros/cartographer_ros/map_builder_bridge.cc +++ b/cartographer_ros/cartographer_ros/map_builder_bridge.cc @@ -65,26 +65,7 @@ void PushAndResetLineMarker(visualization_msgs::Marker* marker, MapBuilderBridge::MapBuilderBridge(const NodeOptions& node_options, tf2_ros::Buffer* const tf_buffer) : node_options_(node_options), - map_builder_( - node_options.map_builder_options, - cartographer::mapping::MapBuilder::LocalSlamResultCallback( - [this]( - 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_) { - std::shared_ptr - local_slam_data = - std::make_shared( - TrajectoryState::LocalSlamData{ - time, local_pose, - std::move(range_data_in_local)}); - cartographer::common::MutexLocker lock(&mutex_); - trajectory_state_data_[trajectory_id] = - std::move(local_slam_data); - })), + map_builder_(node_options.map_builder_options), tf_buffer_(tf_buffer) {} void MapBuilderBridge::LoadMap(const std::string& map_filename) { @@ -97,7 +78,11 @@ int MapBuilderBridge::AddTrajectory( const std::unordered_set& expected_sensor_ids, const TrajectoryOptions& trajectory_options) { const int trajectory_id = map_builder_.AddTrajectoryBuilder( - expected_sensor_ids, trajectory_options.trajectory_builder_options); + expected_sensor_ids, trajectory_options.trajectory_builder_options, + ::std::bind(&MapBuilderBridge::OnLocalSlamResult, this, + ::std::placeholders::_1, ::std::placeholders::_2, + ::std::placeholders::_3, ::std::placeholders::_4, + ::std::placeholders::_5)); LOG(INFO) << "Added trajectory with ID '" << trajectory_id << "'."; // Make sure there is no trajectory with 'trajectory_id' yet. @@ -338,4 +323,17 @@ SensorBridge* MapBuilderBridge::sensor_bridge(const int trajectory_id) { return sensor_bridges_.at(trajectory_id).get(); } +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) { + std::shared_ptr local_slam_data = + std::make_shared( + TrajectoryState::LocalSlamData{time, local_pose, + std::move(range_data_in_local)}); + cartographer::common::MutexLocker lock(&mutex_); + trajectory_state_data_[trajectory_id] = std::move(local_slam_data); +} + } // namespace cartographer_ros diff --git a/cartographer_ros/cartographer_ros/map_builder_bridge.h b/cartographer_ros/cartographer_ros/map_builder_bridge.h index 2f9947f..308f546 100644 --- a/cartographer_ros/cartographer_ros/map_builder_bridge.h +++ b/cartographer_ros/cartographer_ros/map_builder_bridge.h @@ -78,6 +78,13 @@ class MapBuilderBridge { SensorBridge* sensor_bridge(int trajectory_id); private: + void 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) + EXCLUDES(mutex_); + cartographer::common::Mutex mutex_; const NodeOptions node_options_; std::unordered_map>