主要记录两个非线性优化的方法:Gauss-Newton, Levenburg-Marquadt下降策略,以及学习 Ceres 库和 g2o 库的基本使用方法。摘自《视觉SLAM十四讲》
经典 SLAM 模型由一个状态方程和一个运动方程构成:
$$
\boldsymbol{x}_{k}=f\left(\boldsymbol{x}_{k-1}, \boldsymbol{u}_{k}\right)+\boldsymbol{w}_{k}
$$
$$
\boldsymbol{z}_{k, j}=h\left(\boldsymbol{y}_{j}, \boldsymbol{x}_{k}\right)+\boldsymbol{v}_{k, j}
$$
状态方程中,这里的 $\boldsymbol{x}_{k}$乃是相机的位姿。k时刻的相机位姿由k-1时刻相机位姿,运动传感器的数据和噪声决定。我们可以使用变换矩阵或李代数表示它。观测方程中, ${\boldsymbol{z}_{k, j}}$ 对应$\boldsymbol{x}_{k}$对路标$\boldsymbol{y}_{j}$的一次观测,对应到图像上的像素位置。对于针孔摄像机,观测方程可以表示成:
$$
s \boldsymbol{z}_{k, j}=\boldsymbol{K} \exp \left(\boldsymbol{\xi}^{\wedge}\right) \boldsymbol{y}_{j}
$$
这里 $\boldsymbol{K}$为相机内参,s 为像素点的距离。同时这里$\boldsymbol{z}_{k, j}$和 $\boldsymbol{y}_{j}$都必须以齐次坐标来描述,且中间有一次齐次到非齐次的转换。
由于受到噪声的影响,我们希望通过带噪声的数据 $\boldsymbol{z}$ 和 $\boldsymbol{u}$,推断位姿 $\boldsymbol{x}$和地图 $\boldsymbol{y}$。
在非线性优化中,我们把所有待估计的变量放在一个“状态变量”中:
$$
\boldsymbol{x}=({\boldsymbol{x}_{1}, \ldots, \boldsymbol{x}_{N}, \boldsymbol{y}_{1}, \ldots, \boldsymbol{y}_{M}})
$$
对机器人状态的估计,就是求已知输入数据 $\boldsymbol{u}$ 和观测数据$\boldsymbol{ z }$的条件下,计算状态$\boldsymbol{ x}$ 的条件概率分布:
$$
P(\boldsymbol{x} | \boldsymbol{z}, \boldsymbol{u})
$$
类似于$\boldsymbol{x}$,这里 $\boldsymbol{u}$ 和$\boldsymbol{z}$ 也是对所有数据的统称。特别地,当我们没有测量运动的传感器,只有一张张的图像时,即只考虑观测方程带来的数据时,相当于估计 $P(\boldsymbol{x} | \boldsymbol{z})$ 的条件概率分布。如果忽略图像在时间上的联系,把它们看作一堆彼此没有关系的图片,该问题也称为 Structure from Motion(SfM),即如何从许多图像中重建三维空间结构 。在这种情况下,SLAM 可以看作是图像具有时间先后顺序的,需要实时求解一个 SfM 问题。
直接求后验分布是困难的,但是求一个状态最优估计,使得在该状态下,后验概率最大化(Maximize a Posterior,MAP),则是可行的:
$$
x^{*}_{M A P}=\arg \max P(x | z)=\arg \max P(z | x) P(x)
$$
当不知道机器人位姿大概在什么地方,此时就没有了先验。那么,可以求解x 的最大似然估计(Maximize Likelihood Estimation, MLE):
$$
\boldsymbol{x}^{*}_{M L E}=\arg \max P(\boldsymbol{z} | \boldsymbol{x})
$$
在这里,最大似然估计,可以理解成:“在什么样的状态下,最可能产生现在观测到的数据”。
在求解最大似然估计的时候,最终解的形式可以表示为一个最小二乘问题,度量函数选择误差的平方之和:
$$
J(\boldsymbol{x})=\sum_{k} e_{v, k}^{T} \boldsymbol{R}_{k}^{-1} \boldsymbol{e}_{v, k}+\sum_{k} \sum_{j} \boldsymbol{e}_{y, k, j}^{T} \boldsymbol{Q}_{k, j}^{-1} \boldsymbol{e}_{y, k, j}
$$
上式的最优解等价于状态的最大似然估计。但由于噪声的存在,当我们把估计的轨迹与地图代入 SLAM 的运动、观测方程中时,它们并不会完美的成立。因此我们把状态的估计值进行微调,使得整体的误差下降一些。当然这个下降也有限度,它一般会到达一个极小值。这就是一个典型非线性优化的过程。下面记录两个非线性优化的方法:Gauss-Newton, Levenburg-Marquadt下降策略。
设$\boldsymbol{f}$ 是任意一个非线性函数,我们设它有 m 维:$f(x) \in \mathbb{R}^{m}$。一个简单的最小二乘问题是:
$$
\min _{x} \frac{1}{2}|f(\boldsymbol{x})|_{2}^{2}
$$
Gauss Newton 是最优化算法里面最简单的方法之一。它的思想是将 $f(\boldsymbol{x})$进行一阶的泰勒展开:
$$
f(\boldsymbol{x}+\Delta \boldsymbol{x}) \approx f(\boldsymbol{x})+\boldsymbol{J}(\boldsymbol{x}) \Delta \boldsymbol{x}
$$
这里$J(\boldsymbol{x})$为$f(\boldsymbol{x})$关于 x 的导数,实际上是一个 m × n 的矩阵,也是一个雅可比矩阵。根据前面的框架,当前的目标是为了寻找下降矢量 $\Delta \boldsymbol{x}$,使得$|f(\boldsymbol{x}+\Delta \boldsymbol{x})|^{2}$达到最小。为了求 $\Delta \boldsymbol{x}$,,我们需要解一个线性的最小二乘问题:
$$
\Delta \boldsymbol{x}^{*}=\arg \min _{\Delta \boldsymbol{x}} \frac{1}{2}|f(\boldsymbol{x})+\boldsymbol{J}(\boldsymbol{x}) \Delta \boldsymbol{x}|^{2}
$$
求上式关于 $\Delta \boldsymbol{x}$的导数,并令其为零,可以得到如下方程组:
$$
J(\boldsymbol{x})^{T} \boldsymbol{J}(\boldsymbol{x}) \Delta \boldsymbol{x}=-\boldsymbol{J}(\boldsymbol{x})^{T} f(\boldsymbol{x})
$$
Gauss-Newton 的算法步骤可以写成:
-
给定初始值 $\boldsymbol{x}_{0}$ 。
-
对于第 k 次迭代,求出当前的雅可比矩阵$J\left(x_{k}\right)$和误差$f\left(\boldsymbol{x}_{k}\right)$。
-
求解增量方程:$\boldsymbol{H} \Delta \boldsymbol{x}_{k}=\boldsymbol{g}$
-
若$\Delta \boldsymbol{x}_{k}$ 足够小,则停止。否则,令$\boldsymbol{x}_{k+1}=\boldsymbol{x}_{k}+\Delta \boldsymbol{x}_{k}$,返回 2.
由于 Gauss-Newton 方法中采用的近似二阶泰勒展开只能在展开点附近有较好的近似
效果,所以我们很自然地想到应该给 ∆x 添加一个信赖区域(Trust Region),不能让它太大而使得近似不准确。非线性优化种有一系列这类方法,这类方法也被称之为信赖区域方法 (Trust Region Method)。在信赖区域里边,我们认为近似是有效的;出了这个区域,近似可能会出问题。
一个比较好的方法是根据我们的近似模型跟实际函数之间的差异来确定这个范围:如果差异小,我们就让范围尽可能大;如果差异大,我们就缩小这个近似范围。
$$
\rho=\frac{f(\boldsymbol{x}+\Delta \boldsymbol{x})-f(\boldsymbol{x})}{\boldsymbol{J}(\boldsymbol{x}) \Delta \boldsymbol{x}}
$$
$\rho$ 的分子是实际函数下降的值,分母是近似模型下降的值。如果 $\rho$ 接近于 1,则近似是好的。如果 $\rho$太小,说明实际减小的值远少于近似减小的值,则认为近似比较差,需要缩小近似范围。反之,如果 $\rho$比较大,则说明实际下降的比预计的更大,我们可以放大近似范围。
Levenberg-Marquadt的算法步骤可以写成:
-
给定初始值 $\boldsymbol{x}_{0}$ ,以及初始优化半径 $\mu$。
-
对于第 k 次迭代,求解:
$$
\min _{\Delta \boldsymbol{x}_{k}} \frac{1}{2}\left|f\left(\boldsymbol{x}_{k}\right)+\boldsymbol{J}\left(\boldsymbol{x}_{k}\right) \Delta \boldsymbol{x}_{k}\right|^{2}, \quad \text { s.t. }\left|\boldsymbol{D} \Delta \boldsymbol{x}_{k}\right|^{2} \leq \mu
$$
这里 $\mu$ 是信赖区域的半径,$D$将在后文说明。
-
计算 $\rho$。
-
若 $\rho$ > 34 ,则 $\mu$ = 2$\mu$;
-
若 $\rho$ < 14 ,则 $\mu$ = 0.5$\mu$;
-
如果 $\rho$ 大于某阈值,认为近似可行。令$\boldsymbol{x}_{k+1}=\boldsymbol{x}_{k}+\Delta \boldsymbol{x}_{k}$ 。
-
判断算法是否收敛。如不收敛则返回 2,否则结束。
上式用 拉格朗日乘子将它转化为一个无约束优化问题:
$$
\min _{\Delta \boldsymbol{x}_{k}} \frac{1}{2}\left|f\left(\boldsymbol{x}_{k}\right)+\boldsymbol{J}\left(\boldsymbol{x}_{k}\right) \Delta \boldsymbol{x}_{k}\right|^{2}+\frac{\lambda}{2}|\boldsymbol{D} \Delta \boldsymbol{x}|^{2}
$$
类似于 Gauss-Newton 中的做法,把它展开后,我们发现
该问题的核心仍是计算增量的线性方程:
$$
\left(\boldsymbol{H}+\lambda \boldsymbol{D}^{T} \boldsymbol{D}\right) \Delta \boldsymbol{x}=\boldsymbol{g}
$$
可以看到,增量方程相比于 Gauss-Newton,多了一项$\lambda \boldsymbol{D}^{T} \boldsymbol{D}$。如果考虑它的简化形式,即$\boldsymbol{D}=\boldsymbol{I}$,那么相当于求解:
$$
(\boldsymbol{H}+\lambda \boldsymbol{I}) \Delta \boldsymbol{x}=\boldsymbol{g}
$$
我们看到,当参数 $\lambda$比较小时,$\boldsymbol{H}$占主要地位,这说明二次近似模型在该范围内是比较好的,L-M 方法更接近于 G-N 法。另一方面,当 λ 比较大时,λI 占据主要地位,L-M更接近于一阶梯度下降法(即最速下降),这说明附近的二次近似不够好。L-M 的求解方式,可在一定程度上避免线性方程组的系数矩阵的非奇异和病态问题,提供更稳定更准确的增量 $\Delta \boldsymbol{x}$。
无论是 G-N 还是 L-M,在做最优化计算的时候,都需要提供变量的初始值。实际上非线性优化的所有迭代求解方案,都需要用户来提供一个良好的初始值。由于目标函数太复杂,导致在求解空间上的变化难以琢磨,对问题提供不同的初始值往往会导致不同的计算结果。这种情况是非线性优化的通病:大多数算法都容易陷入局部极小值。因此,无论是哪类科学问题,我们提供初始值都应该有科学依据,例如视觉 SLAM 问题中,我们会用 ICP,PnP 之类的算法提供优化初始值。总之,一个良好的初始值对最优化问题非常重要!
- 编译Ceres有两个注意的点:当初编译sophus要求eigen版本是3.3,编译Ceres时要求是3.2。
- gcc版本我之前的是4.9,要升级为gcc-5
用Ceres拟合曲线:
$$
y=\exp \left(a x^{2}+b x+c\right)+w
$$
其中 a, b, c 为曲线的参数,w 为高斯噪声。我们故意选择了这样一个非线性模型,以使问题不至于太简单。现在,假设我们有 N 个关于 x, y 的观测数据点,想根据这些数据点求出曲线的参数。那么,可以求解下面的最小二乘问题以估计曲线参数:
$$
\min {a, b, c} \frac{1}{2} \sum{i=1}^{N}\left|y_{i}-\exp \left(a x_{i}^{2}+b x_{i}+c\right)\right|^{2}
$$
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
|
#include <iostream>
#include <opencv2/core/core.hpp>
#include <ceres/ceres.h>
#include <chrono>
using namespace std;
// 代价函数的计算模型
struct CURVE_FITTING_COST
{
CURVE_FITTING_COST ( double x, double y ) : _x ( x ), _y ( y ) {}
// 残差的计算
template <typename T>
bool operator() (
const T* const abc, // 模型参数,有3维
T* residual ) const // 残差
{
residual[0] = T ( _y ) - ceres::exp ( abc[0]*T ( _x ) *T ( _x ) + abc[1]*T ( _x ) + abc[2] ); // y-exp(ax^2+bx+c)
return true;
}
const double _x, _y; // x,y数据
};
int main ( int argc, char** argv )
{
double a=1.0, b=2.0, c=1.0; // 真实参数值
int N=100; // 数据点
double w_sigma=1.0; // 噪声Sigma值
cv::RNG rng; // OpenCV随机数产生器
double abc[3] = {0,0,0}; // abc参数的估计值
vector<double> x_data, y_data; // 数据
cout<<"generating data: "<<endl;
for ( int i=0; i<N; i++ )
{
double x = i/100.0;
x_data.push_back ( x );
y_data.push_back (
exp ( a*x*x + b*x + c ) + rng.gaussian ( w_sigma )
);
cout<<x_data[i]<<" "<<y_data[i]<<endl;
}
// 构建最小二乘问题
ceres::Problem problem;
for ( int i=0; i<N; i++ )
{
problem.AddResidualBlock ( // 向问题中添加误差项
// 使用自动求导,模板参数:误差类型,输出维度,输入维度,维数要与前面struct中一致
new ceres::AutoDiffCostFunction<CURVE_FITTING_COST, 1, 3> (
new CURVE_FITTING_COST ( x_data[i], y_data[i] )
),
nullptr, // 核函数,这里不使用,为空
abc // 待估计参数
);
}
// 配置求解器
ceres::Solver::Options options; // 这里有很多配置项可以填
options.linear_solver_type = ceres::DENSE_QR; // 增量方程如何求解
options.minimizer_progress_to_stdout = true; // 输出到cout
ceres::Solver::Summary summary; // 优化信息
chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
ceres::Solve ( options, &problem, &summary ); // 开始优化
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;
// 输出结果
cout<<summary.BriefReport() <<endl;
cout<<"estimated a,b,c = ";
for ( auto a:abc ) cout<<a<<" ";
cout<<endl;
return 0;
}
|
CMakeLists.txt:
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
|
cmake_minimum_required( VERSION 2.8 )
project( ceres_curve_fitting )
set( CMAKE_BUILD_TYPE "Release" )
set( CMAKE_CXX_FLAGS "-std=c++11 -O3" )
# 添加cmake模块以使用ceres库
list( APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules )
# 寻找Ceres库并添加它的头文件
find_package( Ceres REQUIRED )
include_directories( ${CERES_INCLUDE_DIRS} )
# OpenCV
find_package( OpenCV REQUIRED )
include_directories( ${OpenCV_DIRS} )
add_executable( curve_fitting main.cpp )
# 与Ceres和OpenCV链接
target_link_libraries( curve_fitting ${CERES_LIBRARIES} ${OpenCV_LIBS} )
|
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
|
#include <iostream>
#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() // 重置
{
_estimate << 0,0,0;
}
virtual void oplusImpl( const double* update ) // 更新
{
_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) {}
// 计算曲线模型误差
void computeError()
{
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 bool read( istream& in ) {}
virtual bool write( ostream& out ) const {}
public:
double _x; // x 值, y 值为 _measurement
};
int main( int argc, char** argv )
{
double a=1.0, b=2.0, c=1.0; // 真实参数值
int N=100; // 数据点
double w_sigma=1.0; // 噪声Sigma值
cv::RNG rng; // OpenCV随机数产生器
double abc[3] = {0,0,0}; // abc参数的估计值
vector<double> x_data, y_data; // 数据
cout<<"generating data: "<<endl;
for ( int i=0; i<N; i++ )
{
double x = i/100.0;
x_data.push_back ( x );
y_data.push_back (
exp ( a*x*x + b*x + c ) + rng.gaussian ( w_sigma )
);
cout<<x_data[i]<<" "<<y_data[i]<<endl;
}
// 构建图优化,先设定g2o
typedef g2o::BlockSolver< g2o::BlockSolverTraits<3,1> > Block; // 每个误差项优化变量维度为3,误差值维度为1
Block::LinearSolverType* linearSolver = new g2o::LinearSolverDense<Block::PoseMatrixType>(); // 线性方程求解器
Block* solver_ptr = new Block( linearSolver ); // 矩阵块求解器
// 梯度下降方法,从GN, LM, DogLeg 中选
g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg( solver_ptr );
// g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton( solver_ptr );
// g2o::OptimizationAlgorithmDogleg* solver = new g2o::OptimizationAlgorithmDogleg( solver_ptr );
g2o::SparseOptimizer optimizer; // 图模型
optimizer.setAlgorithm( solver ); // 设置求解器
optimizer.setVerbose( true ); // 打开调试输出
// 往图中增加顶点
CurveFittingVertex* v = new CurveFittingVertex();
v->setEstimate( Eigen::Vector3d(0,0,0) );
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(100);
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;
}
|
CMakeLists.txt
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
|
cmake_minimum_required( VERSION 2.8 )
project( g2o_curve_fitting )
set( CMAKE_BUILD_TYPE "Release" )
set( CMAKE_CXX_FLAGS "-std=c++11 -O3" )
# 添加cmake模块以使用ceres库
list( APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules )
# 寻找G2O
find_package( G2O REQUIRED )
include_directories(
${G2O_INCLUDE_DIRS}
"/usr/include/eigen3"
)
# OpenCV
find_package( OpenCV REQUIRED )
include_directories( ${OpenCV_DIRS} )
add_executable( curve_fitting main.cpp )
# 与G2O和OpenCV链接
target_link_libraries( curve_fitting
${OpenCV_LIBS}
g2o_core g2o_stuff
)
|