视觉SLAM笔记(18) Sophus
发布时间
阅读量:
阅读量
这份笔记介绍了视觉SLAM中的关键数学工具——Sophus库、SO(3)和SE(3)运算。Sophus是一个用于李代数计算的Eigen库扩展,支持SO(3)(三维旋转群)和平移变换SE(3),并提供了非模板类版本以简化使用。笔记详细展示了如何通过C++代码构造和操作这些对象,并解释了它们在刚体变换中的应用。此外,还提到了相关参考书籍《视觉SLAM十四讲》,供进一步学习参考。
视觉SLAM笔记(18) Sophus
- 1. Sophus 库
- 2. SO(3) 运算
- 3. SE(3) 运算
1. Sophus 库
一套成熟的李代数库由 Strasdat 维护即 Sophus 库
Sophus 库不仅包含之前主要讨论的 SO(3)和 SE(3)而且还包括二维运动中的 SO(2)和 SE(2)以及相似变换 Sim(3)
基于 Eigen 开发的 Sophus 库无需额外依赖库,
因历史原因,
早期版本仅提供双精度李群/李代数类,
而后续版本则改写了为一种模板类,
该种模板类不仅支持不同精度,
而且增加了使用复杂度,
这里采用的是非模板实现,
而 github 提供的 VSLAM_note\3rdparty\Sophus.tar.gz 则属于非模板版本。
Sophus 本身亦是一个 cmake 工程,只须编译即可,无须安装
2. SO(3) 运算
创建useSophus_SO3.cpp文件:
#include <iostream>
#include <cmath>
using namespace std;
#include <Eigen/Core>
#include <Eigen/Geometry>
#include "sophus/so3.h"
int main( int argc, char** argv )
{
// 沿Z轴转90度的旋转矩阵
Eigen::Matrix3d R = Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d(0,0,1)).toRotationMatrix();
Sophus::SO3 SO3_R(R); // Sophus::SO(3)可以直接从旋转矩阵构造
Sophus::SO3 SO3_v( 0, 0, M_PI/2 ); // 亦可从旋转向量构造
Eigen::Quaterniond q(R); // 或者四元数
Sophus::SO3 SO3_q( q );
// 上述表达方式都是等价的
// 输出SO(3)时,以so(3)形式输出
cout<<"SO(3) from matrix: "<<SO3_R<<endl;
cout<<"SO(3) from vector: "<<SO3_v<<endl;
cout<<"SO(3) from quaternion :"<<SO3_q<<endl;
// 使用对数映射获得它的李代数
Eigen::Vector3d so3 = SO3_R.log();
// transpose纯粹是为了输出美观一些
cout<<"so3 = "<<so3.transpose()<<endl;
// hat 为向量到反对称矩阵
cout<<"so3 hat=\n"<<Sophus::SO3::hat(so3)<<endl;
// 相对的,vee为反对称矩阵到向量
cout<<"so3 hat vee= "<<Sophus::SO3::vee( Sophus::SO3::hat(so3) ).transpose()<<endl;
// 增量扰动模型的更新
Eigen::Vector3d update_so3(1e-4, 0, 0); //假设更新量为这么多
Sophus::SO3 SO3_updated = Sophus::SO3::exp(update_so3)*SO3_R;
cout<<"SO3 updated = "<<SO3_updated<<endl;
return 0;
}
AI助手
编译后执行输出结果如下:

3. SE(3) 运算
创建useSophus_SE3.cpp文件:
#include <iostream>
#include <cmath>
using namespace std;
#include <Eigen/Core>
#include <Eigen/Geometry>
#include "sophus/se3.h"
int main( int argc, char** argv )
{
// 沿Z轴转90度的旋转矩阵
Eigen::Matrix3d R = Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d(0,0,1)).toRotationMatrix();
Eigen::Quaterniond q(R); // 四元数
Eigen::Vector3d t(1,0,0); // 沿X轴平移1
Sophus::SE3 SE3_Rt(R, t); // 从R,t构造SE(3)
Sophus::SE3 SE3_qt(q,t); // 从q,t构造SE(3)
cout<<"SE3 from R,t= "<<endl<<SE3_Rt<<endl;
cout<<"SE3 from q,t= "<<endl<<SE3_qt<<endl;
// 李代数se(3) 是一个六维向量,方便起见先typedef一下
typedef Eigen::Matrix<double,6,1> Vector6d;
Vector6d se3 = SE3_Rt.log();
cout<<"se3 = "<<se3.transpose()<<endl;
// 观察输出,会发现在Sophus中,se(3)的平移在前,旋转在后.
// hat 为向量到反对称矩阵
cout<<"se3 hat = "<<endl<<Sophus::SE3::hat(se3)<<endl;
// 相对的,vee为反对称矩阵到向量
cout<<"se3 hat vee = "<<Sophus::SE3::vee( Sophus::SE3::hat(se3) ).transpose()<<endl;
// 最后,演示一下更新
Vector6d update_se3; //更新量
update_se3.setZero();
update_se3(0,0) = 1e-4d;
Sophus::SE3 SE3_updated = Sophus::SE3::exp(update_se3)*SE3_Rt;
cout<<"SE3 updated = "<<endl<<SE3_updated.matrix()<<endl;
return 0;
}
AI助手
编译后执行输出结果如下:

参考:
相关推荐:
视觉SLAM笔记(十七) 李代数求导与扰动模型
视觉SLAM笔记(十六) 指数与对数映射
视觉SLAM笔记(十五) 李群与李代数
视觉SLAM笔记(十四) Eigen几何模块
视觉SLAM笔记(十三) 空间变换
谢谢!
全部评论 (0)
还没有任何评论哟~
