随手笔记——Sophus的基本使用方法
- 说明
- CMakeLists.txt
- 补充:关于 ADD_SUBDIRECTORY 的使用
- 使用
- CMakeLists执行顺序
- 源代码
说明
Sophus 库支持SO(3) 和SE(3),此外还含有二维运动 SO(2),SE(2) 以及相似变换 Sim(3) 的内容。它是直接在 Eigen 基础上开发的,不需要安装额外的依赖库。Sophus 库只需编译即可,无须安装。
CMakeLists.txt
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)
target_link_libraries(useSophus Sophus::Sophus)
add_subdirectory(example)
补充:关于 ADD_SUBDIRECTORY 的使用
使用
ADD_SUBDIRCTORY:这个指令用来向当前工程中添加存放源文件的子目录,并可以指定中间、目标二进制的存放位置。
CMakeLists执行顺序
CMakeLists是逐层进行执行的:
1)执行cmake指定路径下的CMakeLists
2)当在CMakeLists中遇到ADD_SUBDIRECTORY时,则跳转到该关键字指定的路径下执行相应的CMakeLists
3)执行之后返回跳转位置的下一条指令,然后继续按顺序执行
源代码
#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) {
// 沿Z轴转90度的旋转矩阵
Matrix3d R = AngleAxisd(M_PI / 2, Vector3d(0, 0, 1)).toRotationMatrix();
// 或者四元数
Quaterniond q(R);
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;
// 使用对数映射获得它的李代数
Vector3d so3 = SO3_R.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;
cout << "SO3 updated = \n" << SO3_updated.matrix() << endl;
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;
cout << "SE3 from q,t= \n" << SE3_qt.matrix() << 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和vee两个算符
cout << "se3 hat = \n" << Sophus::SE3d::hat(se3) << endl;
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;
Sophus::SE3d SE3_updated = Sophus::SE3d::exp(update_se3) * SE3_Rt;
cout << "SE3 updated = " << endl << SE3_updated.matrix() << endl;
return 0;
}
补充:相互转换关系,图片载自网络