PoseGraph位姿图
mapping2D::PoseGraph类的注释:
// Implements the loop closure method called Sparse Pose Adjustment (SPA) from |
1.继承关系mapping,mapping2D,mapping3D (以前叫sparse_pose_graph.h,目前名称被修改了)
类中一个很重要的类OptimizationProblem对象optimization_problem_,该类的注释是Implements the SPA loop closure method.即实现了SPA方法的闭环。
类的主要成员变量和成员函数如类图所示,其中重要的方法PoseGraph::RunOptimization()。
pose_graph::OptimizationProblem optimization_problem_;
pose_graph::ConstraintBuilder constraint_builder_ GUARDED_BY(mutex_);
std::vector<Constraint> constraints_ GUARDED_BY(mutex_);
接上一篇在PoseGraph::AddNode方法中调用了 AddTrajectoryIfNeeded() 和 PoseGraph::ComputeConstraintsForNode()方法。
void PoseGraph::ComputeConstraintsForNode(
const mapping::NodeId& node_id,
std::vector<std::shared_ptr<const Submap>> insertion_submaps,
const bool newly_finished_submap) {
const auto& constant_data = trajectory_nodes_.at(node_id).constant_data;
const std::vector<mapping::SubmapId> submap_ids = InitializeGlobalSubmapPoses(
node_id.trajectory_id, constant_data->time, insertion_submaps);
CHECK_EQ(submap_ids.size(), insertion_submaps.size());
const mapping::SubmapId matching_id = submap_ids.front();
const transform::Rigid2d pose = transform::Project2D(
constant_data->local_pose *
transform::Rigid3d::Rotation(constant_data->gravity_alignment.inverse()));
const transform::Rigid2d optimized_pose =
optimization_problem_.submap_data().at(matching_id).global_pose *
pose_graph::ComputeSubmapPose(*insertion_submaps.front()).inverse() *
pose;
optimization_problem_.AddTrajectoryNode(
matching_id.trajectory_id, constant_data->time, pose, optimized_pose,
constant_data->gravity_alignment);
for (size_t i = ; i < insertion_submaps.size(); ++i) {
const mapping::SubmapId submap_id = submap_ids[i];
// Even if this was the last node added to 'submap_id', the submap will only
// be marked as finished in 'submap_data_' further below.
CHECK(submap_data_.at(submap_id).state == SubmapState::kActive);
submap_data_.at(submap_id).node_ids.emplace(node_id);
const transform::Rigid2d constraint_transform =
pose_graph::ComputeSubmapPose(*insertion_submaps[i]).inverse() * pose;
constraints_.push_back(Constraint{submap_id,
node_id,
{transform::Embed3D(constraint_transform),
options_.matcher_translation_weight(),
options_.matcher_rotation_weight()},
Constraint::INTRA_SUBMAP});
} for (const auto& submap_id_data : submap_data_) {
if (submap_id_data.data.state == SubmapState::kFinished) {
CHECK_EQ(submap_id_data.data.node_ids.count(node_id), );
ComputeConstraint(node_id, submap_id_data.id);
}
} if (newly_finished_submap) {
const mapping::SubmapId finished_submap_id = submap_ids.front();
SubmapData& finished_submap_data = submap_data_.at(finished_submap_id);
CHECK(finished_submap_data.state == SubmapState::kActive);
finished_submap_data.state = SubmapState::kFinished;
// We have a new completed submap, so we look into adding constraints for
// old nodes.
ComputeConstraintsForOldNodes(finished_submap_id);
}
constraint_builder_.NotifyEndOfNode();
++num_nodes_since_last_loop_closure_;
if (options_.optimize_every_n_nodes() > &&
num_nodes_since_last_loop_closure_ > options_.optimize_every_n_nodes()) {
CHECK(!run_loop_closure_);
run_loop_closure_ = true;
// If there is a 'work_queue_' already, some other thread will take care.
if (work_queue_ == nullptr) {
work_queue_ = common::make_unique<std::deque<std::function<void()>>>();
HandleWorkQueue();
}
}
}
可以看到对本类中ComputeConstraint、ComputeConstraintsForOldNodes、HandleWorkQueue方法的调用。这里有个pose_graph::ComputeSubmapPose方法在cartographer/mapping_2d/pose_graph/constraint_builder.h文件中。子图submap位姿?
transform::Rigid2d ComputeSubmapPose(const Submap& submap)
{
return transform::Project2D(submap.local_pose());
}
注意HandleWorkQueue()方法中调用了RunOptimization方法。
void PoseGraph::HandleWorkQueue() {
constraint_builder_.WhenDone(
[this](const pose_graph::ConstraintBuilder::Result& result) {
{
common::MutexLocker locker(&mutex_);
constraints_.insert(constraints_.end(), result.begin(), result.end());
}
RunOptimization(); common::MutexLocker locker(&mutex_);
for (const Constraint& constraint : result) {
UpdateTrajectoryConnectivity(constraint);
}
TrimmingHandle trimming_handle(this);
for (auto& trimmer : trimmers_) {
trimmer->Trim(&trimming_handle);
}
trimmers_.erase(
std::remove_if(
trimmers_.begin(), trimmers_.end(),
[](std::unique_ptr<mapping::PoseGraphTrimmer>& trimmer) {
return trimmer->IsFinished();
}),
trimmers_.end()); num_nodes_since_last_loop_closure_ = ;
run_loop_closure_ = false;
while (!run_loop_closure_) {
if (work_queue_->empty()) {
work_queue_.reset();
return;
}
work_queue_->front()();
work_queue_->pop_front();
}
LOG(INFO) << "Remaining work items in queue: " << work_queue_->size();
// We have to optimize again.
HandleWorkQueue();
});
}
PoseGraph::HandleWorkQueue
查看PoseGraph::RunOptimization方法,
void PoseGraph::RunOptimization()
{
if (optimization_problem_.submap_data().empty())
{
return;
} // No other thread is accessing the optimization_problem_, constraints_ and
// frozen_trajectories_ when executing the Solve. Solve is time consuming, so
// not taking the mutex before Solve to avoid blocking foreground processing.
optimization_problem_.Solve(constraints_, frozen_trajectories_);
common::MutexLocker locker(&mutex_); const auto& submap_data = optimization_problem_.submap_data();
const auto& node_data = optimization_problem_.node_data();
for (const int trajectory_id : node_data.trajectory_ids())
{
for (const auto& node : node_data.trajectory(trajectory_id))
{
auto& mutable_trajectory_node = trajectory_nodes_.at(node.id);
mutable_trajectory_node.global_pose =
transform::Embed3D(node.data.pose) *
transform::Rigid3d::Rotation(mutable_trajectory_node.constant_data->gravity_alignment);
} // Extrapolate all point cloud poses that were not included in the
// 'optimization_problem_' yet.
const auto local_to_new_global =
ComputeLocalToGlobalTransform(submap_data, trajectory_id);
const auto local_to_old_global =
ComputeLocalToGlobalTransform(global_submap_poses_, trajectory_id);
const transform::Rigid3d old_global_to_new_global =
local_to_new_global * local_to_old_global.inverse(); const mapping::NodeId last_optimized_node_id =
std::prev(node_data.EndOfTrajectory(trajectory_id))->id;
auto node_it = std::next(trajectory_nodes_.find(last_optimized_node_id));
for (; node_it != trajectory_nodes_.EndOfTrajectory(trajectory_id); ++node_it)
{
auto& mutable_trajectory_node = trajectory_nodes_.at(node_it->id);
mutable_trajectory_node.global_pose =
old_global_to_new_global * mutable_trajectory_node.global_pose;
}
}
global_submap_poses_ = submap_data;
}
查看Constraint 结构体,该结构体在PoseGraphInterface中定义。
// A "constraint" as in the paper by Konolige, Kurt, et al. "Efficient sparse
// pose adjustment for 2d mapping." Intelligent Robots and Systems (IROS),
// 2010 IEEE/RSJ International Conference on (pp. 22--29). IEEE, 2010.
struct Constraint {
struct Pose {
transform::Rigid3d zbar_ij;
double translation_weight;
double rotation_weight;
}; SubmapId submap_id; // 'i' in the paper.
NodeId node_id; // 'j' in the paper. // Pose of the node 'j' relative to submap 'i'.
Pose pose; // Differentiates between intra-submap (where node 'j' was inserted into
// submap 'i') and inter-submap constraints (where node 'j' was not inserted
// into submap 'i').
enum Tag { INTRA_SUBMAP, INTER_SUBMAP } tag;
};