forked from raulmur/ORB_SLAM
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Converter.h
57 lines (46 loc) · 1.98 KB
/
Converter.h
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
/**
* This file is part of ORB-SLAM.
*
* Copyright (C) 2014 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
* For more information see <http://webdiis.unizar.es/~raulmur/orbslam/>
*
* ORB-SLAM is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef CONVERTER_H
#define CONVERTER_H
#include<opencv2/core/core.hpp>
#include<Eigen/Dense>
#include"Thirdparty/g2o/g2o/types/types_six_dof_expmap.h"
#include"Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h"
namespace ORB_SLAM
{
class Converter
{
public:
static std::vector<cv::Mat> toDescriptorVector(const cv::Mat &Descriptors);
static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT);
static cv::Mat toCvMat(const g2o::SE3Quat &SE3);
static cv::Mat toCvMat(const g2o::Sim3 &Sim3);
static cv::Mat toCvMat(const Eigen::Matrix<double,4,4> &m);
static cv::Mat toCvMat(const Eigen::Matrix3d &m);
static cv::Mat toCvMat(const Eigen::Matrix<double,3,1> &m);
static cv::Mat toCvSE3(const Eigen::Matrix<double,3,3> &R, const Eigen::Matrix<double,3,1> &t);
static Eigen::Matrix<double,3,1> toVector3d(const cv::Mat &cvVector);
static Eigen::Matrix<double,3,1> toVector3d(const cv::Point3f &cvPoint);
static Eigen::Matrix<double,2,1> toVector2d(const cv::Mat &cvVector);
static Eigen::Matrix<double,3,3> toMatrix3d(const cv::Mat &cvMat3);
static std::vector<float> toQuaternion(const cv::Mat &M);
};
}// namespace ORB_SLAM
#endif // CONVERTER_H