Converter.h
Go to the documentation of this file.
1 
21 #ifndef CONVERTER_H
22 #define CONVERTER_H
23 
24 #include<opencv2/core/core.hpp>
25 
26 #include<Eigen/Dense>
29 
30 namespace ORB_SLAM2
31 {
32 
33 class Converter
34 {
35 public:
36  static std::vector<cv::Mat> toDescriptorVector(const cv::Mat &Descriptors);
37 
38  static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT);
39  static g2o::SE3Quat toSE3Quat(const g2o::Sim3 &gSim3);
40 
41  static cv::Mat toCvMat(const g2o::SE3Quat &SE3);
42  static cv::Mat toCvMat(const g2o::Sim3 &Sim3);
43  static cv::Mat toCvMat(const Eigen::Matrix<double,4,4> &m);
44  static cv::Mat toCvMat(const Eigen::Matrix3d &m);
45  static cv::Mat toCvMat(const Eigen::Matrix<double,3,1> &m);
46  static cv::Mat toCvMat(const std::vector<float>& v);
47  static cv::Mat toCvSE3(const Eigen::Matrix<double,3,3> &R, const Eigen::Matrix<double,3,1> &t);
48 
49  static Eigen::Matrix<double,3,1> toVector3d(const cv::Mat &cvVector);
50  static Eigen::Matrix<double,3,1> toVector3d(const cv::Point3f &cvPoint);
51  static Eigen::Matrix<double,3,3> toMatrix3d(const cv::Mat &cvMat3);
52 
53  static std::vector<float> toQuaternion(const cv::Mat &M);
54 };
55 
56 }// namespace ORB_SLAM
57 
58 #endif // CONVERTER_H
Definition: sim3.h:41
static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT)
static std::vector< float > toQuaternion(const cv::Mat &M)
static cv::Mat toCvSE3(const Eigen::Matrix< double, 3, 3 > &R, const Eigen::Matrix< double, 3, 1 > &t)
static Eigen::Matrix< double, 3, 3 > toMatrix3d(const cv::Mat &cvMat3)
static cv::Mat toCvMat(const g2o::SE3Quat &SE3)
static std::vector< cv::Mat > toDescriptorVector(const cv::Mat &Descriptors)
static Eigen::Matrix< double, 3, 1 > toVector3d(const cv::Mat &cvVector)


orb_slam2_with_maps_odom
Author(s): teng zhang
autogenerated on Fri Sep 25 2020 03:24:47