• 手撕 视觉slam14讲 ch7 / pose_estimation_3d2d.cpp (2)


    上一篇文章中: 手撕ch7/pose_estimation_3d2d(1),我们调用了epnp的方法进行位姿估计,这里我们使用非线性优化的方法来求解位姿,使用g2o进行BA优化

    首先介绍g2o:可参考:g2o详细介绍

    1.构建g2o图优化思路:

    • 步骤一: 创建线性方程求解器,确定分解方法
    1. // 每个误差项优化变量维度为3,误差值维度为1
    2. typedef g2o::BlockSolver< g2o::BlockSolverTraits<3,1> > Block;
    3. // 创建一个线性求解器 LinearSolver,采用 dense cholesky 分解法
    4. Block::LinearSolverType* linearSolver
    5. = new g2o::LinearSolverDense();
    • 步骤二: 构造线性方程的矩阵块,并用上面定义的线性求解器初始化
    Block* solver_ptr = new Block( linearSolver );
    

    BlockSolver 内部包含 LinearSolver,用上面定义的线性求解器 LinearSolver 来初始化,前面已经给定了优化变量的维度;

    • 步骤三: 创建总求解器 solver,并从 GN, LM, DogLeg 中选一个,再用上述块求解器 BlockSolver 初始化
    1. g2o::OptimizationAlgorithmLevenberg* solver =
    2. new g2o::OptimizationAlgorithmLevenberg( solver_ptr );
    • 步骤四: 创建稀疏优化器(SparseOptimizer)
    1. g2o::SparseOptimizer optimizer; // 图模型
    2. optimizer.setAlgorithm( solver ); // 用前面定义好的求解器作为求解方法:
    3. optimizer.setVerbose( true ); // 打开调试输出
    • 步骤五: 定义图的顶点和边,并添加到 SparseOptimizer 优化器中
    1. // 创建一个顶点
    2. CurveFittingVertex* v = new CurveFittingVertex();
    3. // 初始化顶点的值
    4. v->setEstimate( Eigen::Vector3d(0,0,0) );
    5. // 设置顶点的编号
    6. v->setId(0);
    7. // 向图中添加顶点
    8. optimizer.addVertex( v );
    9. for ( int i=0; i// 往图中增加边
    10. {
    11. // 创建一条边
    12. CurveFittingEdge* edge = new CurveFittingEdge( x_data[i] );
    13. // 设置边的 id
    14. edge->setId(i);
    15. // 设置边连接的顶点
    16. edge->setVertex( 0, v );
    17. // 设置观测数值
    18. edge->setMeasurement( y_data[i] );
    19. // 设置信息矩阵:协方差矩阵之逆
    20. edge->setInformation( Eigen::Matrix<double,1,1>::Identity()*1/(w_sigma*w_sigma) );
    21. // 将边添加到图中
    22. optimizer.addEdge( edge );
    23. }
    •  步骤六: 设置优化参数,开始执行优化
    1. optimizer.initializeOptimization();
    2. optimizer.optimize(100); // 迭代次数
    对应原文完整代码如下:
    1. void bundleAdjustmentG2O(
    2. const VecVector3d &points_3d,
    3. const VecVector2d &points_2d,
    4. const Mat &K,
    5. Sophus::SE3d &pose) {
    6. // 步骤一:构建图优化,先设定g2o
    7. typedef g2o::BlockSolver6, 3>> BlockSolverType; // pose is 6, landmark is 3
    8. //步骤二: 线性求解器类型
    9. typedef g2o::LinearSolverDense LinearSolverType;
    10. //步骤三: 梯度下降方法,可以从GN, LM, DogLeg 中选
    11. auto solver = new g2o::OptimizationAlgorithmGaussNewton(
    12. g2o::make_unique(g2o::make_unique()));
    13. //步骤四: 创建稀疏优化器
    14. g2o::SparseOptimizer optimizer; // 图模型
    15. optimizer.setAlgorithm(solver); // 设置求解器
    16. optimizer.setVerbose(true); // 打开调试输出
    17. //步骤五: 定义图的顶点和边
    18. // vertex 定义顶点
    19. VertexPose *vertex_pose = new VertexPose(); // 定义 相机位姿 为顶点
    20. vertex_pose->setId(0);// 设置顶点的编号
    21. vertex_pose->setEstimate(Sophus::SE3d());// 初始化顶点的值
    22. optimizer.addVertex(vertex_pose);// 向图中添加顶点
    23. // K 相机内参
    24. Eigen::Matrix3d K_eigen;
    25. K_eigen <<
    26. K.at<double>(0, 0), K.at<double>(0, 1), K.at<double>(0, 2),
    27. K.at<double>(1, 0), K.at<double>(1, 1), K.at<double>(1, 2),
    28. K.at<double>(2, 0), K.at<double>(2, 1), K.at<double>(2, 2);
    29. // edges 定义 边
    30. int index = 1;
    31. // 往图中增加边
    32. for (size_t i = 0; i < points_2d.size(); ++i) {
    33. auto p2d = points_2d[i];
    34. auto p3d = points_3d[i];
    35. EdgeProjection *edge = new EdgeProjection(p3d, K_eigen);// 创建一条边
    36. edge->setId(index);// 设置边的 id
    37. edge->setVertex(0, vertex_pose);// 设置边连接的顶点
    38. edge->setMeasurement(p2d); // 设置观测数值
    39. edge->setInformation(Eigen::Matrix2d::Identity());// 设置信息矩阵:协方差矩阵之逆
    40. optimizer.addEdge(edge);// 将边添加到图中
    41. index++;
    42. }
    43. //步骤六:设置优化参数,开始优化
    44. chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
    45. optimizer.setVerbose(true);
    46. optimizer.initializeOptimization();// 设置优化初始值
    47. optimizer.optimize(10);// 迭代次数
    48. chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
    49. chrono::duration<double> time_used = chrono::duration_castdouble>>(t2 - t1);
    50. cout << "optimization costs time: " << time_used.count() << " seconds." << endl;
    51. cout << "pose estimated by g2o =\n" << vertex_pose->estimate().matrix() << endl;
    52. pose = vertex_pose->estimate();
    53. }

    其中我们需要关注如何定义顶点(Vertex)和边(edge)

    2. 顶点(Vertex):

    g2o 提供了一个比较通用的适合大多数情况的模板类 BaseVertex,其中D 是 int 类型,表示顶点 Vertex 的最小维度,比如 3D 空间中旋转是 3 维的,那么这里 D=3;
    但是在源码注释中说 D 并非是顶点(更确切的说是状态变量)的维度,而是其在流形空间(manifold)的最小表示(SO3->so3,SE3->se3).

    T 是待估计 Vertex 的数据类型,比如用四元数表达三维旋转的话,T 就是 Quaternion 类型

    我们自定义一个顶点需要重写以下函数

    1. class myVertex: public g2::BaseVertex
    2. {
    3. public:
    4. // 类成员变量如果是固定大小对象需要加上以下的宏定义
    5. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
    6. // 构造函数
    7. myVertex(){}
    8. // 读写函数
    9. virtual void read(std::istream& is) {}
    10. virtual void write(std::ostream& os) const {}
    11. // 重置函数
    12. virtual void setOriginImpl()
    13. {
    14. _estimate = Type();
    15. }
    16. // 更新函数
    17. virtual void oplusImpl(const double* update) override
    18. {
    19. _estimate += /*update*/;
    20. }
    21. }
    对应原文代码:
    1. class VertexPose : public g2o::BaseVertex<6, Sophus::SE3d> { //优化变量是 6 自由度的李代数
    2. public:
    3. EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
    4. //重置,设定被优化变量的原始值
    5. virtual void setToOriginImpl() override {
    6. _estimate = Sophus::SE3d();
    7. }
    8. /// left multiplication on SE3 //更新
    9. virtual void oplusImpl(const double *update) override {
    10. Eigen::Matrix<double, 6, 1> update_eigen;
    11. update_eigen << update[0], update[1], update[2], update[3], update[4], update[5];
    12. _estimate = Sophus::SE3d::exp(update_eigen) * _estimate; // 左乘更新 SE3 - 旋转矩阵R
    13. }
    14. virtual bool read(istream &in) override {} //存盘
    15. virtual bool write(ostream &out) const override {}//读盘
    16. };

    3. 边(edge)

    我们一般使用的类是 BaseUnaryEdge,BaseBinaryEdge,BaseMultiEdge 分别表示一元边,两元边,多元边(位于 g2o/g2o/core/base_edge.h 中),类似于顶点,他们又继承自OptimizableGraph::Edge (位于 g2o/g2o/core/optimizable_graph.h 中),hyper_graph::Edge(位于g2o/g2o/core/hyper_graph.h 中)

    一元边表示只连接一个顶点,二元边表示连接两个顶点,多元边表示连接 3 个或以上顶点。

    主要参数有:D, E, VertexXi, VertexXj

    • D 是 int 型,表示测量值的维度;
    • E 表示测量值的数据类型;
    • VertexXi,VertexXj 分别表示不同顶点的类型。

    自定义边需要重写以下成员函数:最重要的是误差计算函数computeError(),计算雅克比矩阵linearizeOplus() 两个函数

    1. class myEdge: public g2o::BaseBinaryEdge
    2. {
    3. public:
    4. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
    5. myEdge(){}
    6. // 读写函数
    7. virtual bool read(istream& in) {}
    8. virtual bool write(ostream& out) const {}
    9. // 误差计算函数
    10. virtual void computeError() override
    11. {
    12. // ...
    13. _error = _measurement - Something;
    14. }
    15. // 计算雅克比矩阵
    16. virtual void linearizeOplus() override
    17. {
    18. _jacobianOplusXi(pos, pos) = something;
    19. // ...
    20. /*
    21. _jocobianOplusXj(pos, pos) = something;
    22. ...
    23. */
    24. }
    25. private:
    26. // data
    27. }
    对应原文代码:
    1. // 仅估计位姿的一元边
    2. class EdgeProjection : public g2o::BaseUnaryEdge<2, Eigen::Vector2d, VertexPose> {
    3. public:
    4. EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
    5. //构造函数
    6. EdgeProjection(const Eigen::Vector3d &pos, const Eigen::Matrix3d &K) : _pos3d(pos), _K(K) {}
    7. // 误差计算函数
    8. virtual void computeError() override {
    9. const VertexPose *v = static_cast (_vertices[0]);
    10. Sophus::SE3d T = v->estimate();
    11. Eigen::Vector3d pos_pixel = _K * (T * _pos3d);//将3D世界坐标转为相机像素坐标
    12. pos_pixel /= pos_pixel[2];
    13. _error = _measurement - pos_pixel.head<2>(); //误差=测量值-投影得到的值
    14. }
    15. // 计算雅克比矩阵
    16. virtual void linearizeOplus() override {
    17. const VertexPose *v = static_cast (_vertices[0]);
    18. Sophus::SE3d T = v->estimate();
    19. Eigen::Vector3d pos_cam = T * _pos3d;//相机坐标系下空间点的坐标=相机位姿 * 空间点的坐标
    20. double fx = _K(0, 0);
    21. double fy = _K(1, 1);
    22. double cx = _K(0, 2);
    23. double cy = _K(1, 2);
    24. double X = pos_cam[0];
    25. double Y = pos_cam[1];
    26. double Z = pos_cam[2];
    27. double Z2 = Z * Z;
    28. // 2*6的雅克比矩阵
    29. _jacobianOplusXi
    30. << -fx / Z, 0, fx * X / Z2, fx * X * Y / Z2, -fx - fx * X * X / Z2, fx * Y / Z,
    31. 0, -fy / Z, fy * Y / (Z * Z), fy + fy * Y * Y / Z2, -fy * X * Y / Z2, -fy * X / Z;
    32. }
    33. //读写操作
    34. virtual bool read(istream &in) override {}
    35. virtual bool write(ostream &out) const override {}
    36. private:
    37. Eigen::Vector3d _pos3d;
    38. Eigen::Matrix3d _K;
    39. };

  • 相关阅读:
    【PTA-训练day10】L2-022 重排链表 + L1-043 阅览室
    STM32CubeMX教程31 USB_DEVICE - HID外设_模拟键盘或鼠标
    非零基础自学Java (老师:韩顺平) 第2章 Java概述 2.1 2.1 什么是程序——2.14 老韩聊 如何快速掌握技术或知识点
    对GROUP BY的增强
    使用KiCad插件,将PCB焊接可视化
    分布式机器学习(Parameter Server)
    心理学杂文
    解决Maven打包Nacos时插件报错
    Visual Studio 2022下载安装及使用教程
    ajax,axios,fetch
  • 原文地址:https://blog.csdn.net/weixin_62952541/article/details/133893035