《自动驾驶与机器人中的SLAM技术》ch8:基于预积分和图优化的紧耦合 LIO 系统
和组合导航一样,也可以通过预积分 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 边缘化
优化完毕后,把 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);
将 中的
边缘化,即消去对应的大 Hessian 矩阵
中左上角 15x15 的小块,取边缘化后的
对应的子矩阵,即矩阵右下角15x15 的小块作为下一轮优化的先验因子的信息矩阵使用:
// 边缘化(利用 H 的稀疏性加速 HΔx=g 的求解的方法。视觉SLAM十四讲 p245)// 边缘化(在本轮优化完成后,利用边缘化的方法,求出下一个关键帧位姿的协方差,作为下一轮优化的先验因子的信息矩阵使用。sad p245)H = math::Marginalize(H, 0, 14);prior_info_ = H.block<15, 15>(15, 15);
边缘化的目标如下,要将通过函数形参 start 和 end 选定的 对应的小矩阵块 b 消去:
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 矩阵;
TODO:待补充
- 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) {// ① b 矩阵块为需要边缘化的矩阵块(通过 start 和 end 确定)// 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 marginalizeconst 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);// ② 将 b 矩阵块移动到右下角// 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 矩阵块进行奇异值分解求其伪逆。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// H22 = 0// H12 = 0// H21 = 0 Hn.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 系统
和组合导航一样,也可以通过预积分 IMU 因子加上雷达残差来实现基于预积分和图优化的紧耦合 LIO 系统。一些现代的 Lidar SLAM 系统也采用了这种方式。相比滤波器方法来说,预积分因子可以更方便地整合到现有的优化框架中,从开发到实现都更为便…...
Mysql学习笔记
连接数据库 找到 MySQL 安装目录下的 bin 目录,然后打开命令窗口,在命令窗口中按如下语法输入命令: mysql - h MySQL 数据库服务器的 IP 地址 - u 用户名 - p 然后按下回车键,输入密码即可 数据库操作 创建数据库 CREAT…...
Safari常用快捷键
一、书签边栏 1、显示或隐藏书签边栏:Control-Command-1 2、选择下一个书签或文件夹:向上头键或向下头键 3、打开所选书签:空格键 4、打开所选文件夹:空格键或右箭头键 5、关闭所选文件夹:空格键或左箭头键 6、更…...
OpenEuler学习笔记(二):用通俗的道理讲操作系统原理
用通俗的道理讲操作系统原理 基础概念类比 把OpenEuler操作系统想象成一个大型的工厂,这个工厂有各种各样的部门,每个部门都有自己的职责,共同协作来让整个工厂正常运转。内核就像是工厂的管理中心,它负责指挥和协调所有的工作。 …...
ros2-7.5 做一个自动巡检机器人
7.5.1 需求及设计 又到了小鱼老师带着做最佳实践项目了。需求:做一个在各个房间不断巡逻并记录图像的机器人。 到达目标点后首先通过语音播放到达目标点信息, 再通过摄像头拍摄一张图片保存到本地。 7.5.2 编写巡检控制节点 在chapt7_ws/src下新建功…...
使用 `scanpy` 观察 `AnnData` 对象内部数据结构
以下是使用 scanpy 观察 AnnData 对象内部数据结构的步骤: 一、导入必要的库: import scanpy as sc二、读取 AnnData 对象: 假设你的 AnnData 对象存储在一个文件中,例如 adata.h5ad,你可以使用以下代码读取它: adata = sc.read(adata.h5ad)如果你已经有了 adata 对象…...
《CPython Internals》阅读笔记:p232-p249
《CPython Internals》学习第 13天,p232-p249 总结,总计 18 页。 一、技术总结 无。 二、英语总结(生词:1) 1.overhead (1)overhead: over-(“above”) head(“top part, uppermost section”) overhead的字面意思是:above…...
Java并发08 - 并发安全容器详解
并发容器详解 文章目录 并发容器详解一:不使用并发容器如何保证安全二:阻塞队列容器2:ArrayBlockingQueue2.1:内部成员2.2:put方法的实现2.3:take方法的实现 3:LinkedBlockingQueue3.1ÿ…...
抽奖系统(3——奖品模块)
1. 图片上传 application.properties 配置上传文件路径 ## 文件上传 ## # 目标路径 pic.local-pathD:/PIC # spring boot3 升级配置名 spring.web.resources.static-locationsclasspath:/static/,file:${pic.local-path} tip: 1. 如果访问的是本地路径,…...
36.centos7上安装python3.6.5、安装卸载依赖包
查看openssl的版本号,默认python3.6.5需要OpenSSL 1.0.2以上的版本支持。 监测安装好的python,是否可以正确导入ssl和_ssl包 pip3安装依赖包 通过Pycharm工具导出requirements.txt文件 查看/usr/bin/目录下的软连接 pip3, python...
微透镜阵列精准全检,白光干涉3D自动量测方案提效70%
广泛应用的微透镜阵列 微透镜是一种常见的微光学元件,通过设计微透镜,可对入射光进行扩散、光束整形、光线均分、光学聚焦、集成成像等调制,进而实现许多传统光学元器件难以实现的特殊功能。 微透镜阵列(Microlens Array&#x…...
nature genetics | scATAC-seq预测scRNA-seq,识别影响基因表达的新染色质区域
–https://doi.org/10.1038/s41588-024-01689-8 Single-cell multi-ome regression models identify functional and disease-associated enhancers and enable chromatin potential analysis 研究团队和单位 Christina S. Leslie–Memorial Sloan Kettering Cancer Center …...
简述mysql 主从复制原理及其工作过程,配置一主两从并验证。
MySQL 主从同步是一种数据库复制技术,它通过将主服务器上的数据更改复制到一个或多个从服务器,实现数据的自动同步。 主从同步的核心原理是将主服务器上的二进制日志复制到从服务器,并在从服务器上执行这些日志中的操作。 MySQL主从同步是基…...
Java API:封装自定义响应类
本文介绍 Web 服务开发中自定义响应,涵盖标准 HTTP 响应状态码局限性、自定义响应价值、设计原则与实现、在 Spring Boot 项目应用、与其他响应格式对比总结及应用场景。 1. 标准HTTP响应与自定义响应 1.1标准HTTP响应状态码 在 Web 服务开发中,HTTP…...
【Unity3D】利用Hinge Joint 2D组件制作绳索效果
目录 一、动态绳索 (可移动根节点) 二、静态绳索 三、利用Skinning Editor(Unity2022.3.15f1正常使用) 四、注意事项 一、动态绳索 (可移动根节点) 动态绳索 DynamicRope空物体 Anchor和whitecircle是相同位置的物体ÿ…...
vim练级攻略(精简版)
vim推荐配置: curl -sLf https://gitee.com/HGtz2222/VimForCpp/raw/master/install.sh -o ./install.sh && bash ./install.sh 0. 规定 Ctrl-λ 等价于 <C-λ> :command 等价于 :command <回车> n 等价于 数字 blank字符 等价于 空格,tab&am…...
嵌入式硬件篇---PID控制
文章目录 前言第一部分:连续PID1.比例(Proportional,P)控制2.积分(Integral,I)控制3.微分(Derivative,D)控制4.PID的工作原理5..实质6.分析7.各种PID控制器P控…...
技术洞察:C++在后端开发中的前沿趋势与社会影响
文章目录 引言C在后端开发中的前沿趋势1. 高性能计算的需求2. 微服务架构的兴起3. 跨平台开发的便利性 跨领域技术融合与创新实践1. C与人工智能的结合2. C与区块链技术的融合 C对社会与人文的影响1. 提升生产力与创新能力2. 促进技术教育与人才培养3. 技术与人文的深度融合 结…...
C语言程序设计之小系统
🌟 嗨,我是LucianaiB! 🌍 总有人间一两风,填我十万八千梦。 🚀 路漫漫其修远兮,吾将上下而求索。 目录 系统说明 1.1 系统概述 1.2 功能模块总体设计详细设计 3.1 程序中使用的函数 3.2各类问…...
pyinstaller : 无法将“pyinstaller”项识别为 cmdlet、函数、脚本文件或可运行程序的名称。
pyinstaller : 无法将“pyinstaller”项识别为 cmdlet、函数、脚本文件或可运行程序的名称。请检查名称的拼写,如果包括路径,请确保路径正确,然后再试一次。 所在位置 行:1 字符: 1pyinstaller --onefile --windowed 过年烟花.py~~~~~~~~~~~ …...
接口传参 data格式和json格式区别是什么
接口传参 data格式和json格式区别是什么 以下是接口传参 data 格式和 JSON 格式的区别: 定义和范围 Data 格式: 是一个较为宽泛的概念,它可以指代接口传递参数时所使用的任何数据的组织形式。包括但不限于 JSON、XML、Form 数据、纯文本、二进…...
ClickHouse 入门
简介 ClickHouse 是一个列式数据库,传统的数据库一般是按行存储,而ClickHouse则是按列存储,每一列都有自己的存储空间,并且只存储该列的数值,而不是存储整行的数据。这样做主要有几个好处,压缩率高&#x…...
Python自动化:基于faker批量生成模拟数据(以电商行业销售数据为例)
引言:个人认为,“造数据”是一个数据分析师的一项基本技能,当然啦,“造数据”不是说胡编乱造,而是根据自己的需求去构造一些模拟数据集,用于测试等用途,而且使用虚拟数据不用担心数据隐私和安全…...
3.3 OpenAI GPT-4, GPT-3.5, GPT-3 模型调用:开发者指南
OpenAI GPT-4, GPT-3.5, GPT-3 模型调用:开发者指南 OpenAI 的 GPT 系列语言模型,包括 GPT-4、GPT-3.5 和 GPT-3,已经成为自然语言处理领域的标杆。无论是文本生成、对话系统,还是自动化任务,开发者都可以通过 API 调用这些强大的模型来增强他们的应用。本文将为您详细介…...
【Spring Boot】掌握 Spring 事务:隔离级别与传播机制解读与应用
前言 🌟🌟本期讲解关于spring 事务传播机制介绍~~~ 🌈感兴趣的小伙伴看一看小编主页:GGBondlctrl-CSDN博客 🔥 你的点赞就是小编不断更新的最大动力 🎆那么废话…...
力扣203题—— 移除链表元素
题目 递归法使用 if(headnull){return null; }//假设remove返回后面已经去掉val值的链表 我们用head.next去存放他,接着我们要判断此时head head值是否等于val,如果等于我们就返回后继元素即可 head.nextremove(head.next,val); if(head.valval){return…...
Express中间件
目录 Express中间件 中间件的概念 next函数 全局中间与局部中间件 多个中间件 中间的5个注意事项 中间的分类 应用级中间件 路由级中间件 错误级中间件 Express内置中间件 express.json express.urlencoded 第三方中间件编辑 自定义中间件 Express中间件 中间…...
【AIGC】SYNCAMMASTER:多视角多像机的视频生成
标题:SYNCAMMASTER: SYNCHRONIZING MULTI-CAMERA VIDEO GENERATION FROM DIVERSE VIEWPOINTS 主页:https://jianhongbai.github.io/SynCamMaster/ 代码:https://github.com/KwaiVGI/SynCamMaster 文章目录 摘要一、引言二、使用步骤2.1 TextT…...
模块化架构与微服务架构,哪种更适合桌面软件开发?
前言 在现代软件开发中,架构设计扮演着至关重要的角色。两种常见的架构设计方法是模块化架构与微服务架构。它们各自有独特的优势和适用场景,尤其在C#桌面软件开发领域,模块化架构往往更加具有实践性。本文将对这两种架构进行对比࿰…...
Ubuntu 24.04 LTS 安装 tailscale 并访问 SMB共享文件夹
Ubuntu 24.04 LTS 安装 tailscale 安装 Tailscale 官方仓库 首先,确保系统包列表是最新的: sudo apt update接下来,安装 Tailscale 所需的仓库和密钥: curl -fsSL https://tailscale.com/install.sh | sh这会自动下载并安装 …...
fgets、scanf存字符串应用
题目1 夺旗(英语:Capture the flag,简称 CTF)在计算机安全中是一种活动,当中会将“旗子”秘密地埋藏于有目的的易受攻击的程序或网站。参赛者从其他参赛者或主办方偷去旗子。 非常崇拜探姬的小学妹最近迷上了 CTF&am…...
C#高级:用Csharp操作鼠标和键盘
一、winform 1.实时获取鼠标位置 public Form1() {InitializeComponent();InitialTime(); }private void InitialTime() {// 初始化 Timer 控件var timer new System.Windows.Forms.Timer();timer.Interval 100; // 设置为 100 毫秒,即每 0.1 秒更新一次timer.…...
关于AI agent的学术论文实验部分:准确率,响应时间,用户满意度
关于AI agent的学术论文实验部分 在撰写关于AI agent的学术论文时,实验设计和实施是关键部分,仅搭建完成AI agent通常是不够的,需要通过严谨的实验来验证其性能、效果和创新性。以下以一个在智能客服场景中应用AI agent的例子,说明如何完成实验: 明确实验目的:确定通过实…...
消息队列实战指南:三大MQ 与 Kafka 适用场景全解析
前言:在当今数字化时代,分布式系统和大数据处理变得愈发普遍,消息队列作为其中的关键组件,承担着系统解耦、异步通信、流量削峰等重要职责。ActiveMQ、RabbitMQ、RocketMQ 和 Kafka 作为市场上极具代表性的消息队列产品࿰…...
postgresql表分区及测试
本文主要采用list类型实现表分区,并对表分区数据进行查询对比,数据量6000万条以上,速度相差10倍以上。 一、创建表,以substationcode字段为ist类型表分区 CREATE TABLE "public"."d_population_partition" …...
VUE学习笔记(入门)1__创建VUE实例
核心步骤 <div id"app"><!-- 这里存放渲染逻辑代码 --><h1>{{ msg }}</h1><a href"#">{{count}}</a> </div><!-- 引入在线的开发版本核心包 --> <!-- 引入核心包后全局可使用VUE构造函数 --> <…...
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的…...
pthread_create函数
函数原型 pthread_create 是 POSIX 线程(pthread)库中的一个函数,用于在程序中创建一个新线程。 #include <pthread.h>int pthread_create(pthread_t *thread, const pthread_attr_t *attr,void *(*start_routine) (void *), void *a…...
suctf2025
Suctf2025 --2标识为看的wp,没环境复现了 所有参考资料将在文本末尾标明 WEB SU_photogallery 思路👇 构造一个压缩包,解压出我们想解压的部分,然后其他部分是损坏的,这样是不是就可以让整个解压过程是出错的从而…...
二、点灯基础实验
嵌入式基础实验第一个就是点灯,地位相当于编程界的hello world。 如下为LED原理图,要让相应LED发光,需要给I/O口设置输出引脚,低电平,二极管才会导通 2.1 打开初始工程,编写代码 以下会实现BLINKY常亮&…...
ESP8266-01S、手机、STM32连接
1、ESP8266-01S的工作原理 1.1、AP和STA ESP8266-01S为WIFI的透传模块,主要模式如下图: 上节说到,我们需要用到AT固件进行局域网应用(ESP8266连接的STM32和手机进行连接)。 ESP8266为一个WiFi透传模块,和…...
微服务学习:基础理论
一、微服务和应用现代化 1、时代的浪潮,企业的机遇和挑战 在互联网化数字化智能化全球化的当今社会,IT行业也面临新的挑战: 【快】业务需求如“滔滔江水连绵不绝”,企业需要更快的交付【变】林子大了,百色用户&…...
【c++继承篇】--继承之道:在C++的世界中编织血脉与传承
目录 引言 一、定义二、继承定义格式2.1定义格式2.2继承关系和访问限定符2.3继承后子类访问权限 三、基类和派生类赋值转换四、继承的作用域4.1同名变量4.2同名函数 五、派生类的默认成员构造函数5.1**构造函数调用顺序:**5.2**析构函数调用顺序:**5.3调…...
Java操作Excel导入导出——POI、Hutool、EasyExcel
目录 一、POI导入导出 1.数据库导出为Excel文件 2.将Excel文件导入到数据库中 二、Hutool导入导出 1.数据库导出为Excel文件——属性名是列名 2.数据库导出为Excel文件——列名起别名 3.从Excel文件导入数据到数据库——属性名是列名 4.从Excel文件导入数据到数据库…...
基于VSCODE+GDB+GDBSERVER远程单步调试设备篇(可视化界面)
目录 说明 配置方法 1)VSCODE必备插件 2)配置launch.json文件,用于GDB调试 调试步骤 目标板运行程序 1)已启动程序,通过attach方式进入调试 2)通过gdbserver启动时加载程序(程序路径根据实际情…...
【设计模式】 单例模式(单例模式哪几种实现,如何保证线程安全,反射破坏单例模式)
单例模式 作用:单例模式的核心是保证一个类只有一个实例,并且提供一个访问实例的全局访问点。 实现方式优缺点饿汉式线程安全,调用效率高 ,但是不能延迟加载懒汉式线程安全,调用效率不高,能延迟加载双重检…...
lvm快照备份
前提 数据文件要在逻辑卷上; 此逻辑卷所在卷组必须有足够空间使用快照卷; 数据文件和事务日志要在同一个逻辑卷上; 前提:MySQL数据lv和将要创建的快照要在同一vg,vg要有足够的空间存储 优点 几乎是热备&…...
PHP CRM售后系统小程序
💼 CRM售后系统 📺这是一款基于PHP和uniapp深度定制的CRM售后管理系统,它犹如企业的智慧核心,精准赋能销售与售后管理的每一个环节,引领企业步入精细化、数字化的全新管理时代。系统集成了客户管理、合同管理、工单调…...
ETL 数据抽取
ETL ETL 数据抽取 ETL(Extract, Transform, Load)是数据集成和处理的重要过程,其中数据抽取(Extract)是第一步,负责从各种数据源中提取数据。以下是ETL数据抽取的详细说明和常用工具: 1. 数据…...
FANUC机器人系统镜像备份与恢复的具体步骤(图文)
FANUC机器人系统镜像备份与恢复的具体步骤(图文) 镜像备份: 如下图所示,进入文件—工具—切换设备,找到插入的U盘UT1, 如下图所示,进入U盘目录后,创建目录,这里目录名称为11, 如下图所示...