forked from xiaoxifuhongse/ORB-SLAM-RGBD-with-Octomap
-
Notifications
You must be signed in to change notification settings - Fork 16
/
Converter.cc
146 lines (116 loc) · 3.53 KB
/
Converter.cc
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
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
/**
* This file is part of ORB-SLAM2.
* 各种类型转换函数,多一个 四元素 转旋转矩阵
*/
#include "ORBSLAM/include/Converter.h"
namespace ORB_SLAM2
{
std::vector<cv::Mat> Converter::toDescriptorVector(const cv::Mat &Descriptors)
{
std::vector<cv::Mat> vDesc;
vDesc.reserve(Descriptors.rows);
for (int j=0;j<Descriptors.rows;j++)
vDesc.push_back(Descriptors.row(j));
return vDesc;
}
g2o::SE3Quat Converter::toSE3Quat(const cv::Mat &cvT)
{
Eigen::Matrix<double,3,3> R;
R << cvT.at<float>(0,0), cvT.at<float>(0,1), cvT.at<float>(0,2),
cvT.at<float>(1,0), cvT.at<float>(1,1), cvT.at<float>(1,2),
cvT.at<float>(2,0), cvT.at<float>(2,1), cvT.at<float>(2,2);
Eigen::Matrix<double,3,1> t(cvT.at<float>(0,3), cvT.at<float>(1,3), cvT.at<float>(2,3));
return g2o::SE3Quat(R,t);
}
cv::Mat Converter::toCvMat(const g2o::SE3Quat &SE3)
{
Eigen::Matrix<double,4,4> eigMat = SE3.to_homogeneous_matrix();
return toCvMat(eigMat);
}
cv::Mat Converter::toCvMat(const g2o::Sim3 &Sim3)
{
Eigen::Matrix3d eigR = Sim3.rotation().toRotationMatrix();
Eigen::Vector3d eigt = Sim3.translation();
double s = Sim3.scale();
return toCvSE3(s*eigR,eigt);
}
cv::Mat Converter::toCvMat(const Eigen::Matrix<double,4,4> &m)
{
cv::Mat cvMat(4,4,CV_32F);
for(int i=0;i<4;i++)
for(int j=0; j<4; j++)
cvMat.at<float>(i,j)=m(i,j);
return cvMat.clone();
}
cv::Mat Converter::toCvMat(const Eigen::Matrix3d &m)
{
cv::Mat cvMat(3,3,CV_32F);
for(int i=0;i<3;i++)
for(int j=0; j<3; j++)
cvMat.at<float>(i,j)=m(i,j);
return cvMat.clone();
}
cv::Mat Converter::toCvMat(const Eigen::Matrix<double,3,1> &m)
{
cv::Mat cvMat(3,1,CV_32F);
for(int i=0;i<3;i++)
cvMat.at<float>(i)=m(i);
return cvMat.clone();
}
cv::Mat Converter::toCvSE3(const Eigen::Matrix<double,3,3> &R, const Eigen::Matrix<double,3,1> &t)
{
cv::Mat cvMat = cv::Mat::eye(4,4,CV_32F);
for(int i=0;i<3;i++)
{
for(int j=0;j<3;j++)
{
cvMat.at<float>(i,j)=R(i,j);
}
}
for(int i=0;i<3;i++)
{
cvMat.at<float>(i,3)=t(i);
}
return cvMat.clone();
}
Eigen::Matrix<double,3,1> Converter::toVector3d(const cv::Mat &cvVector)
{
Eigen::Matrix<double,3,1> v;
v << cvVector.at<float>(0), cvVector.at<float>(1), cvVector.at<float>(2);
return v;
}
Eigen::Matrix<double,3,1> Converter::toVector3d(const cv::Point3f &cvPoint)
{
Eigen::Matrix<double,3,1> v;
v << cvPoint.x, cvPoint.y, cvPoint.z;
return v;
}
Eigen::Matrix<double,3,3> Converter::toMatrix3d(const cv::Mat &cvMat3)
{
Eigen::Matrix<double,3,3> M;
M << cvMat3.at<float>(0,0), cvMat3.at<float>(0,1), cvMat3.at<float>(0,2),
cvMat3.at<float>(1,0), cvMat3.at<float>(1,1), cvMat3.at<float>(1,2),
cvMat3.at<float>(2,0), cvMat3.at<float>(2,1), cvMat3.at<float>(2,2);
return M;
}
// 旋转矩阵转四元素
std::vector<float> Converter::toQuaternion(const cv::Mat &M)
{
Eigen::Matrix<double,3,3> eigMat = toMatrix3d(M);
Eigen::Quaterniond q(eigMat);
std::vector<float> v(4);
v[0] = q.x();
v[1] = q.y();
v[2] = q.z();
v[3] = q.w();
return v;
}
// 四元素 转旋转矩阵
void Converter::RmatOfQuat(cv::Mat &M, const cv::Mat &q) {
Eigen::Quaterniond _q(q.at<float>(0,3), q.at<float>(0,0), q.at<float>(0,1), q.at<float>(0,2));
Eigen::Matrix<double,3,3> _m = _q.toRotationMatrix();
for(int i=0;i<3;i++)
for(int j=0; j<3; j++)
M.at<float>(i,j) = _m(i,j);
}
} //namespace ORB_SLAM