useSophus.cpp
#include <iostream>
#include <cmath>
#include <Eigen/Core> //Eigen核心模块
#include <Eigen/Geometry>//Eigen几何模块
#include "sophus/se3.hpp"
using namespace std;
using namespace Eigen;
/// 本程序演示sophus的基本用法
int main(int argc, char **argv) {
// 沿Z轴转90度的旋转矩阵
Matrix3d R = AngleAxisd(M_PI / 2, Vector3d(0, 0, 1)).toRotationMatrix();
// 或者四元数
Quaterniond q(R);//用旋转矩阵初始化的四元数
Sophus::SO3d SO3_R(R); // Sophus::SO3d可以直接从旋转矩阵构造 从旋转矩阵构造正交群SO3
Sophus::SO3d SO3_q(q); // 也可以通过四元数构造 从四元数构造正交群SO3
// 二者是等价的
cout << "SO(3) from matrix:\n" << SO3_R.matrix() << endl;//输出旋转矩阵构造正交群SO3的矩阵
cout << "SO(3) from quaternion:\n" << SO3_q.matrix() << endl;//从四元数构造正交群SO3的矩阵
cout << "they are equal" << endl;
// 使用对数映射获得它的李代数
Vector3d so3 = SO3_R.log();//log输出李群所对应的李代数
cout << "so3 = " << so3.transpose() << endl;
// hat 为向量到反对称矩阵
cout << "so3 hat=\n" << Sophus::SO3d::hat(so3) << endl;//下尖那个符号为向量到反对称矩阵
// 相对的,vee为反对称到向量
cout << "so3 hat vee= " << Sophus::SO3d::vee(Sophus::SO3d::hat(so3)).transpose() << endl;//上尖那个符号为反对称矩阵到向量
// 增量扰动模型的更新
Vector3d update_so3(1e-4, 0, 0); //假设更新量为这么多
Sophus::SO3d SO3_updated = Sophus::SO3d::exp(update_so3) * SO3_R;//exp表示李代数
cout << "SO3 updated = \n" << SO3_updated.matrix() << endl;//更新SO3输出的矩阵
cout << "*******************************" << endl;
// 对SE(3)操作大同小异
Vector3d t(1, 0, 0); // 沿X轴平移1
Sophus::SE3d SE3_Rt(R, t); // 从R,t构造SE(3)
Sophus::SE3d SE3_qt(q, t); // 从q,t构造SE(3)
cout << "SE3 from R,t= \n" << SE3_Rt.matrix() << endl;//输出旋转矩阵构造正交群SE3的矩阵
cout << "SE3 from q,t= \n" << SE3_qt.matrix() << endl;//输出四元数构造正交群SE3的矩阵
// 李代数se(3) 是一个六维向量,方便起见先typedef一下
typedef Eigen::Matrix<double, 6, 1> Vector6d;
Vector6d se3 = SE3_Rt.log();//log表示李群所对应的李代数
cout << "se3 = " << se3.transpose() << endl;
// 观察输出,会发现在Sophus中,se(3)的平移在前,旋转在后.
// 同样的,有hat和vee两个算符
cout << "se3 hat = \n" << Sophus::SE3d::hat(se3) << endl;//下尖那个符号为向量到反对称矩阵 即hat
cout << "se3 hat vee = " << Sophus::SE3d::vee(Sophus::SE3d::hat(se3)).transpose() << endl;
// 最后,演示一下更新
Vector6d update_se3; //更新量
update_se3.setZero();
update_se3(0, 0) = 1e-4;
cout << "SE3 updated = " << endl << SE3_updated.matrix() << endl;//更新SE3输出的矩阵
return 0;
}
CmakeLists文件:
cmake_minimum_required(VERSION 3.0)
project(useSophus)
# 为使用 sophus,需要使用find_package命令找到它
find_package(Sophus REQUIRED)
# Eigen
include_directories("/usr/include/eigen3")
add_executable(useSophus useSophus.cpp)
add_executable(useSophus1 useSophus1.cpp)
target_link_libraries(useSophus Sophus::Sophus)
add_subdirectory(example)
执行结果:
SO(3) from matrix:
2.22045e-16 -1 0
1 2.22045e-16 0
0 0 1
SO(3) from quaternion:
2.22045e-16 -1 0
1 2.22045e-16 0
0 0 1
they are equal
so3 = 0 0 1.5708
so3 hat=
0 -1.5708 0
1.5708 0 -0
-0 0 0
so3 hat vee= 0 0 1.5708
SO3 updated =
0 -1 0
1 0 -0.0001
0.0001 2.03288e-20 1
*******************************
SE3 from R,t=
2.22045e-16 -1 0 1
1 2.22045e-16 0 0
0 0 1 0
0 0 0 1
SE3 from q,t=
2.22045e-16 -1 0 1
1 2.22045e-16 0 0
0 0 1 0
0 0 0 1
se3 = 0.785398 -0.785398 0 0 0 1.5708
se3 hat =
0 -1.5708 0 0.785398
1.5708 0 -0 -0.785398
-0 0 0 0
0 0 0 0
se3 hat vee = 0.785398 -0.785398 0 0 0 1.5708
SE3 updated =
2.22045e-16 -1 0 1.0001
1 2.22045e-16 0 0
0 0 1 0
0 0 0 1
trajectoryError.cpp
#include <iostream>
#include <fstream>
#include <unistd.h>
#include <pangolin/pangolin.h>
#include <sophus/se3.hpp>
using namespace Sophus;
using namespace std;
string groundtruth_file = "/home/liqiang/slambook2/ch4/example/groundtruth.txt";//groundtruth_file 存储位置
//string groundtruth_file = "../groundtruth.txt";
string estimated_file = "/home/liqiang/slambook2/ch4/example/estimated.txt";//estimated_file 存储位置
//string estimated_file = "../estimated.txt";
typedef vector<Sophus::SE3d, Eigen::aligned_allocator<Sophus::SE3d>> TrajectoryType;
void DrawTrajectory(const TrajectoryType >, const TrajectoryType &esti);
TrajectoryType ReadTrajectory(const string &path);
int main(int argc, char **argv) {
TrajectoryType groundtruth = ReadTrajectory(groundtruth_file);//读取groundtruth_file
TrajectoryType estimated = ReadTrajectory(estimated_file);//读取estimated_file
//assert()为断言函数。如果它的条件返回错误,则终止程序执行!
assert(!groundtruth.empty() && !estimated.empty());
assert(groundtruth.size() == estimated.size());
// compute rmse
//计算绝对轨迹误差,即为李代数的均方根误差
double rmse = 0;
for (size_t i = 0; i < estimated.size(); i++) {
Sophus::SE3d p1 = estimated[i], p2 = groundtruth[i];//p1为estimated_file中的值(为估计轨迹T(esti,i)) p2为groundtruth_file中的值(为真实轨迹T(gt,i))
//error = (p2.inverse() * p1).log().norm();为视觉slam十四讲p89的4.44式ATE(all)
double error = (p2.inverse() * p1).log().norm();//n = norm(v) 返回向量 v 的欧几里德范数。此范数也称为 2-范数、向量模或欧几里德长度。例如:K>> norm([3 4]) ans =5
rmse += error * error;//rmse+ error * error
}
rmse = rmse / double(estimated.size());//rmse / 估计轨迹的点数
rmse = sqrt(rmse);//开根
cout << "RMSE = " << rmse << endl;//输出RMSE
DrawTrajectory(groundtruth, estimated);
return 0;
}
TrajectoryType ReadTrajectory(const string &path) {
ifstream fin(path);
TrajectoryType trajectory;
if (!fin)//如果文件打开失败,则执行
{
cerr << "trajectory " << path << " not found." << endl; //cerr是标准错误流。该流中的信息只能输出到显示器上,而不能输出到文件中。该流中信息不经过缓冲区,直接输出至显示器。
return trajectory;
}
while (!fin.eof()) //当fin并未指向EOF时,则执行
{
double time, tx, ty, tz, qx, qy, qz, qw;//time 平移向量 四元数
fin >> time >> tx >> ty >> tz >> qx >> qy >> qz >> qw;
Sophus::SE3d p1(Eigen::Quaterniond(qw, qx, qy, qz), Eigen::Vector3d(tx, ty, tz));
trajectory.push_back(p1);
}
return trajectory;
}
void DrawTrajectory(const TrajectoryType >, const TrajectoryType &esti) {
// create pangolin window and plot the trajectory 创建pangolin窗口
pangolin::CreateWindowAndBind("Trajectory Viewer", 1024, 768);//分别表示窗口名Trajectory Viewer、窗口宽度=1024和窗口高度=768
glEnable(GL_DEPTH_TEST);//启用深度渲染,当需要显示3D模型时需要打开,根据目标的远近自动隐藏被遮挡的模型
glEnable(GL_BLEND);//窗口使用颜色混合模式,让物体显示半透明效果
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);//GL_SRC_ALPHA表示使用源颜色的alpha值作为权重因子,GL_ONE_MINUS_SRC_ALPHA表示用1.0-源颜色的alpha值作为权重因子
pangolin::OpenGlRenderState s_cam(
pangolin::ProjectionMatrix(1024, 768, 500, 500, 512, 389, 0.1, 1000),
pangolin::ModelViewLookAt(0, -0.1, -1.8, 0, 0, 0, 0.0, -1.0, 0.0)
);
//ProjectionMatrix()中各参数依次为图像宽度=1024、图像高度=768、fx=500、fy=500、cx=512、cy=389、最近距离=0.1和最远距离=1000
//ModelViewLookAt()中各参数为相机位置,被观察点位置和相机哪个轴朝上
//比如,ModelViewLookAt(0, -0.1, -1.8, 0, 0, 0, 0.0, -1.0, 0.0)表示相机在(0, -0.1, -1.8)位置处观看视点(0, 0, 0),并设置相机XYZ轴正方向为(0,-1,0),即右上前
//创建一个观察相机视图
pangolin::View &d_cam = pangolin::CreateDisplay()
.SetBounds(0.0, 1.0, pangolin::Attach::Pix(175), 1.0, -1024.0f / 768.0f)
.SetHandler(new pangolin::Handler3D(s_cam));
//SetBounds()内的前4个参数分别表示交互视图的大小,均为相对值,范围在0.0至1.0之间
//第1个参数表示bottom,即为视图最下面在整个窗口中的位置
//第2个参数为top,即为视图最上面在整个窗口中的位置
//第3个参数为left,即视图最左边在整个窗口中的位置
//第4个参数为right,即为视图最右边在整个窗口中的位置
//第5个参数为aspect,表示横纵比
while (pangolin::ShouldQuit() == false) //如果pangolin窗口没有关闭,则执行
{
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);//清空颜色和深度缓存,使得前后帧不会互相干扰
d_cam.Activate(s_cam);//激活显示,并设置相机状态
glClearColor(1.0f, 1.0f, 1.0f, 1.0f);//设置背景颜色为白色
glLineWidth(2);//设置线条宽度为2
for (size_t i = 0; i < gt.size() - 1; i++) {
glColor3f(0.0f, 0.0f, 1.0f); // blue for ground truth 颜色设置为蓝色
glBegin(GL_LINES);
auto p1 = gt[i], p2 = gt[i + 1];
glVertex3d(p1.translation()[0], p1.translation()[1], p1.translation()[2]);
glVertex3d(p2.translation()[0], p2.translation()[1], p2.translation()[2]);
glEnd();
}
for (size_t i = 0; i < esti.size() - 1; i++) {
glColor3f(1.0f, 0.0f, 0.0f); // red for estimated 颜色设置为红色
glBegin(GL_LINES);
auto p1 = esti[i], p2 = esti[i + 1];
glVertex3d(p1.translation()[0], p1.translation()[1], p1.translation()[2]);
glVertex3d(p2.translation()[0], p2.translation()[1], p2.translation()[2]);
glEnd();
}
pangolin::FinishFrame();//执行渲染,即按照前面的设置进行最终的显示
usleep(5000); // sleep 5 ms
}
}
CmakeLists文件:
option(USE_UBUNTU_20 "Set to ON if you are using Ubuntu 20.04" OFF)
find_package(Pangolin REQUIRED)
if(USE_UBUNTU_20)
message("You are using Ubuntu 20.04, fmt::fmt will be linked")
find_package(fmt REQUIRED)
set(FMT_LIBRARIES fmt::fmt)
endif()
include_directories(${Pangolin_INCLUDE_DIRS})
add_executable(trajectoryError trajectoryError.cpp)
target_link_libraries(trajectoryError ${Pangolin_LIBRARIES} ${FMT_LIBRARIES})
执行结果:
1.验证SO(3),SE(3)和Sim(3)关于乘法成群。
参考链接:《视觉SLAM十四讲》学习笔记-第四讲部分习题的证明思路_摸着石头撑船-CSDN博客
2.验证 三维向量(R3,R,×)构成一个李代数。
参考链接:《视觉SLAM十四讲》学习笔记-三维向量定义的叉积为李代数的证明(部分)_摸着石头撑船-CSDN博客
3.验证so(3)和se(3)满足李代数的性质。
参考链接:《视觉SLAM十四讲》学习笔记-两个三维向量的李括号(即公式4.12)是李代数的验证_摸着石头撑船-CSDN博客_李括号运算具体例子
4.验证性质(4.20)和(4.21)
5.证明:Rp^R(T)=(Rp)^ 。
6.证明 :
太难了,直接及结论吧。
7.仿照左扰动的推到,推导SO(3)和SE(3)在左扰动下的导数。