文章目录
一、李群与李代数
1.1 目的
将位姿估计转换成无约束优化问题,简化求解方式。
1.2 群的概念
对于特殊正交群SO与特殊欧式群SE对于加法不封闭,对于乘法封闭,这样只有一个运算的集合称之为群。群是由一种集合+一种运算的代数结构。
1.3 李群的概念
具有连续(光滑)的群:SO(n)、SE(n)
1.4 李代数
- 李代数定义
- 一个旋转矩阵R可以与一个反对称阵构成指数关系
3. 李代数so(3)
- 李代数se(3)
- 上尖括号表示向量->矩阵,下尖括号表示矩阵->向量
1.5 李群与李代数的转换关系
1.6 李代数的求导与扰动模型
-
BCH线性近似
-
SO求导与扰动
-
SE求导与扰动
二、Sophus的使用(SO/SE的构造,指数、对数映射,更新)
2.1 CMakeLists.txt
cmake_minimum_required(VERSION 3.0)
project(useSophus)
# Sophus,需要使用find_package命令找到它
find_package(Sophus REQUIRED)
include_directories(${Sophus_INCLUDE_DIRS})
# Eigen
include_directories("/usr/include/eigen3")
add_executable(useSophus useSophus.cpp)
# 把自己的程序链接到Sophus库上
target_link_libraries(useSophus Sophus::Sophus)
add_subdirectory(example)
2.2 代码展示
#include <iostream>
#include <cmath>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include "sophus/se3.hpp"
using namespace std;
using namespace Eigen;
// 本程序演示sophus的基本用法
int main(int argc, char **argv) {
// 1.1 构造李群SO
// 旋转矩阵:沿Z轴转90度+平移=旋转向量->旋转矩阵
Matrix3d R = AngleAxisd(M_PI / 2, Vector3d(0, 0, 1)).toRotationMatrix();
// 四元数:旋转矩阵->四元数
Quaterniond q(R);
// 李群SO:由旋转矩阵/四元数构造
Sophus::SO3d SO3_R(R); // Sophus::SO3d可以直接从旋转矩阵构造
Sophus::SO3d SO3_q(q); // 也可以通过四元数构造
// 二者是等价的
cout << "SO(3) from matrix:\n" << SO3_R.matrix() << endl;
cout << "SO(3) from quaternion:\n" << SO3_q.matrix() << endl;
cout << "they are equal!!!" << endl;
// 1.2 使用对数映射获得它的李代数so
Vector3d so3 = SO3_R.log();
cout << "so3 = " << so3.transpose() << endl;
// 向量->反对称矩阵
cout << "so3 hat=\n" << Sophus::SO3d::hat(so3) << endl;
// 反对称->向量
cout << "so3 hat vee= " << Sophus::SO3d::vee(Sophus::SO3d::hat(so3)).transpose() << endl;
// 1.3 增量扰动模型的更新
Vector3d update_so3(1e-4, 0, 0); //假设更新量为这么多
Sophus::SO3d SO3_updated = Sophus::SO3d::exp(update_so3) * SO3_R;//左乘更新量
cout << "SO3 updated = \n" << SO3_updated.matrix() << endl;
cout << "*******************************" << endl;
// 2.1 构造李群SE
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;
cout << "SE3 from q,t= \n" << SE3_qt.matrix() << endl;
// 2.2 李代数se(3) 是一个六维向量,方便起见先typedef一下
typedef Eigen::Matrix<double, 6, 1> Vector6d;
Vector6d se3 = SE3_Rt.log();
cout << "se3 = " << se3.transpose() << endl;
cout << "se3 hat = \n" << Sophus::SE3d::hat(se3) << endl;
cout << "se3 hat vee = " << Sophus::SE3d::vee(Sophus::SE3d::hat(se3)).transpose() << endl;
// 2.3 更新
Vector6d update_se3; //更新量
update_se3.setZero();
update_se3(0, 0) = 1e-4;
Sophus::SE3d SE3_updated = Sophus::SE3d::exp(update_se3) * SE3_Rt;//左乘更新量
cout << "SE3 updated = " << endl << SE3_updated.matrix() << endl;
return 0;
}
2.3 结果
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
三、评估轨迹误差
在实际工程中,我们需要评估一个算法的估计轨道和真实轨道的差异来评价算法的精度。
3.1 CMakeLists.txt
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})
target_link_libraries(trajectoryError ${Pangolin_LIBRARIES} ${FMT_LIBRARIES} fmt)
3.2 代码展示
#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/robot/桌面/slambook2-master/ch4/example/groundtruth.txt";
string estimated_file = "/home/robot/桌面/slambook2-master/ch4/example/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);
TrajectoryType estimated = ReadTrajectory(estimated_file);
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];
double error = (p2.inverse() * p1).log().norm();
rmse += error * error;
}
rmse = rmse / double(estimated.size());
rmse = sqrt(rmse);
cout << "RMSE = " << rmse << endl;
DrawTrajectory(groundtruth, estimated);
return 0;
}
TrajectoryType ReadTrajectory(const string &path) {
ifstream fin(path);
TrajectoryType trajectory;
if (!fin) {
cerr << "trajectory " << path << " not found." << endl;
return trajectory;
}
while (!fin.eof()) {
double time, tx, ty, tz, qx, qy, qz, qw;
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::CreateWindowAndBind("Trajectory Viewer", 1024, 768);
glEnable(GL_DEPTH_TEST);
glEnable(GL_BLEND);
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_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)
);
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));
while (pangolin::ShouldQuit() == false) {
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);
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
}
}