前言
以高翔的《视觉SLAM14讲》中的 g2o 拟合曲线为例,讲解 g2o 的使用。源文件为 g2oCurveFitting.cpp。
拟合非线性函数的曲线 y=e^{ax^2+bx+c}(其中,a = 1、b = 2、c = 1 ,待拟合数据点:[ 0 , 1 ] 之间均匀生成的100个数据点,加上方差为1的白噪声)
注意:①新版 g2o 的源码相对于旧版有所改动。总体来说,差别在 BlockSolver 的接口由裸指针变成了 unique_ptr、VertexSBAPointXYZ 类被删除等。具体可以看:SLAM十四讲ch7代码调整(undefined reference to symbol)。
②本文介绍的 g2o 编程框架是分块进行的,也可以通过工厂函数类 OptimizationAlgorithmFactory 直接生成固定搭配的优化算法。
#include <iostream>
#include <g2o/core/g2o_core_api.h>
#include <g2o/core/base_vertex.h>
#include <g2o/core/base_unary_edge.h>
#include <g2o/core/block_solver.h>
#include <g2o/core/optimization_algorithm_levenberg.h>
#include <g2o/core/optimization_algorithm_gauss_newton.h>
#include <g2o/core/optimization_algorithm_dogleg.h>
#include <g2o/solvers/dense/linear_solver_dense.h>
#include <Eigen/Core>
#include <opencv2/core/core.hpp>
#include <cmath>
#include <chrono>
using namespace std;
// 曲线模型的顶点,模板参数:优化变量维度和数据类型
class CurveFittingVertex : public g2o::BaseVertex<3, Eigen::Vector3d> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// 重置
virtual void setToOriginImpl() override {
_estimate << 0, 0, 0;
}
// 更新
virtual void oplusImpl(const double *update) override {
_estimate += Eigen::Vector3d(update);
}
// 存盘和读盘:留空
virtual bool read(istream &in) {}
virtual bool write(ostream &out) const {}
};
// 误差模型 模板参数:观测值维度,类型,连接顶点类型
class CurveFittingEdge : public g2o::BaseUnaryEdge<1, double, CurveFittingVertex> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
CurveFittingEdge(double x) : BaseUnaryEdge(), _x(x) {}
// 计算曲线模型误差
virtual void computeError() override {
const CurveFittingVertex *v = static_cast<const CurveFittingVertex *> (_vertices[0]);
const Eigen::Vector3d abc = v->estimate();
_error(0, 0) = _measurement - std::exp(abc(0, 0) * _x * _x + abc(1, 0) * _x + abc(2, 0));
}
// 计算雅可比矩阵
virtual void linearizeOplus() override {
const CurveFittingVertex *v = static_cast<const CurveFittingVertex *> (_vertices[0]);
const Eigen::Vector3d abc = v->estimate();
double y = exp(abc[0] * _x * _x + abc[1] * _x + abc[2]);
_jacobianOplusXi[0] = -_x * _x * y;
_jacobianOplusXi[1] = -_x * y;
_jacobianOplusXi[2] = -y;
}
virtual bool read(istream &in) {}
virtual bool write(ostream &out) const {}
public:
double _x; // x 值, y 值为 _measurement
};
int main(int argc, char **argv) {
double ar = 1.0, br = 2.0, cr = 1.0; // 真实参数值
double ae = 2.0, be = -1.0, ce = 5.0; // 估计参数值
int N = 100; // 数据点
double w_sigma = 1.0; // 噪声Sigma值
double inv_sigma = 1.0 / w_sigma;
cv::RNG rng; // OpenCV随机数产生器
vector<double> x_data, y_data; // 数据
for (int i = 0; i < N; i++) {
double x = i / 100.0;
x_data.push_back(x);
y_data.push_back(exp(ar * x * x + br * x + cr) + rng.gaussian(w_sigma * w_sigma));
}
// 构建图优化,先设定g2o
typedef g2o::BlockSolver<g2o::BlockSolverTraits<3, 1>> my_BlockSolverType; // 每个误差项优化变量维度为3,误差值维度为1
typedef g2o::LinearSolverDense<my_BlockSolverType::PoseMatrixType> my_LinearSolverType; // 线性求解器类型
// 梯度下降方法,可以从GN, LM, DogLeg 中选
auto solver = new g2o::OptimizationAlgorithmGaussNewton(
g2o::make_unique<my_BlockSolverType>(g2o::make_unique<my_LinearSolverType>()));
g2o::SparseOptimizer optimizer; // 图模型
optimizer.setAlgorithm(solver); // 设置求解器
optimizer.setVerbose(true); // 打开调试输出
// 往图中增加顶点
CurveFittingVertex *v = new CurveFittingVertex();
v->setEstimate(Eigen::Vector3d(ae, be, ce));
v->setId(0);
optimizer.addVertex(v);
// 往图中增加边
for (int i = 0; i < N; i++) {
CurveFittingEdge *edge = new CurveFittingEdge(x_data[i]);
edge->setId(i);
edge->setVertex(0, v); // 设置连接的顶点
edge->setMeasurement(y_data[i]); // 观测数值
edge->setInformation(Eigen::Matrix<double, 1, 1>::Identity() * 1 / (w_sigma * w_sigma)); // 信息矩阵:协方差矩阵之逆
optimizer.addEdge(edge);
}
// 执行优化
cout << "start optimization" << endl;
chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
optimizer.initializeOptimization();
optimizer.optimize(10);
chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
chrono::duration<double> time_used = chrono::duration_cast<chrono::duration<double>>(t2 - t1);
cout << "solve time cost = " << time_used.count() << " seconds. " << endl;
// 输出优化值
Eigen::Vector3d abc_estimate = v->estimate();
cout << "estimated model: " << abc_estimate.transpose() << endl;
return 0;
}
其中
// 构建图优化,先设定g2o
typedef g2o::BlockSolver<g2o::BlockSolverTraits<3, 1>> my_BlockSolverType; // 每个误差项优化变量维度为3,误差值维度为1
typedef g2o::LinearSolverDense<my_BlockSolverType::PoseMatrixType> my_LinearSolverType; // 线性求解器类型
// 梯度下降方法,可以从GN, LM, DogLeg 中选
auto solver = new g2o::OptimizationAlgorithmGaussNewton(
g2o::make_unique<my_BlockSolverType>(g2o::make_unique<my_LinearSolverType>()));
可以替换为
// 构建图优化,先设定g2o
typedef g2o::BlockSolver<g2o::BlockSolverTraits<3, 1>> my_BlockSolverType; // 每个误差项优化变量维度为3,误差值维度为1
std::unique_ptr<my_BlockSolverType::LinearSolverType> linearSolver(new g2o::LinearSolverDense<my_BlockSolverType::PoseMatrixType>());
std::unique_ptr<my_BlockSolverType> solver_ptr(new my_BlockSolverType(std::move(linearSolver)));
g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(std::move(solver_ptr));
一、g2o 编程框架
SparseOptimizer 包含一个OptimizationAlgorithm(优化算法)的对象。OptimizationAlgorithm 继承自 OptimizationWithHessian 。其中迭代策略可以从Gauss-Newton(高斯牛顿法,简称GN), Levernberg-Marquardt(简称LM法), Powell's dogleg 中选择。
OptimizationWithHessian 内部包含一个Solver(求解器),这个 Solver 实际继承自BlockSolver 。这个 BlockSolver 有两个部分,一部分是 SparseBlockMatrix<T> ,用于计算稀疏的雅可比和 Hessian 矩阵;另一部分是 LinearSolver(线性求解器),它用于计算迭代过程中最关键的一步 HΔx=−b,LinearSolver 有几种方法可以选择:PCG(预条件共轭梯度), CSparse, Choldmod(Cholesky 分解) 。
- ①创建 线性求解器 LinearSolver
增量方程的形式是:H△X=-b,通常情况下通过直接求逆,也就是△X=-H.inv * b 的方式求解 △X。但当 H 的维度较大时,矩阵求逆变得很困难,求解问题也变得很复杂。此时需要一些特殊的方法对矩阵进行求逆,在 g2o 中主要有以下几种线性求解方法:
//***g2o源码***//
// 使用sparse cholesky分解法
LinearSolverCholmod : public LinearSolverCCS<MatrixType>;
// 使用CSparse法
LinearSolverCSparse : public LinearSolverCCS<MatrixType>;
// 依赖项只有eigen,使用eigen中sparse Cholesky求解,因此编译好后可以方便的在其他地方使用,性能和CSparse差不多
LinearSolverEigen : public LinearSolverCCS<MatrixType>;
// 使用dense cholesky分解法
LinearSolverDense : public LinearSolver<MatrixType>
// 使用preconditioned conjugate gradient 法
LinearSolverPCG : public LinearSolver<MatrixType>
- ②创建 块求解器 BlockSolver。并用上面定义的 线性求解器 初始化 块求解器
BlockSolver 有两种定义方式。一种是固定尺寸的 BlockSolver
//***g2o源码 g2o/g2o/core/block_solver.h ***//
// p:PoseDim 位姿的维度
// l:LandmarkDim 路标点的维度
template<int p, int l>
using BlockSolverPL = BlockSolver< BlockSolverTraits<p, l> >;
另一种是可变尺寸的 BlockSolver
//***g2o源码 g2o/g2o/core/block_solver.h ***//
//variable size solver
using BlockSolverX = BlockSolverPL<Eigen::Dynamic, Eigen::Dynamic>;
在某些应用场景中,位姿和路标点在程序开始时并不能被确定,此时块求解器就没办法固定尺寸,应该使用可变尺寸的 BlockSolver,以便让所有的参数都在中间过程中被确定。
在块求解器头文件 block_solver.h 的最后,预定义了比较常用的几种类型,如下所示:
//***g2o源码 g2o/g2o/core/block_solver.h ***//
// 表示 pose 是 6 维,观测点是 3 维。用于 3D SLAM 中的 BA
// solver for BA/3D SLAM
using BlockSolver_6_3 = BlockSolverPL<6, 3>;
// 在 BlockSolver_6_3 的基础上多了一个 scale
// solver fo BA with scale
using BlockSolver_7_3 = BlockSolverPL<7, 3>;
// 表示 pose 是 3 维,观测点是 2 维
// 2Dof landmarks 3Dof poses
using BlockSolver_3_2 = BlockSolverPL<3, 2>;
注意:虽然是先创建 线性求解器 LinearSolver,再创建 块求解器 BlockSolver,但在实际使用中,创建 线性求解器 时要传入 Hessian 矩阵的类型,Hessian 矩阵的类型可由 my_BlockSolverType::PoseMatrixType 确定,所以一般在创建 线性求解器 前 先创建 块求解器类型。如下所示:
//***高翔代码***//
// g2o::BlockSolver 是一个模板类,用于定义优化问题的 块求解器。它接受一个 g2o::BlockSolverTraits 模板参数。
typedef g2o::BlockSolver<g2o::BlockSolverTraits<p, l>> my_BlockSolverType; // 块求解器类型
// PoseMatrixType 是从 my_BlockSolverType 中提取的位姿矩阵类型,专门用于处理和表示位姿相关的矩阵。PoseMatrixType 是一个方阵,大小为 PoseDim x PoseDim。
// g2o::LinearSolverDense 是一个模板类,用于定义优化问题的 线性求解器,它使用 使用 dense cholesky 分解法 求解矩阵的逆。它接受一个模版参数,表示 H 矩阵的类型,即 PoseMatrixType。
typedef g2o::LinearSolverDense<my_BlockSolverType::PoseMatrixType> my_LinearSolverType; // 线性求解器类型
- ③创建 总求解器 solver。并从GN, LM, DogLeg 中选择迭代策略,再用上述定义的 块求解器初始化 总求解器
g2o/g2o/core/ 目录下,Solver 的优化方法有三种:分别是高斯牛顿(GaussNewton)法,LM(Levenberg–Marquardt)法、Dogleg法
//***g2o源码 g2o/g2o/core/optimization_algorithm_gauss_newton.h ***//
// Gauss Newton 法
g2o::OptimizationAlgorithmGaussNewton(std::unique_ptr<Solver> solver)
// Levenberg–Marquardt 法
g2o::OptimizationAlgorithmLevenberg(std::unique_ptr<Solver> solver)
// Dogleg 法
g2o::OptimizationAlgorithmDogleg(std::unique_ptr<Solver> solver)
// 其中 solver 为 块求解器
实际创建 总求解器 solver 的创建如下所示:
//***高翔代码***//
auto solver = new g2o::OptimizationAlgorithmGaussNewton(
g2o::make_unique<my_BlockSolverType>(g2o::make_unique<my_LinearSolverType>()));
先创建一个 线性求解器 LineraSolver,再创建 块求解器 BlockSolver(使用上面创建的线性求解器初始化),最后创建 总求解器 (使用上面创建的块求解器初始化)。
- ④创建 稀疏优化器 SparseOptimizer,并用已定义总求解器 solver 作为求解方法
//***高翔代码***//
g2o::SparseOptimizer optimizer; // 稀疏优化器
optimizer.setAlgorithm(solver); // 将已定义的总求解器 solver 设置为 稀疏优化器 SparseOptimizer 的求解方法
optimizer.setVerbose(true); // 打开调试输出,输出优化过程中的详细信息
//***g2o源码 g2o/core/sparse_optimizer.h ***//
//! the solver used by the optimizer
const OptimizationAlgorithm* algorithm() const { return _algorithm; }
OptimizationAlgorithm* solver() { return _algorithm; }
void setAlgorithm(OptimizationAlgorithm* algorithm);
//! verbose information during optimization
bool verbose() const { return _verbose; }
void setVerbose(bool verbose);
- ⑤定义图的顶点并添加到 稀疏优化器 SparseOptimizer 中
//***高翔代码***//
// 往图中增加顶点
CurveFittingVertex *v = new CurveFittingVertex();
v->setEstimate(Eigen::Vector3d(ae, be, ce));
v->setId(0);
optimizer.addVertex(v);
//***g2o源码 g2o/g2o/core/base_vertex.h ***//
//! set the estimate for the vertex also calls updateCache()
void setEstimate(const EstimateType& et) { _estimate = et; updateCache();}
//***g2o源码 g2o/g2o/core/optimizable_graph.h ***//
//设置图中节点(顶点)的 ID,并在改变 ID 后确保图的结构一致性
virtual void setId(int id) {_id = id;}
//***g2o源码 g2o/g2o/core/optimizable_graph.h ***//
/**
* 添加一个新顶点。然后“获取”新顶点。
* @param userData:用户自定义数据,通常用于存储与顶点相关的附加信息,类型为 Data*。这个参数是可选的,默认值为 0(或 nullptr)。
* @如果图中已经存在与v具有相同id的顶点,则返回false,否则返回true。
*/
virtual bool addVertex(HyperGraph::Vertex* v, Data* userData);
virtual bool addVertex(HyperGraph::Vertex* v) { return addVertex(v, 0);}
bool addVertex(OptimizableGraph::Vertex* v, Data* userData);
bool addVertex(OptimizableGraph::Vertex* v) { return addVertex(v, 0); }
- ⑥ 定义图的边并添加到 稀疏优化器 SparseOptimizer 中
//***高翔代码***//
// 往图中增加边
for (int i = 0; i < N; i++) {
CurveFittingEdge *edge = new CurveFittingEdge(x_data[i]);
edge->setId(i);
edge->setVertex(0, v); // 设置连接的顶点
edge->setMeasurement(y_data[i]); // 观测数值
edge->setInformation(Eigen::Matrix<double, 1, 1>::Identity() * 1 / (w_sigma * w_sigma)); // 信息矩阵:协方差矩阵之逆
optimizer.addEdge(edge);
}
//***g2o源码 g2o/g2o/core/hyper_graph.h ***//
void HyperGraph::Edge::setId(int id) { _id = id; }
//***g2o源码 g2o/g2o/core/hyper_graph.h ***//
/**
* 将超边上的第 i 个顶点设置为提供的指针
* @param i: 要设置的顶点在超边中的索引,类型为 size_t
* @param v: 指向要设置的顶点的指针,类型为 Vertex*
*/
void setVertex(size_t i, Vertex* v) { assert(i < _vertices.size() && "index out of bounds"); _vertices[i]=v;}
//***g2o源码 g2o/g2o/core/base_edge.h ***//
//设置与边相关的测量值
virtual void setMeasurement(const Measurement& m) { _measurement = m;}
//***g2o源码 g2o/g2o/core/base_edge.h ***//
//约束的信息矩阵
//设置边的信息矩阵(协方差矩阵之逆)
EIGEN_STRONG_INLINE void setInformation(const InformationType& information) { _information = information;}
//***g2o源码 g2o/g2o/core/optimizable_graph.h ***//
/**
* 添加一个新边
* 新边应该已经设置好它所连接的顶点(使用 setFrom 和 setTo 函数)。
* @如果插入不起作用(顶点类型不兼容/缺少顶点),则返回false。反之亦然。
*/
virtual bool addEdge(HyperGraph::Edge* e);
bool addEdge(OptimizableGraph::Edge* e);
- ⑦设置优化参数,开始执行优化
初始化 稀疏优化器 SparseOptimizer ,并设置迭代次数,最终输出优化结果。
//***高翔代码***//
// 执行优化
cout << "start optimization" << endl;
chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
optimizer.initializeOptimization();
optimizer.optimize(10);
chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
chrono::duration<double> time_used = chrono::duration_cast<chrono::duration<double>>(t2 - t1);
cout << "solve time cost = " << time_used.count() << " seconds. " << endl;
// 输出优化值
Eigen::Vector3d abc_estimate = v->estimate();
cout << "estimated model: " << abc_estimate.transpose() << endl;
initializeOptimization() 函数有 3 种重载版本
//***g2o源码 g2o/g2o/core/sparse_optimizer.h ***//
// 优化器的新接口
// 旧函数将被删除
/**
* 优化某个特定子图,而不是整个图。
* 调用它之前,必须确保正确设置顶点的边缘化(marginalized())和固定状态(fixed())。这是为了在优化过程中能够明确哪些顶点应该被固定,哪些顶点参与舒尔补(Schur Complement)计算。
* @param eset: 要优化的边的子集。这个边集合定义了子图,通过这些边涉及的顶点决定哪些顶点将参与优化。
* @出现问题时return false
*/
virtual bool initializeOptimization(HyperGraph::EdgeSet& eset);
/**
* 优化某个特定子图,而不是整个图。
* 调用它之前,必须确保正确设置顶点的边缘化(marginalized())和固定状态(fixed())。这是为了在优化过程中能够明确哪些顶点应该被固定,哪些顶点参与舒尔补(Schur Complement)计算。
* @param vset: 要优化的顶点子集。只有包含在这个集合中的顶点才会参与优化。
* @param level: 在多层次优化中表示优化层级,默认为0
* @出现问题时return false
*/
virtual bool initializeOptimization(HyperGraph::VertexSet& vset, int level=0);
/**
* 优化整个图。
* 调用它之前,必须确保正确设置顶点的边缘化(marginalized())和固定状态(fixed())。这是为了在优化过程中能够明确哪些顶点应该被固定,哪些顶点参与舒尔补(Schur Complement)计算。
* @param level: 在多层次优化中表示优化层级,默认为0
* @出现问题时return false
*/
virtual bool initializeOptimization(int level=0);
//***g2o源码 g2o/g2o/core/optimizable_graph.h ***//
//! true=>此节点在优化过程中是固定的
bool fixed() const {return _fixed;}
//! true=>在优化过程中,应将此节点视为固定节点
void setFixed(bool fixed) { _fixed = fixed;}
//! true=>此节点在优化过程中被边缘化
bool marginalized() const {return _marginalized;}
//! true=>在优化过程中,该节点应被边缘化
void setMarginalized(bool marginalized) { _marginalized = marginalized;}
//***g2o源码 g2o/g2o/core/sparse_optimizer.h ***//
/**
* 根据当前图的配置和存储在类实例中的设置,启动一次图优化运行
* 在调用 initializeOptimization() 之后才能被调用
* @param iterations: 迭代次数
* @param online: 默认值为 false,表示是否以“在线模式”进行优化。在线模式(增量式优化)允许在处理新数据时只优化增量部分。
* @returns 实际执行的迭代次数。这个值可以小于传入的 iterations 参数,如果优化在收敛条件下提前停止。
*/
int optimize(int iterations, bool online = false);
//***g2o源码 g2o/g2o/core/base_vertex.h ***//
//return 顶点的当前估计值
const EstimateType& estimate() const { return _estimate;}
二、自定义 g2o 顶点
//***高翔代码***//
// 曲线模型的顶点,模板参数:优化变量维度和数据类型
class CurveFittingVertex : public g2o::BaseVertex<3, Eigen::Vector3d> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// 重置
virtual void setToOriginImpl() override {
_estimate << 0, 0, 0;
}
// 更新
virtual void oplusImpl(const double *update) override {
_estimate += Eigen::Vector3d(update);
}
// 存盘和读盘:留空
virtual bool read(istream &in) {}
virtual bool write(ostream &out) const {}
};
//***g2o源码 g2o/g2o/core/base_vertex.h ***//
/**
* \brief 模板化 BaseVertex
*
* D : int 类型,表示vertex的最小维度,例如3D空间中旋转是3维的,则 D = 3
* T : 待估计 vertex 的数据类型,例如用四元数表达三维旋转时,T 为 Quaternion 类型
*/
template <int D, typename T>
class BaseVertex : public OptimizableGraph::Vertex {
// 类的具体实现...
};
在我们定义自己的 Vertex 之前,可以先看下 g2o 本身已经定义好的一些常用的顶点类型: 见链接 g2o 中定义好的常用顶点类型
三、自定义 g2o 边
//***高翔代码***//
// 误差模型 模板参数:观测值维度,类型,连接顶点类型
class CurveFittingEdge : public g2o::BaseUnaryEdge<1, double, CurveFittingVertex> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
CurveFittingEdge(double x) : BaseUnaryEdge(), _x(x) {}
// 计算曲线模型误差
virtual void computeError() override {
const CurveFittingVertex *v = static_cast<const CurveFittingVertex *> (_vertices[0]);
const Eigen::Vector3d abc = v->estimate();
_error(0, 0) = _measurement - std::exp(abc(0, 0) * _x * _x + abc(1, 0) * _x + abc(2, 0));
}
// 计算雅可比矩阵
virtual void linearizeOplus() override {
const CurveFittingVertex *v = static_cast<const CurveFittingVertex *> (_vertices[0]);
const Eigen::Vector3d abc = v->estimate();
double y = exp(abc[0] * _x * _x + abc[1] * _x + abc[2]);
_jacobianOplusXi[0] = -_x * _x * y;
_jacobianOplusXi[1] = -_x * y;
_jacobianOplusXi[2] = -y;
}
virtual bool read(istream &in) {}
virtual bool write(ostream &out) const {}
public:
double _x; // x 值, y 值为 _measurement
};
g2o 边的源码
//***g2o源码 g2o/g2o/core/base_unary_edge.h ***//
/**
* \brief 模板化 BaseUnaryEdge,单边
*
* D : int 类型,表示测量值的维度(Dimension)
* E : 测量值的数据类型
*/
template <int D, typename E, typename VertexXi>
class BaseUnaryEdge : public BaseEdge<D,E>{
// 类的具体实现...
};
//***g2o源码 g2o/g2o/core/base_binary_edge.h ***
/**
* \brief 模板化 BaseBinaryEdge,双边
*
* D : int 类型,表示测量值的维度(Dimension)
* E : 测量值的数据类型
* VertexXi : 边连接的顶点类型
* VertexXj : 边连接的顶点类型
*/
template <int D, typename E, typename VertexXi, typename VertexXj>
class BaseBinaryEdge : public BaseEdge<D, E>
// 类的具体实现...
};
//***g2o源码 g2o/g2o/core/base_multi_edge.h ***//
/**
* D : int 类型,表示测量值的维度(Dimension)
* E : 测量值的数据类型
*/
template <int D, typename E>
using BaseMultiEdge = BaseVariableSizedEdge<D, E>;
在我们定义自己的 Edge 之前,可以先看下 g2o 本身已经定义好的一些常用的边的类型: 见链接 g2o 中定义好的常用边的类型
四、g2o 中重要的成员变量和成员函数汇总
1. 稀疏优化器 SparseOptimizer 可以调用的
//***g2o源码 g2o/core/sparse_optimizer.h 中 SparseOptimizer 类的成员变量和成员函数***//
//! the solver used by the optimizer
const OptimizationAlgorithm* algorithm() const { return _algorithm; }
OptimizationAlgorithm* solver() { return _algorithm; }
void setAlgorithm(OptimizationAlgorithm* algorithm);
//! verbose information during optimization
bool verbose() const { return _verbose; }
void setVerbose(bool verbose);
// 优化器的新接口
// 旧函数将被删除
/**
* 优化某个特定子图,而不是整个图。
* 调用它之前,必须确保正确设置顶点的边缘化(marginalized())和固定状态(fixed())。这是为了在优化过程中能够明确哪些顶点应该被固定,哪些顶点参与舒尔补(Schur Complement)计算。
* @param eset: 要优化的边的子集。这个边集合定义了子图,通过这些边涉及的顶点决定哪些顶点将参与优化。
* @出现问题时return false
*/
virtual bool initializeOptimization(HyperGraph::EdgeSet& eset);
/**
* 优化某个特定子图,而不是整个图。
* 调用它之前,必须确保正确设置顶点的边缘化(marginalized())和固定状态(fixed())。这是为了在优化过程中能够明确哪些顶点应该被固定,哪些顶点参与舒尔补(Schur Complement)计算。
* @param vset: 要优化的顶点子集。只有包含在这个集合中的顶点才会参与优化。
* @param level: 在多层次优化中表示优化层级,默认为0
* @出现问题时return false
*/
virtual bool initializeOptimization(HyperGraph::VertexSet& vset, int level=0);
/**
* 优化整个图。
* 调用它之前,必须确保正确设置顶点的边缘化(marginalized())和固定状态(fixed())。这是为了在优化过程中能够明确哪些顶点应该被固定,哪些顶点参与舒尔补(Schur Complement)计算。
* @param level: 在多层次优化中表示优化层级,默认为0
* @出现问题时return false
*/
virtual bool initializeOptimization(int level=0);
/**
* 根据当前图的配置和存储在类实例中的设置,启动一次图优化运行
* 在调用 initializeOptimization() 之后才能被调用
* @param iterations: 迭代次数
* @param online: 默认值为 false,表示是否以“在线模式”进行优化。在线模式(增量式优化)允许在处理新数据时只优化增量部分。
* @returns 实际执行的迭代次数。这个值可以小于传入的 iterations 参数,如果优化在收敛条件下提前停止。
*/
int optimize(int iterations, bool online = false);
/**
* Propagates an initial guess from the vertex specified as origin.
* It should be called after initializeOptimization(...), as it relies on the _activeVertices/_edges structures.
* It constructs a set of trees starting from the nodes in the graph which are fixed and eligible for preforming optimization.
* The trees are constructed by utlizing a cost-function specified.
* @param costFunction: the cost function used
* @patam maxDistance: the distance where to stop the search
*/
/**
* 从指定的起始顶点传播初始猜测
* 该方法应该在调用 initializeOptimization(...) 之后使用,因为它依赖于 _activeVertices 和 _activeEdges 这些内部结构。
* 从图中固定且可进行优化的节点开始使用指定的成本函数构建一组树
* @param costFunction: 使用的成本函数
* @patam maxDistance: 停止搜索的距离
*/
virtual void computeInitialGuess();
/**
* Same as above but using a specific propagator
* 与上述相同,但使用了一个特定的传播器(EstimatePropagatorCost)
*/
virtual void computeInitialGuess(EstimatePropagatorCost& propagator);
/**
* computes the error vectors of all edges in the activeSet, and caches them
* 计算活动集合(activeSet)中所有边的误差向量并将其缓存
*/
void computeActiveErrors();
//***g2o源码 g2o/g2o/core/optimizable_graph.h 中 OptimizableGraph 类的成员变量和成员函数***//
/**
* 添加一个新顶点。然后“获取”新顶点。
* @param userData:用户自定义数据,通常用于存储与顶点相关的附加信息,类型为 Data*。这个参数是可 选的,默认值为 0(或 nullptr)。
* @如果图中已经存在与v具有相同id的顶点,则返回false,否则返回true。
*/
virtual bool addVertex(HyperGraph::Vertex* v, Data* userData);
virtual bool addVertex(HyperGraph::Vertex* v) { return addVertex(v, 0);}
bool addVertex(OptimizableGraph::Vertex* v, Data* userData);
bool addVertex(OptimizableGraph::Vertex* v) { return addVertex(v, 0); }
//! returns the vertex number <i>id</i> appropriately casted
inline Vertex* vertex(int id) { return reinterpret_cast<Vertex*>(HyperGraph::vertex(id));}
//! returns the vertex number <i>id</i> appropriately casted
inline const Vertex* vertex (int id) const{ return reinterpret_cast<const Vertex*>(HyperGraph::vertex(id));}
/**
* 添加一个新边
* 新边应该已经设置好它所连接的顶点(使用 setFrom 和 setTo 函数)。
* @如果插入不起作用(顶点类型不兼容/缺少顶点),则返回false。反之亦然。
*/
virtual bool addEdge(HyperGraph::Edge* e);
bool addEdge(OptimizableGraph::Edge* e);
//! returns the chi2 of the current configuration
number_t chi2() const;
//***g2o源码 g2o/g2o/core/hyper_graph.h 中 HyperGraph 类的成员函数和成员变量***//
// std::unordered_map 是 C++ 标准库中的一个容器,用于存储键值对(key-value pair),
// 它是一种哈希表实现,可以在常数时间内查找、插入和删除元素。
typedef std::unordered_map<int, Vertex*> VertexIDMap;
// std::set 是 C++ 标准库中的集合容器,用于存储唯一的元素,并且默认按照某种顺序对元素进行排序。
typedef std::set<Edge*> EdgeSet;
VertexIDMap _vertices;
EdgeSet _edges;
//! @returns the map <i>id -> vertex</i> where the vertices are stored
const VertexIDMap& vertices() const { return _vertices; }
//! @returns the map <i>id -> vertex</i> where the vertices are stored
VertexIDMap& vertices() { return _vertices; }
//! @returns the set of edges of the hyper graph
const EdgeSet& edges() const { return _edges; }
//! @returns the set of edges of the hyper graph
EdgeSet& edges() { return _edges; }
其中 number_t chi2() const; 函数的实现
//***g2o源码 g2o/g2o/core/optimizable_graph.cpp 中 OptimizableGraph 类的成员变量和成员函数***//
//! returns the chi2 of the current configuration
number_t OptimizableGraph::chi2() const {
number_t chi = 0.0;
for (OptimizableGraph::EdgeSet::const_iterator it = this->edges().begin();
it != this->edges().end(); ++it) {
const OptimizableGraph::Edge* e =
static_cast<const OptimizableGraph::Edge*>(*it);
chi += e->chi2();
}
return chi;
}
//***g2o源码 g2o/g2o/core/optimizable_graph.cpp 中 OptimizableGraph::Edge 类的成员变量和成员函数***//
// OptimizableGraph::Edge 类继承自 HyperGraph::Edge 类
class G2O_CORE_API Edge : public HyperGraph::Edge,
public HyperGraph::DataContainer {
//! computes the chi2 based on the cached error value, only valid after
//! computeError has been called.
virtual number_t chi2() const = 0;
/* 类中其他函数 */
};
//***g2o源码 g2o/g2o/core/base_edge.h 中 BaseEdge 类的成员变量和成员函数***//
// BaseEdge 类继承自 OptimizableGraph::Edge
virtual number_t chi2() const
{
return _error.dot(information()*_error);
}
2.自定义顶点可以调用的
//***g2o源码 g2o/g2o/core/base_vertex.h 中 BaseVertex 类的成员变量和成员函数***//
// 顶点的估计值,其中,该 EstimateType 类型就是 BaseVertex 的第二个模板参数 T 类型,即待估计 vertex 的数据类型
EstimateType _estimate;
//! return the current estimate of the vertex
const EstimateType& estimate() const { return _estimate;}
//! set the estimate for the vertex also calls updateCache()
void setEstimate(const EstimateType& et) { _estimate = et; updateCache();}
//***g2o源码 g2o/g2o/core/optimizable_graph.h 中 OptimizableGraph::Vertex 类的成员变量和成员函数***//
//设置图中节点(顶点)的 ID,并在改变 ID 后确保图的结构一致性
virtual void setId(int id) {_id = id;}
//! true=>此节点在优化过程中是固定的
bool fixed() const {return _fixed;}
//! true=>在优化过程中,应将此节点视为固定节点
void setFixed(bool fixed) { _fixed = fixed;}
//! true=>此节点在优化过程中被边缘化
bool marginalized() const {return _marginalized;}
//! true=>在优化过程中,该节点应被边缘化
void setMarginalized(bool marginalized) { _marginalized = marginalized;}
3.自定义边可以调用的
注意 g2o源码 g2o/g2o/core/hyper_graph.h 中 HyperGraph 和 HyperGraph::Edge 类中均有名为 _vertices 的成员变量。我们在自定义边时,使用的 _vertices 成员变量继承自 HyperGraph::Edge 类。
//***g2o源码 g2o/g2o/core/base_edge.h 中 BaseEdge 和 BaseEdge<-1,E> 类的成员变量和成员函数***//
// 边的测量值,其中,该 Measurement 类型就是 BaseEdge 的第二个模板参数 E 类型,即测量值的数据类型
Measurement _measurement;
// 误差量,computeError()函数计算后的值
// 其中,该 ErrorVector 类型就是 Eigen::Matrix<number_t, D, 1, Eigen::ColMajor>, D 是 BaseEdge 的第一个模板参数 D 类型,即测量值的维度(int类型)
// Eigen::Matrix<number_t, D, 1, Eigen::ColMajor> 定义了一个 D 维的列向量,number_t 代表向量中元素的类型(通常是 double 或 float),ColMajor 表示按列优先存储矩阵元素。
ErrorVector _error;
// 信息矩阵,其中,该 InformationType 类型就是Eigen::Matrix<number_t, D, D, Eigen::ColMajor>
InformationType _information;
// 设置与边相关的测量值
//! accessor functions for the measurement represented by the edge
EIGEN_STRONG_INLINE const Measurement& measurement() const { return _measurement;}
virtual void setMeasurement(const Measurement& m) { _measurement = m;}
// 约束的信息矩阵
// 设置边的信息矩阵(协方差矩阵之逆)
//! information matrix of the constraint
EIGEN_STRONG_INLINE const InformationType& information() const { return _information;}
EIGEN_STRONG_INLINE InformationType& information() { return _information;}
EIGEN_STRONG_INLINE void setInformation(const InformationType& information) { _information = information;}
virtual const number_t* informationData() const { return _information.data();}
virtual number_t* informationData() { return _information.data();}
// 误差
virtual const number_t* errorData() const { return _error.data();}
virtual number_t* errorData() { return _error.data();}
const ErrorVector& error() const { return _error;}
ErrorVector& error() { return _error;}
//***g2o源码 g2o/g2o/core/base_unary_edge.h + base_binary_edge.h + base_multi_edge.h 中对应的类***//
// 雅可比矩阵(双元边)
JacobianXiOplusType _jacobianOplusXi; // (单元边)
JacobianXjOplusType _jacobianOplusXj;
// 雅可比矩阵(多元边)
std::vector<JacobianType, Eigen::aligned_allocator<JacobianType> > _jacobianOplus; ///< jacobians of the edge (w.r.t. oplus)
//***g2o源码 g2o/g2o/core/optimizable_graph.h 中 OptimizableGraph::Edge 类的成员函数和成员变量***//
// 鲁棒核函数
RobustKernel* _robustKernel;
int _level;
//! if NOT NULL, error of this edge will be robustifed with the kernel
RobustKernel* robustKernel() const { return _robustKernel; }
/**
* specify the robust kernel to be used in this edge
*/
void setRobustKernel(RobustKernel* ptr);
// level 等级设置成 1,表示不优化(默认情况下,g2o 只处理 level=0 的边)
//! returns the level of the edge
int level() const { return _level;}
//! sets the level of the edge
void setLevel(int l) { _level=l;}
//***g2o源码 g2o/g2o/core/hyper_graph.h 中 HyperGraph::Edge 类的成员函数和成员变量***//
// 边对应的顶点信息,其中,该 VertexContainer 类型就是 std::vector<Vertex*>,可以通过方括号[]运算符进行顶点提取操作
// 顶点存储顺序由 setVertex(size_t i, Vertex* v) 的 size_t 类型参数 i 决定,_vertices[i]=v
VertexContainer _vertices;
int id() const { return _id; }
void HyperGraph::Edge::setId(int id) { _id = id; }
/**
* 将超边上的第 i 个顶点设置为提供的指针
* @param i: 要设置的顶点在超边中的索引,类型为 size_t
* @param v: 指向要设置的顶点的指针,类型为 Vertex*
*/
/**
set the ith vertex on the hyper-edge to the pointer supplied
*/
void setVertex(size_t i, Vertex* v) {
assert(i < _vertices.size() && "index out of bounds");
_vertices[i] = v;
}
/**
returns the vector of pointers to the vertices connected by the
hyper-edge.
*/
const VertexContainer& vertices() const { return _vertices; }
/**
returns the vector of pointers to the vertices connected by the
hyper-edge.
*/
VertexContainer& vertices() { return _vertices; }
如果要为优化问题中的边(Edge)设置鲁棒核函数(Robust Kernel),在图优化中用于降低异常值(outliers)的影响,增强对噪声的鲁棒性。在使用边(Edge)调用 OptimizableGraph::Edge 类中的 setRobustKernel() 成员函数前
auto rk = new g2o::RobustKernelHuber(); // 创建一个 Huber 鲁棒核函数对象
rk->setDelta(delta_th); // 设置鲁棒核函数的阈值为 delta_th
edge->setRobustKernel(rk); // 为该边(Edge)设置鲁棒核函数(Robust Kernel)
//***g2o源码 g2o/g2o/core/robust_kernel.h 中 RobustKernel 类的成员变量和成员函数***//
#include <memory>
#include "g2o/core/eigen_types.h"
#include "g2o_core_api.h"
namespace g2o {
/**
* \brief base for all robust cost functions
*
* Note in all the implementations for the other cost functions the e in the
* functions corresponds to the squared errors, i.e., the robustification
* functions gets passed the squared error.
*
* e.g. the robustified least squares function is
*
* chi^2 = sum_{e} rho( e^T Omega e )
*/
class G2O_CORE_API RobustKernel {
public:
RobustKernel();
explicit RobustKernel(number_t delta);
virtual ~RobustKernel() {}
/**
* compute the scaling factor for a error:
* The error is e^T Omega e
* The output rho is
* rho[0]: The actual scaled error value
* rho[1]: First derivative of the scaling function
* rho[2]: Second derivative of the scaling function
*/
virtual void robustify(number_t squaredError, Vector3& rho) const = 0;
/**
* set the window size of the error. A squared error above delta^2 is
* considered as outlier in the data.
* 设置 error 的窗口大小。大于 delta^2 的平方误差被视为数据中的异常值。
*/
virtual void setDelta(number_t delta);
number_t delta() const { return _delta; }
protected:
number_t _delta;
};
typedef std::shared_ptr<RobustKernel> RobustKernelPtr;
} // end namespace g2o
//***g2o源码 g2o/g2o/core/robust_kernel.cpp 中 RobustKernel 类的成员变量和成员函数***//
#include "robust_kernel.h"
namespace g2o {
RobustKernel::RobustKernel() : _delta(1.) {}
RobustKernel::RobustKernel(number_t delta) : _delta(delta) {}
void RobustKernel::setDelta(number_t delta) { _delta = delta; }
} // end namespace g2o
常见的鲁邦核函数如下图:
其中 JacobianXiOplusType 和 JacobianXjOplusType 的类型如下,为一个 m x n 的矩阵,m 为 测量值维度,n 为 顶点维度。
Eigen::Matrix<number_t, D, VertexXiType::Dimension, D==1?Eigen::RowMajor:Eigen::ColMajor>::AlignedMapType
// 其中 ,D 是 BaseEdge 的第一个模板参数 D 类型,即测量值的维度(int类型)
// VertexXiType::Dimension 为 VertexXi::Dimension,就是 BaseVertex 的第一个模板参数 D 类型,即表示 vertex 的最小维度(int类型)
// D==1?Eigen::RowMajor:Eigen::ColMajor: 这是一个条件运算符,用于选择矩阵的存储顺序:
// 如果 D 等于 1,矩阵将按行优先存储(Eigen::RowMajor)。
// 否则,矩阵将按列优先存储(Eigen::ColMajor)。
// ::AlignedMapType 是 Eigen 库中的一个类型,用于创建一个对齐的矩阵映射。
G2O实战案例
示例:3D与2D的PNP问题
已知一批世界坐标系下的3D坐标、和它们对应的像素坐标系下的2D坐标、相机的内参,已通过其他方法诸如PNP求解出初始相机位姿,此时需要通过优化的方法求解出更精准的3D点坐标和相机位姿。
示例:3D与3D的ICP问题
已知一批空间点在两个坐标系的3D坐标、已通过其他方法诸如ICP求解出的两个坐标系之间的相对位姿,此时需要通过优化的方法求解出更精准的相对位姿(这里没有优化3D空间点,实际上也是可以进行优化的)。
由于G2O并没有预先设定该类型的边,因此需要手动创建该边的类型。