1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
|
#include <iostream>
#include <cmath>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include "sophus/so3.h"
#include "sophus/se3.h"
using namespace std;
int main(int argc , char **argv)
{
Eigen::Matrix3d R = Eigen::AngleAxisd(M_PI/2,Eigen::Vector3d(0,0,1)).toRotationMatrix();//z轴旋转pi/2
Sophus::SO3 SO3_R(R);
Sophus::SO3 SO3_v(0,0,M_PI/2);
Eigen::Quaterniond q(R);
Sophus::SO3 SO3_q(q);
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();
cout<<"李代数so3:"<<so3.transpose()<<endl;
//hat为向量到反对称矩阵
cout<<"so3 hat:"<<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;
//对SE(3)的操作
Eigen::Vector3d t(1,0,0);
Sophus::SE3 SE3_Rt(R,t);
Sophus::SE3 SE3_qt(q,t);
cout<<"SE3 from R,t:"<<endl<<SE3_Rt<<endl;
cout<<"SE3 from q,t:"<<endl<<SE3_qt<<endl;
typedef Eigen::Matrix<double,6,1> Vector6d;
Vector6d se3 = SE3_Rt.log();
cout<<"李代数se3:"<<se3.transpose()<<endl;
cout<<"se3 hat:"<<Sophus::SE3::hat(se3)<<endl;
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;
cout<<"update_se3 is:"<<update_se3.transpose()<<endl;
Sophus::SE3 SE3_updated = Sophus::SE3::exp(update_se3)* SE3_Rt;
cout<<"SE3 updated:"<<endl<<SE3_updated.matrix()<<endl;
return 0;
}
|