Follow googlecartographer/cartographer#801 (#657)
parent
31655ba1cb
commit
d10abbf588
|
@ -332,7 +332,8 @@ void MapBuilderBridge::OnLocalSlamResult(
|
||||||
const int trajectory_id, const ::cartographer::common::Time time,
|
const int trajectory_id, 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::NodeId>) {
|
const std::unique_ptr<const ::cartographer::mapping::
|
||||||
|
TrajectoryBuilderInterface::InsertionResult>) {
|
||||||
std::shared_ptr<const TrajectoryState::LocalSlamData> local_slam_data =
|
std::shared_ptr<const TrajectoryState::LocalSlamData> local_slam_data =
|
||||||
std::make_shared<TrajectoryState::LocalSlamData>(
|
std::make_shared<TrajectoryState::LocalSlamData>(
|
||||||
TrajectoryState::LocalSlamData{time, local_pose,
|
TrajectoryState::LocalSlamData{time, local_pose,
|
||||||
|
|
|
@ -86,8 +86,9 @@ class MapBuilderBridge {
|
||||||
const int trajectory_id, const ::cartographer::common::Time time,
|
const int trajectory_id, 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::NodeId>)
|
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_;
|
||||||
|
|
Loading…
Reference in New Issue