#include "Converter.h"
|
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 std::vector< cv::Mat > | toDescriptorVector (const cv::Mat &Descriptors) |
|
static Eigen::Matrix< double, 3, 3 > | toMatrix3d (const cv::Mat &cvMat3) |
|
static std::vector< float > | toQuaternion (const cv::Mat &M) |
|
static g2o::SE3Quat | toSE3Quat (const cv::Mat &cvT) |
|
static g2o::SE3Quat | toSE3Quat (const g2o::Sim3 &gSim3) |
|
static Eigen::Matrix< double, 3, 1 > | toVector3d (const cv::Mat &cvVector) |
|
static Eigen::Matrix< double, 3, 1 > | toVector3d (const cv::Point3f &cvPoint) |
|
◆ toCvMat() [1/5]
static cv::Mat ORB_SLAM2::Converter::toCvMat |
( |
const g2o::SE3Quat & |
SE3 | ) |
|
|
static |
◆ toCvMat() [2/5]
static cv::Mat ORB_SLAM2::Converter::toCvMat |
( |
const g2o::Sim3 & |
Sim3 | ) |
|
|
static |
◆ toCvMat() [3/5]
static cv::Mat ORB_SLAM2::Converter::toCvMat |
( |
const Eigen::Matrix< double, 4, 4 > & |
m | ) |
|
|
static |
◆ toCvMat() [4/5]
static cv::Mat ORB_SLAM2::Converter::toCvMat |
( |
const Eigen::Matrix3d & |
m | ) |
|
|
static |
◆ toCvMat() [5/5]
static cv::Mat ORB_SLAM2::Converter::toCvMat |
( |
const Eigen::Matrix< double, 3, 1 > & |
m | ) |
|
|
static |
◆ toCvSE3()
static cv::Mat ORB_SLAM2::Converter::toCvSE3 |
( |
const Eigen::Matrix< double, 3, 3 > & |
R, |
|
|
const Eigen::Matrix< double, 3, 1 > & |
t |
|
) |
| |
|
static |
◆ toDescriptorVector()
static std::vector<cv::Mat> ORB_SLAM2::Converter::toDescriptorVector |
( |
const cv::Mat & |
Descriptors | ) |
|
|
static |
◆ toMatrix3d()
static Eigen::Matrix<double,3,3> ORB_SLAM2::Converter::toMatrix3d |
( |
const cv::Mat & |
cvMat3 | ) |
|
|
static |
◆ toQuaternion()
static std::vector<float> ORB_SLAM2::Converter::toQuaternion |
( |
const cv::Mat & |
M | ) |
|
|
static |
◆ toSE3Quat() [1/2]
static g2o::SE3Quat ORB_SLAM2::Converter::toSE3Quat |
( |
const cv::Mat & |
cvT | ) |
|
|
static |
◆ toSE3Quat() [2/2]
static g2o::SE3Quat ORB_SLAM2::Converter::toSE3Quat |
( |
const g2o::Sim3 & |
gSim3 | ) |
|
|
static |
◆ toVector3d() [1/2]
static Eigen::Matrix<double,3,1> ORB_SLAM2::Converter::toVector3d |
( |
const cv::Mat & |
cvVector | ) |
|
|
static |
◆ toVector3d() [2/2]
static Eigen::Matrix<double,3,1> ORB_SLAM2::Converter::toVector3d |
( |
const cv::Point3f & |
cvPoint | ) |
|
|
static |
The documentation for this class was generated from the following file: