第四讲 李群与李代数
感觉SLAM十四讲真的是深入浅出。第四讲是李群和李代数,为什么要引入这个概念呢?
在SLAM中位姿是未知的,我们需要解决“什么样的相机位姿最符合当前观测数据”,一种典型的方式是把它构建成一个优化问题,求解最优的R,t,使误差最小化。但旋转矩阵自身带有约束(正交且行列式为1),给优化带来困难。通过李群李代数可以将问题转化为无约束的优化问题。
4.1李群李代数基础
例 :特殊正交群SO(3)和特殊欧式群SE(3)对加法不封闭,对乘法封闭
对于这种只有一个运算的集合,称之为群
群:
是一种集合加上一种运算的代数结构。群上运算的条件如下:
李群是指具有连续(光滑)性质的群。 “想象一个刚体连续在空间中运动”---李群、
通过旋转矩阵引出李代数。过程简单总结一下。主要是从
1. 旋转矩阵的正交性RR=I 出发,在实际中相机位姿随时间变化,将其构造为时间t的函数 R(t)R(t)=I .
2.然后两边对时间求导,得出R(t)'R(t)是反对称矩阵,就可用一个向量表示。
3.最后把R(t)在t=0处泰勒展开,解微分方程,得出旋转矩阵可以由exp(Φ t)计算出。这个Φ描述了R在局部的导数关系,这就是SO(3)上的李代数。
下面为纯公式:
-> ->两边求导-》
-> ->两边右乘R(t)
->泰勒展开。设R(0)=I->
->解微分方程
意义:
李代数的定义
李代数由一个集合v,一个数域F和一个二元运算[,]组成:
李代数so(3)
其与so(3)的关系有指数映射给定
R=exp(φ^)
李代数 se(3)
4.2指数与对数映射
具体推导略。主要关注与SLAM利用的公式。推出SO(3)的指数映射
指数映射即为罗德里格斯公式
但是指数映射不是单射,可能存在多个李代数中的元素对应到同一个李群。但我们把旋转角度固定在-+π之间就是一一对应的。
SE(3)指数映射
4.3;李代数求导与扰动模型
BCH公式:
对于两个李代指数映射乘积:
以第一个近似为例。该式告诉我们,当对一个旋转矩阵 R2(李代数为 ϕ2)左乘一个微小旋转矩阵 R1(李代数为 ϕ1)
时,可以近似地看作,在原有的李代数 ϕ2 上,加上了一项 Jl(ϕ2)-1ϕ1。同理,第二个近似描述了右乘一个微小位移的情况。于是,李代数在 BCH
近似下,分成了左乘近似和右乘近似两种,在使用时我们须加注意,使用的是左乘模型还是右乘模型。
假定对某个旋转 R,对应的李代数为 ϕ。我们给它左乘一个微小旋转,记作 ∆R,对应的李代数为 ∆ϕ。
那么,在李群上,得到的结果就是 ∆R · R,而在李代数上,根据 BCH近似,为: Jl-1(ϕ)∆ϕ + ϕ。合并起来,
可以简单地写成:
反之,如果我们在李代数上进行加法,让一个 ϕ 加上 ∆ϕ,那么可以近似为李群上带左右雅可比的乘法:
SO(3)的李代数求导
SLAM中,设某个时刻相机位姿为T,观察到了世界坐标系下位于p的点,产生了一个观测数据z,z=Tp+w.
w为随机噪声。
误差e=z-Tp
所以我们就是在n组这样的数据中找一个最优T是的整体误差最小化
我们经常会构建与位姿有关的函数,然后讨论该函数关于位姿的导数,以调整当前的估计值
使用李代数解决求导问题的思路分为两种:
1. 用李代数表示姿态,然后对根据李代数加法来对李代数求导。
2. 对李群左乘或右乘微小扰动,然后对该扰动求导,称为左扰动和右扰动模型。
第一种方式对应到李代数的求导模型,而第二种则对应到扰动模型。
假设我们对一个空间点 p 进行了旋转,得到了 Rp。现在,要计算旋转之后点的坐标相对于旋转的导数
-》
第二行的近似为 BCH 线性近似,第三行为泰勒展开舍去高阶项后近似,第四行至第五行将反对称符号看作叉积,交换之后变号。
SO3扰动模型(左乘)
SE3 李代数求导
评估轨迹误差。
估计轨迹与真实轨迹的差异。真实轨迹由更高精度的系统获得。
常见的有ATE,绝对轨迹误差,
RPE,相对轨迹误差。
4.4 实践 :SOPhus
1 #include <iostream> 2 #include <cmath> 3 #include <Eigen/Core> 4 #include <Eigen/Geometry> 5 #include "sophus/se3.hpp" 6 7 using namespace std; 8 using namespace Eigen; 9 10 /// 本程序演示sophus的基本用法 11 12 int main(int argc, char **argv) { 13 14 // 沿Z轴转90度的旋转矩阵 15 Matrix3d R = AngleAxisd(M_PI / 2, Vector3d(0, 0, 1)).toRotationMatrix(); 16 // 或者四元数 17 Quaterniond q(R); 18 Sophus::SO3d SO3_R(R); // Sophus::SO3d可以直接从旋转矩阵构造 19 Sophus::SO3d SO3_q(q); // 也可以通过四元数构造 20 // 二者是等价的 21 cout << "SO(3) from matrix:\n" << SO3_R.matrix() << endl; 22 cout << "SO(3) from quaternion:\n" << SO3_q.matrix() << endl; 23 cout << "they are equal" << endl; 24 25 // 使用对数映射获得它的李代数 26 Vector3d so3 = SO3_R.log(); 27 cout << "so3 = " << so3.transpose() << endl; 28 // hat 为向量到反对称矩阵 29 cout << "so3 hat=\n" << Sophus::SO3d::hat(so3) << endl; 30 // 相对的,vee为反对称到向量 31 cout << "so3 hat vee= " << Sophus::SO3d::vee(Sophus::SO3d::hat(so3)).transpose() << endl; 32 33 // 增量扰动模型的更新 34 Vector3d update_so3(1e-4, 0, 0); //假设更新量为这么多 35 Sophus::SO3d SO3_updated = Sophus::SO3d::exp(update_so3) * SO3_R; 36 cout << "SO3 updated = \n" << SO3_updated.matrix() << endl; 37 38 cout << "*******************************" << endl; 39 // 对SE(3)操作大同小异 40 Vector3d t(1, 0, 0); // 沿X轴平移1 41 Sophus::SE3d SE3_Rt(R, t); // 从R,t构造SE(3) 42 Sophus::SE3d SE3_qt(q, t); // 从q,t构造SE(3) 43 cout << "SE3 from R,t= \n" << SE3_Rt.matrix() << endl; 44 cout << "SE3 from q,t= \n" << SE3_qt.matrix() << endl; 45 // 李代数se(3) 是一个六维向量,方便起见先typedef一下 46 typedef Eigen::Matrix<double, 6, 1> Vector6d; 47 Vector6d se3 = SE3_Rt.log(); 48 cout << "se3 = " << se3.transpose() << endl; 49 // 观察输出,会发现在Sophus中,se(3)的平移在前,旋转在后. 50 // 同样的,有hat和vee两个算符 51 cout << "se3 hat = \n" << Sophus::SE3d::hat(se3) << endl; 52 cout << "se3 hat vee = " << Sophus::SE3d::vee(Sophus::SE3d::hat(se3)).transpose() << endl; 53 54 // 最后,演示一下更新 55 Vector6d update_se3; //更新量 56 update_se3.setZero(); 57 update_se3(0, 0) = 1e-4d; 58 Sophus::SE3d SE3_updated = Sophus::SE3d::exp(update_se3) * SE3_Rt; 59 cout << "SE3 updated = " << endl << SE3_updated.matrix() << endl; 60 61 return 0; 62 }
打开终端,找到sophus所在位置
mkdir build cd build/ cmake .. make
如果按照十四讲的做法会找不到 “SE3.CPP”,我把include_directories(${Sophus_INCLUDE_DIRS})注释掉
换成:include_directories("/home/leo/slambook2/3rdparty/Sophus/")。
然后执行编译“四件套”。执行结果如下:
例2:评估轨迹误差
这个例子中偶groundtruth.txt和estimated.txt.两条轨迹,用以下代码读取轨迹,计算误差。
1 #include <iostream> 2 #include <fstream> 3 #include <unistd.h> 4 #include <pangolin/pangolin.h> 5 #include <sophus/se3.hpp> 6 7 using namespace Sophus; 8 using namespace std; 9 10 string groundtruth_file = "./groundtruth.txt"; 11 string estimated_file = "./estimated.txt"; 12 13 typedef vector<Sophus::SE3d, Eigen::aligned_allocator<Sophus::SE3d>> TrajectoryType; 14 15 void DrawTrajectory(const TrajectoryType >, const TrajectoryType &esti); 16 17 TrajectoryType ReadTrajectory(const string &path); 18 19 int main(int argc, char **argv) { 20 TrajectoryType groundtruth = ReadTrajectory(groundtruth_file); 21 TrajectoryType estimated = ReadTrajectory(estimated_file); 22 assert(!groundtruth.empty() && !estimated.empty()); 23 assert(groundtruth.size() == estimated.size()); 24 25 // compute rmse 26 double rmse = 0; 27 for (size_t i = 0; i < estimated.size(); i++) { 28 Sophus::SE3d p1 = estimated[i], p2 = groundtruth[i]; 29 double error = (p2.inverse() * p1).log().norm(); 30 rmse += error * error; 31 } 32 rmse = rmse / double(estimated.size()); 33 rmse = sqrt(rmse); 34 cout << "RMSE = " << rmse << endl; 35 36 DrawTrajectory(groundtruth, estimated); 37 return 0; 38 } 39 40 TrajectoryType ReadTrajectory(const string &path) { 41 ifstream fin(path); 42 TrajectoryType trajectory; 43 if (!fin) { 44 cerr << "trajectory " << path << " not found." << endl; 45 return trajectory; 46 } 47 48 while (!fin.eof()) { 49 double time, tx, ty, tz, qx, qy, qz, qw; 50 fin >> time >> tx >> ty >> tz >> qx >> qy >> qz >> qw; 51 Sophus::SE3d p1(Eigen::Quaterniond(qx, qy, qz, qw), Eigen::Vector3d(tx, ty, tz)); 52 trajectory.push_back(p1); 53 } 54 return trajectory; 55 } 56 57 void DrawTrajectory(const TrajectoryType >, const TrajectoryType &esti) { 58 // create pangolin window and plot the trajectory 59 pangolin::CreateWindowAndBind("Trajectory Viewer", 1024, 768); 60 glEnable(GL_DEPTH_TEST); 61 glEnable(GL_BLEND); 62 glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); 63 64 pangolin::OpenGlRenderState s_cam( 65 pangolin::ProjectionMatrix(1024, 768, 500, 500, 512, 389, 0.1, 1000), 66 pangolin::ModelViewLookAt(0, -0.1, -1.8, 0, 0, 0, 0.0, -1.0, 0.0) 67 ); 68 69 pangolin::View &d_cam = pangolin::CreateDisplay() 70 .SetBounds(0.0, 1.0, pangolin::Attach::Pix(175), 1.0, -1024.0f / 768.0f) 71 .SetHandler(new pangolin::Handler3D(s_cam)); 72 73 74 while (pangolin::ShouldQuit() == false) { 75 glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); 76 77 d_cam.Activate(s_cam); 78 glClearColor(1.0f, 1.0f, 1.0f, 1.0f); 79 80 glLineWidth(2); 81 for (size_t i = 0; i < gt.size() - 1; i++) { 82 glColor3f(0.0f, 0.0f, 1.0f); // blue for ground truth 83 glBegin(GL_LINES); 84 auto p1 = gt[i], p2 = gt[i + 1]; 85 glVertex3d(p1.translation()[0], p1.translation()[1], p1.translation()[2]); 86 glVertex3d(p2.translation()[0], p2.translation()[1], p2.translation()[2]); 87 glEnd(); 88 } 89 90 for (size_t i = 0; i < esti.size() - 1; i++) { 91 glColor3f(1.0f, 0.0f, 0.0f); // red for estimated 92 glBegin(GL_LINES); 93 auto p1 = esti[i], p2 = esti[i + 1]; 94 glVertex3d(p1.translation()[0], p1.translation()[1], p1.translation()[2]); 95 glVertex3d(p2.translation()[0], p2.translation()[1], p2.translation()[2]); 96 glEnd(); 97 } 98 pangolin::FinishFrame(); 99 usleep(5000); // sleep 5 ms 100 } 101 102 }
RMSE = 2.20728 下面是可视化以后的图形
4.5相似变换群和李代数sim(3)