Converter.cc
Go to the documentation of this file.
1 
22 #include "Converter.h"
23 
24 namespace ORB_SLAM2
25 {
26 
27 std::vector<cv::Mat> Converter::toDescriptorVector(const cv::Mat &Descriptors)
28 {
29  std::vector<cv::Mat> vDesc;
30  vDesc.reserve(Descriptors.rows);
31  for (int j=0;j<Descriptors.rows;j++)
32  vDesc.push_back(Descriptors.row(j));
33 
34  return vDesc;
35 }
36 
38 {
39  Eigen::Matrix<double,3,3> R;
40  R << cvT.at<float>(0,0), cvT.at<float>(0,1), cvT.at<float>(0,2),
41  cvT.at<float>(1,0), cvT.at<float>(1,1), cvT.at<float>(1,2),
42  cvT.at<float>(2,0), cvT.at<float>(2,1), cvT.at<float>(2,2);
43 
44  Eigen::Matrix<double,3,1> t(cvT.at<float>(0,3), cvT.at<float>(1,3), cvT.at<float>(2,3));
45 
46  return g2o::SE3Quat(R,t);
47 }
48 
49 cv::Mat Converter::toCvMat(const g2o::SE3Quat &SE3)
50 {
51  Eigen::Matrix<double,4,4> eigMat = SE3.to_homogeneous_matrix();
52  return toCvMat(eigMat);
53 }
54 
55 cv::Mat Converter::toCvMat(const g2o::Sim3 &Sim3)
56 {
57  Eigen::Matrix3d eigR = Sim3.rotation().toRotationMatrix();
58  Eigen::Vector3d eigt = Sim3.translation();
59  double s = Sim3.scale();
60  return toCvSE3(s*eigR,eigt);
61 }
62 
63 cv::Mat Converter::toCvMat(const Eigen::Matrix<double,4,4> &m)
64 {
65  cv::Mat cvMat(4,4,CV_32F);
66  for(int i=0;i<4;i++)
67  for(int j=0; j<4; j++)
68  cvMat.at<float>(i,j)=m(i,j);
69 
70  return cvMat.clone();
71 }
72 
73 cv::Mat Converter::toCvMat(const Eigen::Matrix3d &m)
74 {
75  cv::Mat cvMat(3,3,CV_32F);
76  for(int i=0;i<3;i++)
77  for(int j=0; j<3; j++)
78  cvMat.at<float>(i,j)=m(i,j);
79 
80  return cvMat.clone();
81 }
82 
83 cv::Mat Converter::toCvMat(const Eigen::Matrix<double,3,1> &m)
84 {
85  cv::Mat cvMat(3,1,CV_32F);
86  for(int i=0;i<3;i++)
87  cvMat.at<float>(i)=m(i);
88 
89  return cvMat.clone();
90 }
91 
92 cv::Mat Converter::toCvSE3(const Eigen::Matrix<double,3,3> &R, const Eigen::Matrix<double,3,1> &t)
93 {
94  cv::Mat cvMat = cv::Mat::eye(4,4,CV_32F);
95  for(int i=0;i<3;i++)
96  {
97  for(int j=0;j<3;j++)
98  {
99  cvMat.at<float>(i,j)=R(i,j);
100  }
101  }
102  for(int i=0;i<3;i++)
103  {
104  cvMat.at<float>(i,3)=t(i);
105  }
106 
107  return cvMat.clone();
108 }
109 
110 Eigen::Matrix<double,3,1> Converter::toVector3d(const cv::Mat &cvVector)
111 {
112  Eigen::Matrix<double,3,1> v;
113  v << cvVector.at<float>(0), cvVector.at<float>(1), cvVector.at<float>(2);
114 
115  return v;
116 }
117 
118 Eigen::Matrix<double,3,1> Converter::toVector3d(const cv::Point3f &cvPoint)
119 {
120  Eigen::Matrix<double,3,1> v;
121  v << cvPoint.x, cvPoint.y, cvPoint.z;
122 
123  return v;
124 }
125 
126 Eigen::Matrix<double,3,3> Converter::toMatrix3d(const cv::Mat &cvMat3)
127 {
128  Eigen::Matrix<double,3,3> M;
129 
130  M << cvMat3.at<float>(0,0), cvMat3.at<float>(0,1), cvMat3.at<float>(0,2),
131  cvMat3.at<float>(1,0), cvMat3.at<float>(1,1), cvMat3.at<float>(1,2),
132  cvMat3.at<float>(2,0), cvMat3.at<float>(2,1), cvMat3.at<float>(2,2);
133 
134  return M;
135 }
136 
137 std::vector<float> Converter::toQuaternion(const cv::Mat &M)
138 {
139  Eigen::Matrix<double,3,3> eigMat = toMatrix3d(M);
140  Eigen::Quaterniond q(eigMat);
141 
142  std::vector<float> v(4);
143  v[0] = q.x();
144  v[1] = q.y();
145  v[2] = q.z();
146  v[3] = q.w();
147 
148  return v;
149 }
150 
151 } //namespace ORB_SLAM
Definition: sim3.h:41
static Eigen::Matrix< double, 3, 3 > toMatrix3d(const cv::Mat &cvMat3)
Definition: Converter.cc:126
static cv::Mat toCvSE3(const Eigen::Matrix< double, 3, 3 > &R, const Eigen::Matrix< double, 3, 1 > &t)
Definition: Converter.cc:92
XmlRpcServer s
static std::vector< float > toQuaternion(const cv::Mat &M)
Definition: Converter.cc:137
static cv::Mat toCvMat(const g2o::SE3Quat &SE3)
Definition: Converter.cc:49
const Vector3d & translation() const
Definition: sim3.h:280
static Eigen::Matrix< double, 3, 1 > toVector3d(const cv::Mat &cvVector)
Definition: Converter.cc:110
static std::vector< cv::Mat > toDescriptorVector(const cv::Mat &Descriptors)
Definition: Converter.cc:27
static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT)
Definition: Converter.cc:37
const double & scale() const
Definition: sim3.h:288
Matrix< double, 4, 4 > to_homogeneous_matrix() const
Definition: se3quat.h:270
const Quaterniond & rotation() const
Definition: sim3.h:284


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05