31 #include "Eigen/Eigenvalues" 34 #include "cartographer/mapping/proto/pose_graph/constraint_builder_options.pb.h" 37 #include "glog/logging.h" 43 const proto::PoseGraphOptions& options,
44 std::unique_ptr<optimization::OptimizationProblem2D> optimization_problem,
53 CHECK(work_queue_ ==
nullptr);
58 const std::vector<std::shared_ptr<const Submap2D>>& insertion_submaps) {
59 CHECK(!insertion_submaps.empty());
61 if (insertion_submaps.size() == 1) {
63 if (submap_data.SizeOfTrajectoryOrZero(trajectory_id) == 0) {
64 if (initial_trajectory_poses_.count(trajectory_id) > 0) {
67 initial_trajectory_poses_.at(trajectory_id).to_trajectory_id,
time);
72 global_submap_poses_, trajectory_id) *
73 insertion_submaps[0]->local_pose()));
75 CHECK_EQ(1, submap_data.SizeOfTrajectoryOrZero(trajectory_id));
76 const SubmapId submap_id{trajectory_id, 0};
77 CHECK(submap_data_.at(submap_id).submap == insertion_submaps.front());
80 CHECK_EQ(2, insertion_submaps.size());
81 const auto end_it = submap_data.EndOfTrajectory(trajectory_id);
82 CHECK(submap_data.BeginOfTrajectory(trajectory_id) != end_it);
83 const SubmapId last_submap_id = std::prev(end_it)->id;
84 if (submap_data_.at(last_submap_id).submap == insertion_submaps.front()) {
87 const auto& first_submap_pose = submap_data.at(last_submap_id).global_pose;
93 return {last_submap_id,
96 CHECK(submap_data_.at(last_submap_id).submap == insertion_submaps.back());
97 const SubmapId front_submap_id{trajectory_id,
99 CHECK(submap_data_.at(front_submap_id).submap == insertion_submaps.front());
100 return {front_submap_id, last_submap_id};
104 std::shared_ptr<const TrajectoryNode::Data> constant_data,
105 const int trajectory_id,
106 const std::vector<std::shared_ptr<const Submap2D>>& insertion_submaps) {
112 const NodeId node_id = trajectory_nodes_.Append(
114 ++num_trajectory_nodes_;
117 if (submap_data_.SizeOfTrajectoryOrZero(trajectory_id) == 0 ||
118 std::prev(submap_data_.EndOfTrajectory(trajectory_id))->data.submap !=
119 insertion_submaps.back()) {
124 submap_data_.at(submap_id).submap = insertion_submaps.back();
129 const bool newly_finished_submap = insertion_submaps.front()->finished();
132 newly_finished_submap);
138 if (work_queue_ ==
nullptr) {
141 work_queue_->push_back(work_item);
148 if (!global_localization_samplers_[trajectory_id]) {
149 global_localization_samplers_[trajectory_id] =
150 common::make_unique<common::FixedRatioSampler>(
172 const int trajectory_id,
174 LOG(FATAL) <<
"Not yet implemented for 2D.";
182 for (
const auto& observation : landmark_data.landmark_observations) {
183 landmark_nodes_[observation.id].landmark_observations.emplace_back(
184 LandmarkNode::LandmarkObservation{
185 trajectory_id, landmark_data.time,
186 observation.landmark_to_tracking_transform,
187 observation.translation_weight, observation.rotation_weight});
202 last_connection_time +
204 options_.global_constraint_search_after_n_seconds())) {
212 .global_pose.inverse() *
215 submap_id, submap_data_.at(submap_id).submap.get(), node_id,
216 trajectory_nodes_.at(node_id).constant_data.get(),
217 initial_relative_pose);
218 }
else if (global_localization_samplers_[node_id.
trajectory_id]->Pulse()) {
220 submap_id, submap_data_.at(submap_id).submap.get(), node_id,
221 trajectory_nodes_.at(node_id).constant_data.get());
226 const auto& submap_data = submap_data_.at(submap_id);
228 const NodeId& node_id = node_id_data.id;
229 if (submap_data.node_ids.count(node_id) == 0) {
237 std::vector<std::shared_ptr<const Submap2D>> insertion_submaps,
238 const bool newly_finished_submap) {
239 const auto& constant_data = trajectory_nodes_.at(node_id).constant_data;
241 node_id.
trajectory_id, constant_data->time, insertion_submaps);
242 CHECK_EQ(submap_ids.size(), insertion_submaps.size());
243 const SubmapId matching_id = submap_ids.front();
245 constant_data->local_pose *
252 matching_id.trajectory_id,
255 constant_data->gravity_alignment});
256 for (
size_t i = 0; i < insertion_submaps.size(); ++i) {
257 const SubmapId submap_id = submap_ids[i];
261 submap_data_.at(submap_id).node_ids.emplace(node_id);
268 options_.matcher_translation_weight(),
269 options_.matcher_rotation_weight()},
273 for (
const auto& submap_id_data : submap_data_) {
275 CHECK_EQ(submap_id_data.data.node_ids.count(node_id), 0);
280 if (newly_finished_submap) {
281 const SubmapId finished_submap_id = submap_ids.front();
283 submap_data_.at(finished_submap_id);
291 ++num_nodes_since_last_loop_closure_;
292 CHECK(!run_loop_closure_);
293 if (
options_.optimize_every_n_nodes() > 0 &&
294 num_nodes_since_last_loop_closure_ >
options_.optimize_every_n_nodes()) {
300 run_loop_closure_ =
true;
302 if (work_queue_ ==
nullptr) {
303 work_queue_ = common::make_unique<std::deque<std::function<void()>>>();
312 if (!submap_data.
node_ids.empty()) {
313 const NodeId last_submap_node_id =
314 *submap_data_.at(submap_id).node_ids.rbegin();
316 time, trajectory_nodes_.at(last_submap_node_id).constant_data->time);
334 constraints_.insert(constraints_.end(), result.begin(), result.end());
339 std::map<int, NodeId> trajectory_id_to_last_optimized_node_id;
340 std::map<int, SubmapId> trajectory_id_to_last_optimized_submap_id;
345 for (
const int trajectory_id : node_data.trajectory_ids()) {
346 trajectory_id_to_last_optimized_node_id[trajectory_id] =
347 std::prev(node_data.EndOfTrajectory(trajectory_id))->
id;
348 trajectory_id_to_last_optimized_submap_id[trajectory_id] =
349 std::prev(submap_data.EndOfTrajectory(trajectory_id))->
id;
353 trajectory_id_to_last_optimized_submap_id,
354 trajectory_id_to_last_optimized_node_id);
362 for (
auto& trimmer : trimmers_) {
363 trimmer->Trim(&trimming_handle);
366 std::remove_if(trimmers_.begin(), trimmers_.end(),
367 [](std::unique_ptr<PoseGraphTrimmer>& trimmer) {
368 return trimmer->IsFinished();
372 num_nodes_since_last_loop_closure_ = 0;
373 run_loop_closure_ =
false;
374 while (!run_loop_closure_) {
375 if (work_queue_->empty()) {
379 work_queue_->front()();
380 work_queue_->pop_front();
382 LOG(INFO) <<
"Remaining work items in queue: " << work_queue_->size();
389 bool notification =
false;
391 const int num_finished_nodes_at_start =
393 while (!locker.AwaitWithTimeout(
396 num_trajectory_nodes_) &&
400 std::ostringstream progress_info;
401 progress_info <<
"Optimizing: " << std::fixed << std::setprecision(1)
404 num_finished_nodes_at_start) /
405 (num_trajectory_nodes_ - num_finished_nodes_at_start)
407 std::cout <<
"\r\x1b[K" << progress_info.str() << std::flush;
409 std::cout <<
"\r\x1b[KOptimizing: Done. " << std::endl;
414 constraints_.insert(constraints_.end(), result.begin(), result.end());
417 locker.Await([¬ification]() {
return notification; });
423 CHECK_EQ(finished_trajectories_.count(trajectory_id), 0);
424 finished_trajectories_.insert(trajectory_id);
426 for (
const auto& submap : submap_data_.trajectory(trajectory_id)) {
429 CHECK(!run_loop_closure_);
435 return finished_trajectories_.count(trajectory_id) > 0;
442 CHECK_EQ(frozen_trajectories_.count(trajectory_id), 0);
443 frozen_trajectories_.insert(trajectory_id);
448 return frozen_trajectories_.count(trajectory_id) > 0;
453 if (!submap.has_submap_2d()) {
458 submap.submap_id().submap_index()};
459 std::shared_ptr<const Submap2D> submap_ptr =
460 std::make_shared<const Submap2D>(submap.submap_2d());
467 submap_data_.at(submap_id).submap = submap_ptr;
469 global_submap_poses_.Insert(
478 const proto::Node& node) {
480 node.node_id().node_index()};
481 std::shared_ptr<const TrajectoryNode::Data> constant_data =
482 std::make_shared<const TrajectoryNode::Data>(
FromProto(node.node_data()));
486 trajectory_nodes_.Insert(node_id,
TrajectoryNode{constant_data, global_pose});
489 const auto& constant_data = trajectory_nodes_.at(node_id).constant_data;
491 constant_data->gravity_alignment.inverse());
497 gravity_alignment_inverse),
499 constant_data->gravity_alignment});
504 const proto::TrajectoryData& data) {
505 LOG(ERROR) <<
"not implemented";
512 submap_data_.at(submap_id).node_ids.insert(node_id);
520 for (
const auto& constraint : constraints) {
521 CHECK(trajectory_nodes_.Contains(constraint.node_id));
522 CHECK(submap_data_.Contains(constraint.submap_id));
523 CHECK(trajectory_nodes_.at(constraint.node_id).constant_data !=
nullptr);
524 CHECK(submap_data_.at(constraint.submap_id).submap !=
nullptr);
525 switch (constraint.tag) {
526 case Constraint::Tag::INTRA_SUBMAP:
527 CHECK(submap_data_.at(constraint.submap_id)
528 .node_ids.emplace(constraint.node_id)
531 case Constraint::Tag::INTER_SUBMAP:
535 const Constraint::Pose
pose = {
536 constraint.pose.zbar_ij *
538 trajectory_nodes_.at(constraint.node_id)
539 .constant_data->gravity_alignment.inverse()),
540 constraint.pose.translation_weight, constraint.pose.rotation_weight};
542 constraint.
submap_id, constraint.node_id,
pose, constraint.tag});
544 LOG(INFO) <<
"Loaded " << constraints.size() <<
" constraints.";
561 options_.max_num_final_iterations());
566 options_.optimization_problem_options()
567 .ceres_solver_options()
568 .max_num_iterations());
589 for (
const int trajectory_id : node_data.trajectory_ids()) {
590 for (
const auto& node : node_data.trajectory(trajectory_id)) {
591 auto& mutable_trajectory_node = trajectory_nodes_.at(node.id);
592 mutable_trajectory_node.global_pose =
595 mutable_trajectory_node.constant_data->gravity_alignment);
600 const auto local_to_new_global =
602 const auto local_to_old_global =
605 local_to_new_global * local_to_old_global.
inverse();
607 const NodeId last_optimized_node_id =
608 std::prev(node_data.EndOfTrajectory(trajectory_id))->
id;
609 auto node_it = std::next(trajectory_nodes_.find(last_optimized_node_id));
610 for (; node_it != trajectory_nodes_.EndOfTrajectory(trajectory_id);
612 auto& mutable_trajectory_node = trajectory_nodes_.at(node_it->id);
613 mutable_trajectory_node.global_pose =
614 old_global_to_new_global * mutable_trajectory_node.global_pose;
618 landmark_nodes_[landmark.first].global_landmark_pose = landmark.second;
620 global_submap_poses_ = submap_data;
625 return trajectory_nodes_;
632 for (
const auto& node_id_data : trajectory_nodes_) {
634 if (node_id_data.data.constant_data !=
nullptr) {
636 node_id_data.data.constant_data->
time,
637 node_id_data.data.constant_data->local_pose};
648 std::map<std::string, transform::Rigid3d> landmark_poses;
650 for (
const auto& landmark : landmark_nodes_) {
652 if (!landmark.second.global_landmark_pose.has_value())
continue;
653 landmark_poses[landmark.first] =
654 landmark.second.global_landmark_pose.value();
656 return landmark_poses;
663 landmark_nodes_[landmark_id].global_landmark_pose = global_pose;
680 return landmark_nodes_;
683 std::map<int, PoseGraphInterface::TrajectoryData>
694 std::vector<PoseGraphInterface::Constraint> result;
696 for (
const Constraint& constraint : constraints_) {
698 constraint.
submap_id, constraint.node_id,
699 Constraint::Pose{constraint.pose.zbar_ij *
701 trajectory_nodes_.at(constraint.node_id)
702 .constant_data->gravity_alignment),
703 constraint.pose.translation_weight,
704 constraint.pose.rotation_weight},
711 const int to_trajectory_id,
715 initial_trajectory_poses_[from_trajectory_id] =
721 CHECK_GT(trajectory_nodes_.SizeOfTrajectoryOrZero(trajectory_id), 0);
722 const auto it = trajectory_nodes_.lower_bound(trajectory_id, time);
723 if (it == trajectory_nodes_.BeginOfTrajectory(trajectory_id)) {
724 return trajectory_nodes_.BeginOfTrajectory(trajectory_id)->data.global_pose;
726 if (it == trajectory_nodes_.EndOfTrajectory(trajectory_id)) {
727 return std::prev(trajectory_nodes_.EndOfTrajectory(trajectory_id))
732 std::prev(it)->data.global_pose},
734 it->data.global_pose},
740 const int trajectory_id)
const {
765 for (
const auto& submap_id_data : submap_data_) {
777 const int trajectory_id)
const {
780 if (begin_it == end_it) {
781 const auto it = initial_trajectory_poses_.find(trajectory_id);
782 if (it != initial_trajectory_poses_.end()) {
785 it->second.relative_pose;
790 const SubmapId last_optimized_submap_id = std::prev(end_it)->id;
793 global_submap_poses.
at(last_optimized_submap_id).global_pose) *
794 submap_data_.at(last_optimized_submap_id)
795 .submap->local_pose()
801 const auto it = submap_data_.find(submap_id);
802 if (it == submap_data_.end()) {
805 auto submap = it->data.submap;
806 if (global_submap_poses_.Contains(submap_id)) {
814 submap->local_pose()};
822 return submap_data.SizeOfTrajectoryOrZero(trajectory_id);
828 for (
const auto& submap_id_data :
parent_->submap_data_) {
830 !
parent_->global_submap_poses_.Contains(submap_id_data.id)) {
833 submaps.
Insert(submap_id_data.id,
835 transform::Embed3D(parent_->global_submap_poses_
836 .at(submap_id_data.id)
843 int trajectory_id)
const {
844 std::vector<SubmapId> submap_ids;
846 for (
const auto& it : submap_data.trajectory(trajectory_id)) {
847 submap_ids.push_back(it.id);
854 return parent_->trajectory_nodes_;
857 const std::vector<PoseGraphInterface::Constraint>&
874 std::set<NodeId> nodes_to_retain;
876 if (constraint.
tag == Constraint::Tag::INTRA_SUBMAP &&
878 nodes_to_retain.insert(constraint.
node_id);
882 std::set<NodeId> nodes_to_remove;
887 if (constraint.
tag == Constraint::Tag::INTRA_SUBMAP &&
888 nodes_to_retain.count(constraint.
node_id) == 0) {
891 nodes_to_remove.insert(constraint.
node_id);
894 constraints.push_back(constraint);
897 parent_->constraints_ = std::move(constraints);
903 if (nodes_to_remove.count(constraint.
node_id) == 0) {
904 constraints.push_back(constraint);
907 parent_->constraints_ = std::move(constraints);
912 parent_->submap_data_.Trim(submap_id);
913 parent_->constraint_builder_.DeleteScanMatcher(submap_id);
918 for (
const NodeId& node_id : nodes_to_remove) {
919 parent_->trajectory_nodes_.Trim(node_id);
927 for (
const auto& submap_id_data : submap_data_) {
928 submaps.
Insert(submap_id_data.id,
bool IsFinished(int trajectory_id) const override REQUIRES(parent_ -> mutex_)
MapById< NodeId, TrajectoryNodePose > GetTrajectoryNodePoses() const override EXCLUDES(mutex_)
PoseGraph::Constraint::Tag FromProto(const proto::PoseGraph::Constraint::Tag &proto)
common::Time GetLatestNodeTime(const NodeId &node_id, const SubmapId &submap_id) const REQUIRES(mutex_)
TrajectoryConnectivityState trajectory_connectivity_state_
void FreezeTrajectory(int trajectory_id) override
std::unique_ptr< optimization::OptimizationProblem2D > optimization_problem_
PoseGraph2D(const proto::PoseGraphOptions &options, std::unique_ptr< optimization::OptimizationProblem2D > optimization_problem, common::ThreadPool *thread_pool)
transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) const EXCLUDES(mutex_) override
std::vector< Constraint > Result
const std::vector< Constraint > & GetConstraints() const override REQUIRES(parent_ -> mutex_)
std::unique_ptr< ConstraintBuilder2D > constraint_builder_
void Connect(int trajectory_id_a, int trajectory_id_b, common::Time time)
enum cartographer::mapping::PoseGraphInterface::Constraint::Tag tag
void AddNodeFromProto(const transform::Rigid3d &global_pose, const proto::Node &node) override
void AddTrimmer(std::unique_ptr< PoseGraphTrimmer > trimmer) override
MapById< SubmapId, SubmapData > GetOptimizedSubmapData() const override REQUIRES(parent_ -> mutex_)
const DataType & at(const IdType &id) const
void ComputeConstraint(const NodeId &node_id, const SubmapId &submap_id) REQUIRES(mutex_)
void AddNodeToSubmap(const NodeId &node_id, const SubmapId &submap_id) override
void MarkSubmapAsTrimmed(const SubmapId &submap_id) REQUIRES(parent_ -> mutex_) override
std::function< void(const std::map< int, SubmapId > &, const std::map< int, NodeId > &)> GlobalSlamOptimizationCallback
void Insert(const IdType &id, const DataType &data)
MapById< SubmapId, PoseGraphInterface::SubmapData > GetSubmapDataUnderLock() const REQUIRES(mutex_)
void AddSerializedConstraints(const std::vector< Constraint > &constraints) override
std::vector< Constraint > constraints() const override EXCLUDES(mutex_)
const proto::PoseGraphOptions options_
UniversalTimeScaleClock::time_point Time
sensor::MapByTime< sensor::OdometryData > GetOdometryData() const override EXCLUDES(mutex_)
void WaitForAllComputations() EXCLUDES(mutex_)
TrimmingHandle(PoseGraph2D *parent)
void AddLandmarkData(int trajectory_id, const sensor::LandmarkData &landmark_data) override EXCLUDES(mutex_)
sensor::MapByTime< sensor::FixedFramePoseData > GetFixedFramePoseData() const override EXCLUDES(mutex_)
bool IsTrajectoryFinished(int trajectory_id) const override REQUIRES(mutex_)
ConstIterator EndOfTrajectory(const int trajectory_id) const
PoseGraph2D *const parent_
std::vector< SubmapId > InitializeGlobalSubmapPoses(int trajectory_id, const common::Time time, const std::vector< std::shared_ptr< const Submap2D >> &insertion_submaps) REQUIRES(mutex_)
void RunFinalOptimization() override
Duration FromSeconds(const double seconds)
MapById< SubmapId, SubmapPose > GetAllSubmapPoses() const EXCLUDES(mutex_) override
void AddFixedFramePoseData(int trajectory_id, const sensor::FixedFramePoseData &fixed_frame_pose_data) override EXCLUDES(mutex_)
bool IsTrajectoryFrozen(int trajectory_id) const override REQUIRES(mutex_)
common::Time LastConnectionTime(int trajectory_id_a, int trajectory_id_b)
const MapById< NodeId, TrajectoryNode > & GetTrajectoryNodes() const override REQUIRES(parent_ -> mutex_)
sensor::MapByTime< sensor::ImuData > GetImuData() const override EXCLUDES(mutex_)
OptimizationProblem3D optimization_problem_
void Add(int trajectory_id)
MapById< SubmapId, PoseGraphInterface::SubmapData > GetAllSubmapData() const EXCLUDES(mutex_) override
proto::ProbabilityGridRangeDataInserterOptions2D options_
MapById< NodeId, TrajectoryNode > GetTrajectoryNodes() const override EXCLUDES(mutex_)
transform::Rigid2d ComputeSubmapPose(const Submap2D &submap)
transform::Rigid3d GetInterpolatedGlobalTrajectoryPose(int trajectory_id, const common::Time time) const REQUIRES(mutex_)
void SetTrajectoryDataFromProto(const proto::TrajectoryData &data) override
void ComputeConstraintsForNode(const NodeId &node_id, std::vector< std::shared_ptr< const Submap2D >> insertion_submaps, bool newly_finished_submap) REQUIRES(mutex_)
void ComputeConstraintsForOldNodes(const SubmapId &submap_id) REQUIRES(mutex_)
void AddSubmapFromProto(const transform::Rigid3d &global_submap_pose, const proto::Submap &submap) override
void SetGlobalSlamOptimizationCallback(PoseGraphInterface::GlobalSlamOptimizationCallback callback) override
std::map< std::string, PoseGraph::LandmarkNode > GetLandmarkNodes() const override EXCLUDES(mutex_)
void AddTrajectoryIfNeeded(int trajectory_id) REQUIRES(mutex_)
GlobalSlamOptimizationCallback global_slam_optimization_callback_
void AddImuData(int trajectory_id, const sensor::ImuData &imu_data) override EXCLUDES(mutex_)
NodeId AddNode(std::shared_ptr< const TrajectoryNode::Data > constant_data, int trajectory_id, const std::vector< std::shared_ptr< const Submap2D >> &insertion_submaps) EXCLUDES(mutex_)
void DispatchOptimization() REQUIRES(mutex_)
std::vector< std::vector< int > > GetConnectedTrajectories() const override
void RunOptimization() EXCLUDES(mutex_)
std::set< NodeId > node_ids
void AddOdometryData(int trajectory_id, const sensor::OdometryData &odometry_data) override EXCLUDES(mutex_)
void SetInitialTrajectoryPose(int from_trajectory_id, int to_trajectory_id, const transform::Rigid3d &pose, const common::Time time) override EXCLUDES(mutex_)
void UpdateTrajectoryConnectivity(const Constraint &constraint) REQUIRES(mutex_)
void SetLandmarkPose(const std::string &landmark_id, const transform::Rigid3d &global_pose) override EXCLUDES(mutex_)
transform::Rigid3d ComputeLocalToGlobalTransform(const MapById< SubmapId, optimization::SubmapSpec2D > &global_submap_poses, int trajectory_id) const REQUIRES(mutex_)
Mutex::Locker MutexLocker
ConstIterator BeginOfTrajectory(const int trajectory_id) const
void AddWorkItem(const std::function< void()> &work_item) REQUIRES(mutex_)
std::map< std::string, transform::Rigid3d > GetLandmarkPoses() const override EXCLUDES(mutex_)
void HandleWorkQueue(const constraints::ConstraintBuilder2D::Result &result) REQUIRES(mutex_)
PoseGraphInterface::SubmapData GetSubmapData(const SubmapId &submap_id) const EXCLUDES(mutex_) override
std::vector< std::vector< int > > Components() const
std::map< int, TrajectoryData > GetTrajectoryData() const override EXCLUDES(mutex_)
std::vector< SubmapId > GetSubmapIds(int trajectory_id) const override
void FinishTrajectory(int trajectory_id) override
int num_submaps(int trajectory_id) const override