Get rid of std::bind. (#939)

`std::bind` is bug prone and should be avoided.
Lambdas are a more general and safer replacement.
Similar to googlecartographer/cartographer#1261.
master
Wolfgang Hess 2018-07-14 11:57:36 +02:00 committed by Wally B. Feed
parent a90e9952d8
commit b9af6366db
2 changed files with 14 additions and 14 deletions

View File

@ -123,10 +123,14 @@ int MapBuilderBridge::AddTrajectory(
const TrajectoryOptions& trajectory_options) { const TrajectoryOptions& trajectory_options) {
const int trajectory_id = map_builder_->AddTrajectoryBuilder( 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, [this](const int trajectory_id, const ::cartographer::common::Time time,
::std::placeholders::_1, ::std::placeholders::_2, const Rigid3d local_pose,
::std::placeholders::_3, ::std::placeholders::_4, ::cartographer::sensor::RangeData range_data_in_local,
::std::placeholders::_5)); const std::unique_ptr<
const ::cartographer::mapping::TrajectoryBuilderInterface::
InsertionResult>) {
OnLocalSlamResult(trajectory_id, time, local_pose, range_data_in_local);
});
LOG(INFO) << "Added trajectory with ID '" << trajectory_id << "'."; LOG(INFO) << "Added trajectory with ID '" << trajectory_id << "'.";
// Make sure there is no trajectory with 'trajectory_id' yet. // Make sure there is no trajectory with 'trajectory_id' yet.
@ -490,9 +494,7 @@ SensorBridge* MapBuilderBridge::sensor_bridge(const int trajectory_id) {
void MapBuilderBridge::OnLocalSlamResult( void MapBuilderBridge::OnLocalSlamResult(
const int trajectory_id, const ::cartographer::common::Time time, const int trajectory_id, const ::cartographer::common::Time time,
const Rigid3d local_pose, const Rigid3d local_pose,
::cartographer::sensor::RangeData range_data_in_local, ::cartographer::sensor::RangeData range_data_in_local) {
const std::unique_ptr<const ::cartographer::mapping::
TrajectoryBuilderInterface::InsertionResult>) {
std::shared_ptr<const LocalTrajectoryData::LocalSlamData> local_slam_data = std::shared_ptr<const LocalTrajectoryData::LocalSlamData> local_slam_data =
std::make_shared<LocalTrajectoryData::LocalSlamData>( std::make_shared<LocalTrajectoryData::LocalSlamData>(
LocalTrajectoryData::LocalSlamData{time, local_pose, LocalTrajectoryData::LocalSlamData{time, local_pose,

View File

@ -91,13 +91,11 @@ class MapBuilderBridge {
SensorBridge* sensor_bridge(int trajectory_id); SensorBridge* sensor_bridge(int trajectory_id);
private: private:
void OnLocalSlamResult( void OnLocalSlamResult(const int trajectory_id,
const int trajectory_id, const ::cartographer::common::Time time, const ::cartographer::common::Time time,
const ::cartographer::transform::Rigid3d local_pose, const ::cartographer::transform::Rigid3d local_pose,
::cartographer::sensor::RangeData range_data_in_local, ::cartographer::sensor::RangeData range_data_in_local)
const std::unique_ptr<const ::cartographer::mapping:: EXCLUDES(mutex_);
TrajectoryBuilderInterface::InsertionResult>
insertion_result) EXCLUDES(mutex_);
cartographer::common::Mutex mutex_; cartographer::common::Mutex mutex_;
const NodeOptions node_options_; const NodeOptions node_options_;