MapBuilder
在创建GlobalTrajectoryBuilder
时中会实例化 PoseGraph
对象, 并作为 GlobalTrajectoryBuilder
的成员。
接着看GlobalTrajectoryBuilder::AddSensorData
的后端部分1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24/* 将前端的输出结果喂给后端进行闭环检测和全局优化 */
kLocalSlamMatchingResults->Increment();
// 前端匹配的结果,即submap位置和submap
std::unique_ptr<InsertionResult> insertion_result;
// 判定前端是否将传感器的数据插入到子图中
if (matching_result->insertion_result != nullptr)
{
kLocalSlamInsertionResults->Increment();
// 将匹配后的结果加入图优化节点中
// 把前端的输出结果喂给后端,即后端增加一个新的节点
// 后端优化位姿图节点ID,记录在临时对象 node_id
auto node_id = pose_graph_->AddNode(
matching_result->insertion_result->constant_data,
trajectory_id_,
matching_result->insertion_result->insertion_submaps );
CHECK_EQ(node_id.trajectory_id, trajectory_id_);
// 重新封装前端传来的 InsertionResult,增加了一个node_id
insertion_result = absl::make_unique<InsertionResult>( InsertionResult{
node_id, matching_result->insertion_result->constant_data,
std::vector<std::shared_ptr<const Submap>>(
matching_result->insertion_result->insertion_submaps.begin(),
matching_result->insertion_result->insertion_submaps.end() ) } );
}
PoseGraph2D
类的以FromProto
结尾的函数, 全是在 MapBuilder::LoadState 里调用的,也就是纯定位的用途。
1 | NodeId PoseGraph2D::AddNode( |
后端增加一个位姿图节点需要传递匹配后的结果包括submap和点云数据,最后返回一个位姿图节点ID。其中前端处理后的点云数据,包括水平投影的点云,重力方向和在local submap的位置。
GetLocalToGlobalTransform
获取激光点云当前local map下的pose,转换为全局绝对pose的转移矩阵。也就是从local map坐标系转到global map坐标系1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39transform::Rigid3d PoseGraph2D::GetLocalToGlobalTransform(
const int trajectory_id) const
{
absl::MutexLock locker(&mutex_);
return ComputeLocalToGlobalTransform(
data_.global_submap_poses_2d,
trajectory_id );
}
transform::Rigid3d PoseGraph2D::ComputeLocalToGlobalTransform(
const MapById<SubmapId, optimization::SubmapSpec2D>& global_submap_poses,
const int trajectory_id) const
{
// 查找已经优化过的trajectory id中的submap的位置,如果有可返回存储的值
auto begin_it = global_submap_poses.BeginOfTrajectory(trajectory_id);
auto end_it = global_submap_poses.EndOfTrajectory(trajectory_id);
if (begin_it == end_it)
{
const auto it = data_.initial_trajectory_poses.find(trajectory_id);
// 位姿插值
if (it != data_.initial_trajectory_poses.end())
{
return GetInterpolatedGlobalTrajectoryPose(it->second.to_trajectory_id,
it->second.time) *
it->second.relative_pose;
}
// 仅是唯一个,表明为初始submap,转移矩阵为单位矩阵
else
return transform::Rigid3d::Identity();
}
const SubmapId last_optimized_submap_id = std::prev(end_it)->id;
// 如果不存在,则返回由上个优化后的 submap_id 的位置的相对位置换算出的位置
return transform::Embed3D(
global_submap_poses.at(last_optimized_submap_id).global_pose) *
data_.submap_data.at(last_optimized_submap_id)
.submap->local_pose()
.inverse();
}
既然这个函数是返回一个transform,所以是左乘变换: global = transform * local
,因此transform = global * inv(local)
。 初始global为单位矩阵,也就是产生子图前,后续通过相对位置推导每个位置
在InitializeGlobalSubmapPoses
里可以看到获得转换矩阵的逻辑:
首先从global_submap_poses_2d
中找出属于该轨迹的所有submap信息,那就找出上一个优化过的子图的全局位姿global_pose
和局部位姿local_pose
,通过这两个位姿就可以得到 local和global坐标系 的转换矩阵。
如果在global_submap_poses_2d
没有找到该轨迹的submap信息,那就说明该轨迹还没有产生submap,那就从data_.initial_trajectory_poses
中查找该轨迹的初始位姿,如果找到 了初始位姿,就根据该轨迹初始位姿的时间去节点列表中找改时间点最近的节点,根据该节点的global_pose
找到 local 和 global 的转换信息。
initial_trajectory_poses
来自SetInitialTrajectoryPose
,根源在MapBuilder::AddTrajectoryBuilder
的trajectory_options.has_initial_trajectory_pose()
,但是没找到函数has_initial_trajectory_pose()
。怀疑这是纯定位的部分
如果initial_trajectory_poses
中也没有找到该轨迹的初始位姿,就直接返回单位转换矩阵,认为二者重合。