《自动驾驶与机器人中的SLAM技术》ch8:基于预积分和图优化的紧耦合 LIO 系统
目录
1 预积分 LIO 系统的经验
2 预积分图优化的顶点
3 预积分图优化的边
3.1 NDT 残差边(观测值维度为 3 维的单元边)
4 基于预积分和图优化 LIO 系统的实现
4.1 IMU 静止初始化
4.2 使用预积分预测
4.3 使用 IMU 预测位姿进行运动补偿
4.4 位姿配准部分
4.5 图优化部分
4.6 边缘化
4.6.1 边缘化公式
4.6.2 边缘化过程
和组合导航一样,也可以通过预积分 IMU 因子加上雷达残差来实现基于预积分和图优化的紧耦合 LIO 系统。一些现代的 Lidar SLAM 系统也采用了这种方式。相比滤波器方法来说,预积分因子可以更方便地整合到现有的优化框架中,从开发到实现都更为便捷。
1 预积分 LIO 系统的经验
在实现当中,预积分的使用方式是相当灵活的,要设置的参数也比 EKF 系统更多。例如 LIO-SAM 把预积分因子与雷达里程计的因子相结合,来构建整个优化问题。而在 VSLAM 系统里,也可以把预积分因子与重投影误差结合起来去求解 Bundle Adjustment。我们在此介绍一些预积分应用上的经验:
- 1. 预积分因子通常关联两个关键帧的高维状态(典型的 15 维状态
)。在转换为图优化问题时,我们可以选择①把各顶点分开处理,例如 SE(3) 一个顶点,v 占一个顶点,然后让一个预积分边关联到 8 个顶点上;②也可以选择把高维状态写成一个顶点,而预积分边关联两个顶点,但雅可比矩阵含有大量的零块。在本节实际操作中,我们选择前一种做法,即顶点种类数量较多,但边的维度较低的写法。这里使用和 《自动驾驶与机器人中的SLAM技术》ch4:预积分学 中一样的散装的形式。
- 2. 由于预积分因子关联的变量较多,且观测量大部分是状态变量的差值,我们应该对状态变量有足够的观测和约束,否则整个状态变量容易在零空间内自由变动。例如预积分的速度观测
描述了两个关键帧速度之差。如果我们将两个关键帧的速度都增量固定值,也可以让速度项误差保持不变,而在位移项施加一些调整,还能让位移部分观测保持不变。因此,在实际使用中,我们会给前一个关键帧施加先验约束,给后一个关键帧施加观测约束,让整个优化问题限制在一定的范围内。
- 3. 预积分的图优化模型如下图。我们在对两个关键帧计算优化时,为上一个关键帧添加一个先验因子,然后在两个帧间添加预积分因子和零偏随机游走因子,最后在下一个关键帧中添加 NDT 观测的位姿约束。在本轮优化完成后,我们利用边缘化方法,求出下一关键帧位姿的协方差矩阵,作为下一轮优化的先验因子来使用。
- 4. 这个图优化模型和第 4 章中的 GINS 系统非常相似。但是我们应当注意到,雷达里程计的观测位姿是依赖预测数据(初始值)的,这和 RTK 的位姿观测(绝对位姿观测)有着本质区别。如果 RTK 信号良好,我们可以认为 RTK 的观测有着固定的精度,此时滤波器和图优化器都可以保证在位移和旋转方面收敛。然而,如果雷达里程计使用一个不准确的预测位姿,它很有可能给出一个不正常的观测位姿,进而使整个 LIO 发散。这也导致了基于图优化的 LIO 系统调试难度要明显大于 GINS 系统。
- 5. 为了重复使用 《自动驾驶与机器人中的SLAM技术》ch8:基于 IESKF 的紧耦合 LIO 系统 中的代码,我们仍然使用前文所用的 LIO 框架,只是将原先 IESKF 处理的预测和观测部分,变为预积分器的预测和观测部分(在实际的系统中,也可以将滤波器作为前端,把图优化当成关键帧后端来使用)。整个 LIO 的计算框架图如下图所示。我们会在两个点云之间使用预积分进行优化。当然,正如我们前面所说,预积分的使用方式十分灵活,读者不必拘泥于我们的实现方式,也可以使用更长时间的预积分优化,或者将 NDT 内部的残差放到图优化中。但相对的,由于预积分因子关联的顶点较多,实际调试会比较困难,容易造成误差发散的情况。从一个现有系统出发再进行后端优化是个不错的选择。
2 预积分图优化的顶点
这里图优化的顶点 和 《自动驾驶与机器人中的SLAM技术》ch4:基于预积分和图优化的 GINS 中一样,为 15 维的位姿()、速度、陀螺仪零偏、加速度计零偏四种顶点,不再过多介绍。
3 预积分图优化的边
这里的图优化边包括:
- 预积分边(观测值维度为 9 维的多元边):ch4:预积分学 中介绍。
- 零偏随机游走边(观测值维度为 3 维的双元边):ch4:基于预积分和图优化的 GINS 中介绍。
- 先验因子边(观测值维度为 15 维的多元边):ch4:基于预积分和图优化的 GINS 中介绍。
- NDT 观测边(观测值维度为 6 维的单元边):和双天线的 GNSS 观测边一致,在 ch4:基于预积分和图优化的 GINS 中介绍。
3.1 NDT 残差边(观测值维度为 3 维的单元边)
注意(前面提到的): 广义地说,只要我们设计的状态估计系统考虑了各传感器内在的性质,而非模块化地将它们的输出进行融合,就可以称为紧耦合系统。例如,考虑了 IMU 观测噪声和零偏的系统,就可以称为 IMU的(或 INS 的)紧耦合;考虑了激光的配准残差,就可以称为激光的紧耦合;考虑了视觉特征点的重投影误差,或者考虑了 RTK 的细分状态、搜星数等信息,就可以称为视觉或 RTK 的紧耦合。
在 ch8:基于 IESKF 的紧耦合 LIO 系统 中,我们即考虑了 IMU 的观测噪声和零偏,又考虑了激光的配准残差(NDT 残差),所以可以称之为紧耦合的 LIO 系统;但是在这里,我们只考虑的 IMU 的观测噪声和零偏,并没有考虑点云的配准残差,严格来说不能称之为紧耦合的 LIO 系统。但是在 slam_in_autonomous_driving/src/common/g2o_types.h 和 slam_in_autonomous_driving/src/ch7/ndt_inc.cc中,实现了 NDT残差边(EdgeNDT类)和 根据估计的NDT建立edges的函数(IncNdt3d::BuildNDTEdges()),本章中并没有使用这里介绍的NDT残差边,后续可将其加入到图优化中。
残差的定义:
假设图 8.3 中的上一个关键帧是 时刻,下一个关键帧是
时刻。
时刻点云中的某一个点点
经过 预积分预测得到的
时刻的位姿
(
) 的转换后,会落在目标点云中的某一个体素内,假设这个体素的正态分布参数为
。此时,该点的残差
为 转换后的点的坐标和体素中的正态分布参数中的均值之差,即:
残差对状态变量的雅可比矩阵:
slam_in_autonomous_driving/src/common/g2o_types.h/*** NDT误差模型* 残差是 Rp+t-mu,info为NDT内部估计的info* 观测值维度为 3 维的单元边*/
class EdgeNDT : public g2o::BaseUnaryEdge<3, Vec3d, VertexPose> {public:EIGEN_MAKE_ALIGNED_OPERATOR_NEW;EdgeNDT() = default;/// 需要查询NDT内部的体素,这里用一个函数式给设置过去// 该函数已实现,在 IncNdt3d::BuildNDTEdges() 函数内部using QueryVoxelFunc = std::function<bool(const Vec3d& query_pt, Vec3d& mu, Mat3d& info)>;EdgeNDT(VertexPose* v0, const Vec3d& pt, QueryVoxelFunc func) {setVertex(0, v0);pt_ = pt;query_ = func;Vec3d q = v0->estimate().so3() * pt_ + v0->estimate().translation();if (query_(q, mu_, info_)) {setInformation(info_);valid_ = true;} else {valid_ = false;}}bool IsValid() const { return valid_; }Mat6d GetHessian() {linearizeOplus();return _jacobianOplusXi.transpose() * info_ * _jacobianOplusXi;}/// 残差计算void computeError() override {VertexPose* v0 = (VertexPose*)_vertices[0];Vec3d q = v0->estimate().so3() * pt_ + v0->estimate().translation();if (query_(q, mu_, info_)) {_error = q - mu_;setInformation(info_);valid_ = true;} else {valid_ = false;_error.setZero();setLevel(1);}}/// 线性化void linearizeOplus() override {if (valid_) {VertexPose* v0 = (VertexPose*)_vertices[0];SO3 R = v0->estimate().so3();_jacobianOplusXi.setZero();_jacobianOplusXi.block<3, 3>(0, 0) = -R.matrix() * SO3::hat(pt_); // 对R_jacobianOplusXi.block<3, 3>(0, 3) = Mat3d::Identity(); // 对p} else {_jacobianOplusXi.setZero();}}virtual bool read(std::istream& in) { return true; }virtual bool write(std::ostream& out) const { return true; }private:QueryVoxelFunc query_;Vec3d pt_ = Vec3d::Zero();Vec3d mu_ = Vec3d::Zero();Mat3d info_ = Mat3d::Identity();bool valid_ = false;
};
根据估计的NDT(local map)建立 NDT残差边 :
slam_in_autonomous_driving/src/ch7/ndt_inc.cc/**
* 根据估计的NDT建立edges
* @param v :输入参数,位姿顶点
* @param edges :输出参数,全部的有效的NDT残差边
*/
void IncNdt3d::BuildNDTEdges(sad::VertexPose* v, std::vector<EdgeNDT*>& edges) {assert(grids_.empty() == false);SE3 pose = v->estimate();/// 整体流程和NDT一致,只是把查询函数放到edge内部,建立和v绑定的边for (const auto& pt : source_->points) {Vec3d q = ToVec3d(pt);auto edge = new EdgeNDT(v, q, [this](const Vec3d& qs, Vec3d& mu, Mat3d& info) -> bool {Vec3i key = CastToInt(Vec3d(qs * options_.inv_voxel_size_));auto it = grids_.find(key);/// 这里要检查高斯分布是否已经估计if (it != grids_.end() && it->second->second.ndt_estimated_) {auto& v = it->second->second; // voxelmu = v.mu_;info = v.info_;return true;} else {return false;}});if (edge->IsValid()) {edges.emplace_back(edge);} else {delete edge;}}
}
4 基于预积分和图优化 LIO 系统的实现
基于预积分的紧耦合 LioPreinteg类 持有一个 IncNdt3d 对象,一个 IMUPreintegration 对象,一个 MessageSync 对象 处理同步之后的点云和 IMU。该类处理流程非常简单:当 MeasureGroup 到达后,在 IMU 未初始化时,使用第 3 章的静止初始化来估计 IMU 零偏。初始化完毕后,预积分 IMU 数据进行预测,再用预测数据对点云去畸变,最后对去畸变的点云做配准。
void LioPreinteg::ProcessMeasurements(const MeasureGroup &meas) {LOG(INFO) << "call meas, imu: " << meas.imu_.size() << ", lidar pts: " << meas.lidar_->size();measures_ = meas;if (imu_need_init_) {// 初始化IMU系统TryInitIMU();return;}// 利用IMU数据进行状态预测Predict();// 对点云去畸变Undistort();// 配准Align();
}
4.1 IMU 静止初始化
IMU 的静止初始化与《自动驾驶与机器人中的SLAM技术》ch3:惯性导航与组合导航 中介绍的大体一致。当 MeasureGroup 到达后,在 IMU 未初始化时,调用 StaticIMUInit::AddIMU() 函数进行 IMU的静止初始化。
当 IMU 初始化成功时,在当前 MeasureGroup 中使用 IMU 静止初始化结果初始化了 陀螺仪和加速度计的噪声标准差、初始的 、预积分类IMUPreintegration(在其构造中使用陀螺仪和加速度计的噪声方差初始化了 IMU 测量噪声的协方差矩阵)。
void LioPreinteg::TryInitIMU() {for (auto imu : measures_.imu_) {imu_init_.AddIMU(*imu);}if (imu_init_.InitSuccess()) {// 读取初始零偏,设置ESKF// 噪声由初始化器估计options_.preinteg_options_.noise_gyro_ = sqrt(imu_init_.GetCovGyro()[0]);options_.preinteg_options_.noise_acce_ = sqrt(imu_init_.GetCovAcce()[0]);options_.preinteg_options_.init_ba_ = imu_init_.GetInitBa();options_.preinteg_options_.init_bg_ = imu_init_.GetInitBg();preinteg_ = std::make_shared<IMUPreintegration>(options_.preinteg_options_);imu_need_init_ = false;current_nav_state_.v_.setZero();current_nav_state_.bg_ = imu_init_.GetInitBg();current_nav_state_.ba_ = imu_init_.GetInitBa();current_nav_state_.timestamp_ = measures_.imu_.back()->timestamp_;last_nav_state_ = current_nav_state_;last_imu_ = measures_.imu_.back();LOG(INFO) << "IMU初始化成功";}
}
4.2 使用预积分预测
和基于 IESKF 的紧耦合 LIO 系统不同,这里使用了 IMU 预积分进行预测:
void LioPreinteg::Predict() {// 这里会清空 imu_states_ ,所以在每接收一个 MeasureGroup 时,imu_states_ 中会存储 measures_.imu_.size() + 1 个数据,用于去畸变imu_states_.clear();imu_states_.emplace_back(last_nav_state_);/// 对IMU状态进行预测for (auto &imu : measures_.imu_) {if (last_imu_ != nullptr) {preinteg_->Integrate(*imu, imu->timestamp_ - last_imu_->timestamp_);}last_imu_ = imu;imu_states_.emplace_back(preinteg_->Predict(last_nav_state_, imu_init_.GetGravity()));}
}
4.3 使用 IMU 预测位姿进行运动补偿
和 《自动驾驶与机器人中的SLAM技术》ch8:基于 IESKF 的紧耦合 LIO 系统 中介绍的一样,不再介绍。
4.4 位姿配准部分
在配准时,使用预积分给出的预测位姿作为增量NDT里程计的初始位姿输入,迭代得到优化后的位姿,将优化后的位姿作为观测值进行优化(即作为 的初始估计值)。
void LioPreinteg::Align() {FullCloudPtr scan_undistort_trans(new FullPointCloudType);pcl::transformPointCloud(*scan_undistort_, *scan_undistort_trans, TIL_.matrix().cast<float>());scan_undistort_ = scan_undistort_trans;current_scan_ = ConvertToCloud<FullPointType>(scan_undistort_);// voxel 之pcl::VoxelGrid<PointType> voxel;voxel.setLeafSize(0.5, 0.5, 0.5);voxel.setInputCloud(current_scan_);CloudPtr current_scan_filter(new PointCloudType);voxel.filter(*current_scan_filter);/// the first scanif (flg_first_scan_) {ndt_.AddCloud(current_scan_);// my 我认为这里应该添加如下代码// current_nav_state_ = imu_states_.back();// NormalizeVelocity();// last_nav_state_ = current_nav_state_;// 重置预积分 preinteg_preinteg_ = std::make_shared<IMUPreintegration>(options_.preinteg_options_);flg_first_scan_ = false;return;}// 后续的scan,使用NDT配合pose进行更新LOG(INFO) << "=== frame " << frame_num_;ndt_.SetSource(current_scan_filter);current_nav_state_ = preinteg_->Predict(last_nav_state_, imu_init_.GetGravity());ndt_pose_ = current_nav_state_.GetSE3();// 使用 IMU 预积分预测值作为配准初始值ndt_.AlignNdt(ndt_pose_);Optimize();// 若运动了一定范围,则把点云放入地图中SE3 current_pose = current_nav_state_.GetSE3();SE3 delta_pose = last_ndt_pose_.inverse() * current_pose;if (delta_pose.translation().norm() > 0.3 || delta_pose.so3().log().norm() > math::deg2rad(5.0)) {// 将地图合入NDT中CloudPtr current_scan_world(new PointCloudType);pcl::transformPointCloud(*current_scan_filter, *current_scan_world, current_pose.matrix());ndt_.AddCloud(current_scan_world);last_ndt_pose_ = current_pose;}// 放入UIif (ui_) {ui_->UpdateScan(current_scan_, current_nav_state_.GetSE3()); // 转成Lidar Pose传给UIui_->UpdateNavState(current_nav_state_);}frame_num_++;
}
4.5 图优化部分
图优化部分基本上和 ch4:基于预积分和图优化的 GINS 一样,不同之处在于一下几点:
- 1.使用了NDT优化后的位姿作为
时刻位姿顶点的初始估计值,而没有使用预积分预测的位姿;
// 本时刻顶点,pose, v, bg, baauto v1_pose = new VertexPose();v1_pose->setId(4);// 注意:这里使用NDT优化后的位姿作为 j 时刻位姿的初始估计值v1_pose->setEstimate(ndt_pose_); // NDT pose作为初值// v1_pose->setEstimate(current_nav_state_.GetSE3()); // 预测的pose作为初值optimizer.addVertex(v1_pose);
- 2.在优化过程中,使用 setFixed() 函数将
时刻的
和
节点视为固定节点,不进行优化;
// 在优化过程中,将 i 时刻的bg和ba节点视为固定节点,不进行优化v0_bg->setFixed(true);v0_ba->setFixed(true);
- 3.对于
,我们想将
中的
边缘化(对应 Hessian 矩阵中 15x15 的
,要求其逆,从而消去
,边缘化
),得到
时刻状态的信息矩阵(更新后的 15x15维 的
),作为下一轮优化时(
时刻和
时刻)
时刻的先验因子的信息矩阵。在本博客的 4.6 小节中详细介绍;
- 4.对速度进行了限制,将其限制在正常区间。
void LioPreinteg::NormalizeVelocity() {/// 限制v的变化/// 一般是-y 方向速度// 将车体坐标系下 y 方向的分速度限制在 (-2 到 0 之间)Vec3d v_body = current_nav_state_.R_.inverse() * current_nav_state_.v_;if (v_body[1] > 0) {v_body[1] = 0;}// 将车体坐标系下 z 方向的分速度限制为 0v_body[2] = 0;if (v_body[1] < -2.0) {v_body[1] = -2.0;}// 将车体坐标系下 x 方向的分速度限制在(-0.1 到 0.1 之间)if (v_body[0] > 0.1) {v_body[0] = 0.1;} else if (v_body[0] < -0.1) {v_body[0] = -0.1;}current_nav_state_.v_ = current_nav_state_.R_ * v_body;
}
优化部分代码如下所示:
void LioPreinteg::Optimize() {// 调用g2o求解优化问题// 上一个state到本时刻state的预积分因子,本时刻的NDT因子LOG(INFO) << " === optimizing frame " << frame_num_ << " === "<< ", dt: " << preinteg_->dt_;/// NOTE 这些东西是对参数非常敏感的。相差几个数量级的话,容易出现优化不动的情况using BlockSolverType = g2o::BlockSolverX;using LinearSolverType = g2o::LinearSolverEigen<BlockSolverType::PoseMatrixType>;auto *solver = new g2o::OptimizationAlgorithmLevenberg(g2o::make_unique<BlockSolverType>(g2o::make_unique<LinearSolverType>()));g2o::SparseOptimizer optimizer;optimizer.setAlgorithm(solver);// 上时刻顶点, pose, v, bg, baauto v0_pose = new VertexPose();v0_pose->setId(0);v0_pose->setEstimate(last_nav_state_.GetSE3());optimizer.addVertex(v0_pose);auto v0_vel = new VertexVelocity();v0_vel->setId(1);v0_vel->setEstimate(last_nav_state_.v_);optimizer.addVertex(v0_vel);auto v0_bg = new VertexGyroBias();v0_bg->setId(2);v0_bg->setEstimate(last_nav_state_.bg_);optimizer.addVertex(v0_bg);auto v0_ba = new VertexAccBias();v0_ba->setId(3);v0_ba->setEstimate(last_nav_state_.ba_);optimizer.addVertex(v0_ba);// 本时刻顶点,pose, v, bg, baauto v1_pose = new VertexPose();v1_pose->setId(4);// 注意:这里使用NDT优化后的位姿作为 j 时刻位姿的初始估计值v1_pose->setEstimate(ndt_pose_); // NDT pose作为初值// v1_pose->setEstimate(current_nav_state_.GetSE3()); // 预测的pose作为初值optimizer.addVertex(v1_pose);auto v1_vel = new VertexVelocity();v1_vel->setId(5);v1_vel->setEstimate(current_nav_state_.v_);optimizer.addVertex(v1_vel);auto v1_bg = new VertexGyroBias();v1_bg->setId(6);v1_bg->setEstimate(current_nav_state_.bg_);optimizer.addVertex(v1_bg);auto v1_ba = new VertexAccBias();v1_ba->setId(7);v1_ba->setEstimate(current_nav_state_.ba_);optimizer.addVertex(v1_ba);// imu factorauto edge_inertial = new EdgeInertial(preinteg_, imu_init_.GetGravity());edge_inertial->setVertex(0, v0_pose);edge_inertial->setVertex(1, v0_vel);edge_inertial->setVertex(2, v0_bg);edge_inertial->setVertex(3, v0_ba);edge_inertial->setVertex(4, v1_pose);edge_inertial->setVertex(5, v1_vel);auto *rk = new g2o::RobustKernelHuber();rk->setDelta(200.0);edge_inertial->setRobustKernel(rk);optimizer.addEdge(edge_inertial);// 零偏随机游走auto *edge_gyro_rw = new EdgeGyroRW();edge_gyro_rw->setVertex(0, v0_bg);edge_gyro_rw->setVertex(1, v1_bg);edge_gyro_rw->setInformation(options_.bg_rw_info_);optimizer.addEdge(edge_gyro_rw);auto *edge_acc_rw = new EdgeAccRW();edge_acc_rw->setVertex(0, v0_ba);edge_acc_rw->setVertex(1, v1_ba);edge_acc_rw->setInformation(options_.ba_rw_info_);optimizer.addEdge(edge_acc_rw);// 上一帧pose, vel, bg, ba的先验auto *edge_prior = new EdgePriorPoseNavState(last_nav_state_, prior_info_);edge_prior->setVertex(0, v0_pose);edge_prior->setVertex(1, v0_vel);edge_prior->setVertex(2, v0_bg);edge_prior->setVertex(3, v0_ba);optimizer.addEdge(edge_prior);/// 使用NDT的pose进行观测auto *edge_ndt = new EdgeGNSS(v1_pose, ndt_pose_);edge_ndt->setInformation(options_.ndt_info_);optimizer.addEdge(edge_ndt);if (options_.verbose_) {LOG(INFO) << "last: " << last_nav_state_;LOG(INFO) << "pred: " << current_nav_state_;LOG(INFO) << "NDT: " << ndt_pose_.translation().transpose() << ","<< ndt_pose_.so3().unit_quaternion().coeffs().transpose();}// 在优化过程中,将 i 时刻的bg和ba节点视为固定节点,不进行优化v0_bg->setFixed(true);v0_ba->setFixed(true);// gooptimizer.setVerbose(options_.verbose_);optimizer.initializeOptimization();optimizer.optimize(20);// get resultslast_nav_state_.R_ = v0_pose->estimate().so3();last_nav_state_.p_ = v0_pose->estimate().translation();last_nav_state_.v_ = v0_vel->estimate();last_nav_state_.bg_ = v0_bg->estimate();last_nav_state_.ba_ = v0_ba->estimate();current_nav_state_.R_ = v1_pose->estimate().so3();current_nav_state_.p_ = v1_pose->estimate().translation();current_nav_state_.v_ = v1_vel->estimate();current_nav_state_.bg_ = v1_bg->estimate();current_nav_state_.ba_ = v1_ba->estimate();if (options_.verbose_) {LOG(INFO) << "last changed to: " << last_nav_state_;LOG(INFO) << "curr changed to: " << current_nav_state_;LOG(INFO) << "preinteg chi2: " << edge_inertial->chi2() << ", err: " << edge_inertial->error().transpose();LOG(INFO) << "prior chi2: " << edge_prior->chi2() << ", err: " << edge_prior->error().transpose();LOG(INFO) << "ndt: " << edge_ndt->chi2() << "/" << edge_ndt->error().transpose();}/// 重置预积分options_.preinteg_options_.init_bg_ = current_nav_state_.bg_;options_.preinteg_options_.init_ba_ = current_nav_state_.ba_;preinteg_ = std::make_shared<IMUPreintegration>(options_.preinteg_options_);// gauss-newton 迭代中累加Hessian和error,计算dx类似。一共 5 种类型的边,在累加Hessian都要考虑上。// 计算当前时刻先验// 构建hessian// 15x2,顺序:v0_pose, v0_vel, v0_bg, v0_ba, v1_pose, v1_vel, v1_bg, v1_ba// 0 6 9 12 15 21 24 27Eigen::Matrix<double, 30, 30> H;H.setZero();// ①添加 预积分因子的 Hessian 矩阵H.block<24, 24>(0, 0) += edge_inertial->GetHessian();// ②添加 陀螺仪零偏随机游走因子 的 Hessian 矩阵Eigen::Matrix<double, 6, 6> Hgr = edge_gyro_rw->GetHessian();// 行: bg1 列: bg1 H.block<3, 3>(9, 9) += Hgr.block<3, 3>(0, 0);// 行: bg1 列: bg2H.block<3, 3>(9, 24) += Hgr.block<3, 3>(0, 3);// 行: bg2 列: bg1H.block<3, 3>(24, 9) += Hgr.block<3, 3>(3, 0);// 行: bg2 列: bg2H.block<3, 3>(24, 24) += Hgr.block<3, 3>(3, 3);// ③添加 加速度计零偏随机游走因子 的 Hessian 矩阵Eigen::Matrix<double, 6, 6> Har = edge_acc_rw->GetHessian();H.block<3, 3>(12, 12) += Har.block<3, 3>(0, 0);H.block<3, 3>(12, 27) += Har.block<3, 3>(0, 3);H.block<3, 3>(27, 12) += Har.block<3, 3>(3, 0);H.block<3, 3>(27, 27) += Har.block<3, 3>(3, 3);// ④添加 先验因子 的 Hessian 矩阵H.block<15, 15>(0, 0) += edge_prior->GetHessian();// ⑤添加 NDT 观测因子的 Hessian 矩阵H.block<6, 6>(15, 15) += edge_ndt->GetHessian();// 边缘化(利用 H 的稀疏性加速 HΔx=g 的求解的方法。视觉SLAM十四讲 p245)// 边缘化(在本轮优化完成后,利用边缘化的方法,求出下一个关键帧位姿的协方差,作为下一轮优化的先验因子的信息矩阵使用。sad p245)H = math::Marginalize(H, 0, 14);prior_info_ = H.block<15, 15>(15, 15);if (options_.verbose_) {LOG(INFO) << "info trace: " << prior_info_.trace();LOG(INFO) << "optimization done.";}NormalizeVelocity();last_nav_state_ = current_nav_state_;
}
4.6 边缘化
4.6.1 边缘化公式
对于 ,将其变为如下形式,其中下方的
为待边缘化的增量 :
对线性方程组进行高斯消元,目标是消去右上角的 部分(将其变为 0)。
整理得:
消元之后,方程组的第一行就变成和 无关的项。单独把它拿出来,得到关于
部分的增量方程:
这样,就将求解 线性方程组的问题转换为先求解
,在将其带入方程组求解
的问题。这个过程称为边缘化(Marginalization)或者 Schur 消元。即先边缘化
,求出
,再求
的过程。
4.6.2 边缘化过程
图优化完毕后,把 5 种因子(预积分因子、2个零偏随机游走因子、先验因子和NDT观测因子)的海塞 (Hessian) 矩阵按照顺序累加组合成一个大的 Hessian 矩阵,对于
,我们想将
中的
边缘化(对应 Hessian 矩阵中 15x15 的
,要求其逆,从而消去
,边缘化
),得到
时刻状态的信息矩阵(更新后的 15x15维 的
),作为下一轮优化时(
时刻和
时刻)
时刻的先验因子的信息矩阵。
累加 5 种因子的 Hessian 矩阵一个大的 Hessian 矩阵 代码如下:
// gauss-newton 迭代中累加Hessian和error,计算dx类似。一共 5 种类型的边,在累加Hessian都要考虑上。// 计算当前时刻先验// 构建hessian// 15x2,顺序:v0_pose, v0_vel, v0_bg, v0_ba, v1_pose, v1_vel, v1_bg, v1_ba// 0 6 9 12 15 21 24 27Eigen::Matrix<double, 30, 30> H;H.setZero();// ①添加 预积分因子的 Hessian 矩阵H.block<24, 24>(0, 0) += edge_inertial->GetHessian();// ②添加 陀螺仪零偏随机游走因子 的 Hessian 矩阵Eigen::Matrix<double, 6, 6> Hgr = edge_gyro_rw->GetHessian();// 行: bg1 列: bg1 H.block<3, 3>(9, 9) += Hgr.block<3, 3>(0, 0);// 行: bg1 列: bg2H.block<3, 3>(9, 24) += Hgr.block<3, 3>(0, 3);// 行: bg2 列: bg1H.block<3, 3>(24, 9) += Hgr.block<3, 3>(3, 0);// 行: bg2 列: bg2H.block<3, 3>(24, 24) += Hgr.block<3, 3>(3, 3);// ③添加 加速度计零偏随机游走因子 的 Hessian 矩阵Eigen::Matrix<double, 6, 6> Har = edge_acc_rw->GetHessian();H.block<3, 3>(12, 12) += Har.block<3, 3>(0, 0);H.block<3, 3>(12, 27) += Har.block<3, 3>(0, 3);H.block<3, 3>(27, 12) += Har.block<3, 3>(3, 0);H.block<3, 3>(27, 27) += Har.block<3, 3>(3, 3);// ④添加 先验因子 的 Hessian 矩阵H.block<15, 15>(0, 0) += edge_prior->GetHessian();// ⑤添加 NDT 观测因子的 Hessian 矩阵H.block<6, 6>(15, 15) += edge_ndt->GetHessian();// 边缘化(利用 H 的稀疏性加速 HΔx=g 的求解的方法。视觉SLAM十四讲 p245)// 边缘化(在本轮优化完成后,利用边缘化的方法,求出下一个关键帧位姿的协方差,作为下一轮优化的先验因子的信息矩阵使用。sad p245)H = math::Marginalize(H, 0, 14);prior_info_ = H.block<15, 15>(15, 15);
将 中的
边缘化,取边缘化后的
对应的子矩阵作为下一轮优化的先验因子的信息矩阵使用:
// 边缘化(利用 H 的稀疏性加速 HΔx=g 的求解的方法。视觉SLAM十四讲 p245)// 边缘化(在本轮优化完成后,利用边缘化的方法,求出下一个关键帧位姿的协方差,作为下一轮优化的先验因子的信息矩阵使用。sad p245)H = math::Marginalize(H, 0, 14);prior_info_ = H.block<15, 15>(15, 15);
边缘化的目标如下,要将通过函数形参 start 和 end 选定的 增量范围边缘化:
a | ab | ac a* | 0 | ac*
ba | b | bc --> 0 | 0 | 0
ca | cb | c ca* | 0 | c*
- 1.通过函数形参 start 和 end 选定待边缘化的
增量范围(对应矩阵块 b);
- 2.将
移动到
的下方,即对应的 b 矩阵块也移动到矩阵 H 的右下角;
a | ab | ac a | ac | ab
ba | b | bc --> ca | c | cb
ca | cb | c ba | bc | b
- 3.对 b 矩阵块进行奇异值分解求其伪逆,即
。
,
;
- 4.使用如下公式更新 H 矩阵;
注意:有于在这个部分后续不会使用 ,所以将其全部置 0 ,只更新
,并将其作为下一轮优化时(
时刻和
时刻)
时刻的先验因子的信息矩阵。。
- 5.将更新后的 H 矩阵恢复为初始顺序。
a* | ac* | 0 a* | 0 | ac*
ca* | c* | 0 --> 0 | 0 | 0
0 | 0 | 0 ca* | 0 | c*
具体代码如下:
/*** 边缘化。视觉SLAM十四讲。p 249* @param H* @param start* @param end* @return*/
inline Eigen::MatrixXd Marginalize(const Eigen::MatrixXd& H, const int& start, const int& end) {// ① 通过函数形参 start 和 end 选定待边缘化的 Δx_(Scher) 增量范围(对应矩阵块 b)// Goal// a | ab | ac a* | 0 | ac*// ba | b | bc --> 0 | 0 | 0// ca | cb | c ca* | 0 | c*// Size of block before block to marginalize const int a = start;// Size of block to marginalizeconst int b = end - start + 1;// Size of block after block to marginalizeconst int c = H.cols() - (end + 1);// ② 将 Δx_(Scher) 移动到 Δx 的下方,即对应的 b 矩阵块也移动到矩阵 H 的右下角// Reorder as follows:// a | ab | ac a | ac | ab// ba | b | bc --> ca | c | cb// ca | cb | c ba | bc | bEigen::MatrixXd Hn = Eigen::MatrixXd::Zero(H.rows(), H.cols());// block函数:block(startRow, startCol, rows, cols);if (a > 0) {Hn.block(0, 0, a, a) = H.block(0, 0, a, a);Hn.block(0, a + c, a, b) = H.block(0, a, a, b);Hn.block(a + c, 0, b, a) = H.block(a, 0, b, a);}if (a > 0 && c > 0) {Hn.block(0, a, a, c) = H.block(0, a + b, a, c);Hn.block(a, 0, c, a) = H.block(a + b, 0, c, a);}if (c > 0) {Hn.block(a, a, c, c) = H.block(a + b, a + b, c, c);Hn.block(a, a + c, c, b) = H.block(a + b, a, c, b);Hn.block(a + c, a, b, c) = H.block(a, a + b, b, c);}Hn.block(a + c, a + c, b, b) = H.block(a, a, b, b);// ③ 对 b 矩阵块进行奇异值分解求其伪逆,即 H22^-1。A = U*Σ*V^T A^-1 = V*Σ^-1*U^T// Perform marginalization (Schur complement)Eigen::JacobiSVD<Eigen::MatrixXd> svd(Hn.block(a + c, a + c, b, b), Eigen::ComputeThinU | Eigen::ComputeThinV);// 返回奇异值矩阵 Σ,即对角矩阵,其中每个对角元素都是 b 矩阵块 的奇异值。Eigen::JacobiSVD<Eigen::MatrixXd>::SingularValuesType singularValues_inv = svd.singularValues();// 计算 Σ^-1for (int i = 0; i < b; ++i) {if (singularValues_inv(i) > 1e-6) singularValues_inv(i) = 1.0 / singularValues_inv(i);elsesingularValues_inv(i) = 0;}// 使用奇异值分解法求 b 矩阵块的伪逆。A^-1 = V*Σ^-1*U^TEigen::MatrixXd invHb = svd.matrixV() * singularValues_inv.asDiagonal() * svd.matrixU().transpose();// ④ 使用公式更新 H 矩阵// H11 = H11 - H12 * H22^-1 * H21// H12 = 0// H21 = H21// H22 = H22Hn.block(0, 0, a + c, a + c) =Hn.block(0, 0, a + c, a + c) - Hn.block(0, a + c, a + c, b) * invHb * Hn.block(a + c, 0, b, a + c);Hn.block(a + c, a + c, b, b) = Eigen::MatrixXd::Zero(b, b);Hn.block(0, a + c, a + c, b) = Eigen::MatrixXd::Zero(a + c, b);Hn.block(a + c, 0, b, a + c) = Eigen::MatrixXd::Zero(b, a + c);// ⑤将更新后的 H 矩阵恢复为初始顺序// Inverse reorder// a* | ac* | 0 a* | 0 | ac*// ca* | c* | 0 --> 0 | 0 | 0// 0 | 0 | 0 ca* | 0 | c*Eigen::MatrixXd res = Eigen::MatrixXd::Zero(H.rows(), H.cols());if (a > 0) {res.block(0, 0, a, a) = Hn.block(0, 0, a, a);res.block(0, a, a, b) = Hn.block(0, a + c, a, b);res.block(a, 0, b, a) = Hn.block(a + c, 0, b, a);}if (a > 0 && c > 0) {res.block(0, a + b, a, c) = Hn.block(0, a, a, c);res.block(a + b, 0, c, a) = Hn.block(a, 0, c, a);}if (c > 0) {res.block(a + b, a + b, c, c) = Hn.block(a, a, c, c);res.block(a + b, a, c, b) = Hn.block(a, a + c, c, b);res.block(a, a + b, b, c) = Hn.block(a + c, a, b, c);}res.block(a, a, b, b) = Hn.block(a + c, a + c, b, b);return res;
}
相关文章:
《自动驾驶与机器人中的SLAM技术》ch8:基于预积分和图优化的紧耦合 LIO 系统
目录 1 预积分 LIO 系统的经验 2 预积分图优化的顶点 3 预积分图优化的边 3.1 NDT 残差边(观测值维度为 3 维的单元边) 4 基于预积分和图优化 LIO 系统的实现 4.1 IMU 静止初始化 4.2 使用预积分预测 4.3 使用 IMU 预测位姿进行运动补偿 4.4 位姿配准部…...

Linux下PostgreSQL-12.0安装部署详细步骤
一、安装环境 postgresql-12.0 CentOS-7.6 注意:确认linux系统可以正常连接网络,因为在后面需要添加依赖包。 二、pg数据库安装包下载 下载地址:PostgreSQL: File Browser 选择要安装的版本进行下载: 三、安装依赖包 在要安…...
STL—stack与queue
目录 Stack stack的使用 stack的模拟实现 queue queue的使用 queue的模拟实现 priority_queue priority_queue的用法 priority_queue的模拟实现 容器适配器 种类 Stack http://www.cplusplus.com/reference/stack/stack/?kwstack stack是栈,后入先出 stack的…...

docker 使用远程镜像启动一个容器
使用前提: 首先你得安装docker,其次你得拥有一个远程镜像 docker run --name io_11281009 --rm -it -p 2233:22 -v .:/root/py -e ed25519_rootAAAAC3NzaC1lZDI1********Oy7zR7l7aUniR2rul ghcr.lizzie.fun/fj0r/io srv对上述命令解释: 1.docker run:…...

简述mysql 主从复制原理及其工作过程,配置一主两从并验证
第一种基于binlog的主从同步 首先对主库进行配置: [rootopenEuler-1 ~]# vim /etc/my.cnf 启动服务 [rootopenEuler-1 ~]# systemctl enable --now mysqld 主库的配置 从库的配置 第一个从库 [rootopenEuler-1 ~]# vim /etc/my.cnf [rootopenEuler-1 ~]# sys…...
oracle之行转列
对于Oracle的行转列功能一直云里雾里,马马虎虎,对行转列的使用场景和使用方法都不够深刻,最近有空理解一下。 Oracle 11g后有专门的函数pivot,对于特定的场景可以直接套用。 需求:求各份job不同员工工资是多少…...

Windows电脑安装USB Redirector并实现内外网跨网USB共享通信访问
文章目录 前言1. 安装下载软件1.1 内网安装使用USB Redirector1.2 下载安装cpolar内网穿透 2. 完成USB Redirector服务端和客户端映射连接3. 设置固定的公网地址 前言 我们每天都在与各种智能设备打交道,从手机到电脑,再到各种外设,它们已经…...
kafka学习笔记4-TLS加密 —— 筑梦之路
1. 准备证书文件 mkdir /opt/kafka/pkicd !$# 生成CA证书 openssl req -x509 -nodes -days 3650 -newkey rsa:4096 -keyout ca.key -out ca.crt -subj "/CNKafka-CA"# 生成私钥 openssl genrsa -out kafka.key 4096# 生成证书签名请求 (CSR) openssl req -new -key …...

grafana + Prometheus + node_exporter搭建监控大屏
本文介绍生产系统监控大屏的搭建,比较实用也是实际应用比较多的方式,希望能够帮助大家对监控系统有一定的认识。 0、规划 grafana主要是展示和报警,Prometheus用于保存监控数据,node_exporter用于实时采集各个应用服务器的事实状…...
深度学习在语音识别中的应用
引言 语音识别技术是人工智能领域中的一个重要分支,它使得机器能够理解和转换人类的语音为文本。深度学习的出现极大地推动了语音识别技术的发展。本文将介绍如何使用深度学习构建一个基本的语音识别系统,并提供一个实践案例。 环境准备 在开始之前&a…...

RabbitMQ 高级特性
目录 1.消息确认 1.1 消息确认机制 1.2 手动确认方法 1. 2.1肯定确认 1.2.2 否定确认 1.3 SpringBoot 代码示例 1.3.1 配置确认机制 1.3.2 配置队列,交换机,绑定关系 1.3.3 生产者(向 rabbitmq 发送消息) 1.3.4 消费者(消费队列中的信息) 2.持久性 2.1 交换机…...
第01章 07 MySQL+VTK C++示例代码,实现医学影像数据的IO数据库存储
要实现将医学影像数据(如DICOM文件或其他医学图像格式)存储到MySQL数据库中,并使用VTK进行数据读取和处理的C示例代码,可以按照以下步骤进行。这个示例将展示如何将DICOM图像数据存储到MySQL数据库,然后使用VTK读取并显…...
Mysql创建定时任务
mysql查看存储过程 SHOW PROCEDURE STATUS;查看event_scheduler show events;查看当前event_scheduler的状态 SHOW VARIABLES LIKE event_scheduler;关闭event_scheduler set GLOBAL event_schedulerOFF;删除event_scheduler drop event event_name;创建存储过程 -- 创建存…...

【MySQL篇】使用mysqldump导入报错Unknown collation: ‘utf8mb4_0900_ai_ci‘的问题解决
💫《博主介绍》:✨又是一天没白过,我是奈斯,从事IT领域✨ 💫《擅长领域》:✌️擅长阿里云AnalyticDB for MySQL(分布式数据仓库)、Oracle、MySQL、Linux、prometheus监控;并对SQLserver、NoSQL(…...

专业学习|最优化理论(目标函数、约束条件以及解题三板斧)
个人学习使用资料,请勿传播,若有侵权联系删除,资料来源:fairy girl。 一、最优化理论:让决策更科学,让模型更高效 (一)什么是最优化理论? 最优化理论是数学的一个分支,它研究如何在一定约束条件下找到使目标函数达到最大值或最小值的最优解。 关键概念:最优化理论的…...

【Linux】gawk编辑器二
一、变量 gawk编程语言支持两种变量:内建变量和自定义变量。 1、内建变量 gawk使用内建变量来引用一些特殊的功能。 字段和记录分隔符变量 数据字段变量 此变量允许使用美元符号($)和字段在记录中的位置值来引用对应的字段。要引用记录…...

Hadoop美食推荐系统 爬虫1.8w+数据 协同过滤余弦函数推荐美食 Springboot Vue Element-UI前后端分离
Hadoop美食推荐系统 爬虫1.8w数据 协同过滤余弦函数推荐美食 Springboot Vue Element-UI前后端分离 【Hadoop项目】 1. data.csv上传到hadoop集群环境 2. data.csv数据清洗 3.MapReducer数据汇总处理, 将Reducer的结果数据保存到本地Mysql数据库中 4. SpringbootEchartsMySQL 显…...

吴恩达深度学习——神经网络编程的基础知识
文章内容来自BV11H4y1F7uH,仅为个人学习所用。 文章目录 二分分类一些符号说明 逻辑斯蒂回归传统的线性回归函数 y ^ w T x b \hat{y}w^T\boldsymbol{x}b y^wTxbSigmoid激活函数逻辑斯蒂回归损失函数损失函数成本函数与损失函数的关系 梯度下降法计算图逻辑斯蒂…...

第14个项目:E-Learning在线学习平台Python源码
源码下载地址:https://download.csdn.net/download/mosquito_lover1/90292074 系统截图: 功能介绍: 响应式设计,完全支持移动端 现代化的UI界面 用户认证系统 课程展示功能 模块化的结构 要进一步完善这个应用,您可以: 添加用户认证系统(登录/注册) 实现课程详情页面…...

Qt之文件系统操作和读写
Qt creator 6.80 MinGw 64bit 文本文件是指以纯文本格式存储的文件,如cpp和hpp文件。XML文件和JSON文件也是文本文件,只是使用了特定的标记符号定义文本的含义,读取这种文本文件需要先对内容解析再显示。 qt提供了两种读写文本文件的方法。…...

【Axure高保真原型】引导弹窗
今天和大家中分享引导弹窗的原型模板,载入页面后,会显示引导弹窗,适用于引导用户使用页面,点击完成后,会显示下一个引导弹窗,直至最后一个引导弹窗完成后进入首页。具体效果可以点击下方视频观看或打开下方…...

MPNet:旋转机械轻量化故障诊断模型详解python代码复现
目录 一、问题背景与挑战 二、MPNet核心架构 2.1 多分支特征融合模块(MBFM) 2.2 残差注意力金字塔模块(RAPM) 2.2.1 空间金字塔注意力(SPA) 2.2.2 金字塔残差块(PRBlock) 2.3 分类器设计 三、关键技术突破 3.1 多尺度特征融合 3.2 轻量化设计策略 3.3 抗噪声…...

阿里云ACP云计算备考笔记 (5)——弹性伸缩
目录 第一章 概述 第二章 弹性伸缩简介 1、弹性伸缩 2、垂直伸缩 3、优势 4、应用场景 ① 无规律的业务量波动 ② 有规律的业务量波动 ③ 无明显业务量波动 ④ 混合型业务 ⑤ 消息通知 ⑥ 生命周期挂钩 ⑦ 自定义方式 ⑧ 滚的升级 5、使用限制 第三章 主要定义 …...

最新SpringBoot+SpringCloud+Nacos微服务框架分享
文章目录 前言一、服务规划二、架构核心1.cloud的pom2.gateway的异常handler3.gateway的filter4、admin的pom5、admin的登录核心 三、code-helper分享总结 前言 最近有个活蛮赶的,根据Excel列的需求预估的工时直接打骨折,不要问我为什么,主要…...
【论文笔记】若干矿井粉尘检测算法概述
总的来说,传统机器学习、传统机器学习与深度学习的结合、LSTM等算法所需要的数据集来源于矿井传感器测量的粉尘浓度,通过建立回归模型来预测未来矿井的粉尘浓度。传统机器学习算法性能易受数据中极端值的影响。YOLO等计算机视觉算法所需要的数据集来源于…...
【C语言练习】080. 使用C语言实现简单的数据库操作
080. 使用C语言实现简单的数据库操作 080. 使用C语言实现简单的数据库操作使用原生APIODBC接口第三方库ORM框架文件模拟1. 安装SQLite2. 示例代码:使用SQLite创建数据库、表和插入数据3. 编译和运行4. 示例运行输出:5. 注意事项6. 总结080. 使用C语言实现简单的数据库操作 在…...
聊一聊接口测试的意义有哪些?
目录 一、隔离性 & 早期测试 二、保障系统集成质量 三、验证业务逻辑的核心层 四、提升测试效率与覆盖度 五、系统稳定性的守护者 六、驱动团队协作与契约管理 七、性能与扩展性的前置评估 八、持续交付的核心支撑 接口测试的意义可以从四个维度展开,首…...
C++八股 —— 单例模式
文章目录 1. 基本概念2. 设计要点3. 实现方式4. 详解懒汉模式 1. 基本概念 线程安全(Thread Safety) 线程安全是指在多线程环境下,某个函数、类或代码片段能够被多个线程同时调用时,仍能保证数据的一致性和逻辑的正确性…...
rnn判断string中第一次出现a的下标
# coding:utf8 import torch import torch.nn as nn import numpy as np import random import json""" 基于pytorch的网络编写 实现一个RNN网络完成多分类任务 判断字符 a 第一次出现在字符串中的位置 """class TorchModel(nn.Module):def __in…...

让回归模型不再被异常值“带跑偏“,MSE和Cauchy损失函数在噪声数据环境下的实战对比
在机器学习的回归分析中,损失函数的选择对模型性能具有决定性影响。均方误差(MSE)作为经典的损失函数,在处理干净数据时表现优异,但在面对包含异常值的噪声数据时,其对大误差的二次惩罚机制往往导致模型参数…...