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));
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);
44 Eigen::Matrix<double,3,1> t(cvT.at<
float>(0,3), cvT.at<
float>(1,3), cvT.at<
float>(2,3));
57 Eigen::Matrix3d eigR = Sim3.
rotation().toRotationMatrix();
65 cv::Mat cvMat(4,4,CV_32F);
67 for(
int j=0; j<4; j++)
68 cvMat.at<
float>(i,j)=m(i,j);
75 cv::Mat cvMat(3,3,CV_32F);
77 for(
int j=0; j<3; j++)
78 cvMat.at<
float>(i,j)=m(i,j);
85 cv::Mat cvMat(3,1,CV_32F);
87 cvMat.at<
float>(i)=m(i);
92 cv::Mat
Converter::toCvSE3(
const Eigen::Matrix<double,3,3> &R,
const Eigen::Matrix<double,3,1> &t)
94 cv::Mat cvMat = cv::Mat::eye(4,4,CV_32F);
99 cvMat.at<
float>(i,j)=R(i,j);
104 cvMat.at<
float>(i,3)=t(i);
107 return cvMat.clone();
112 Eigen::Matrix<double,3,1> v;
113 v << cvVector.at<
float>(0), cvVector.at<
float>(1), cvVector.at<
float>(2);
120 Eigen::Matrix<double,3,1> v;
121 v << cvPoint.x, cvPoint.y, cvPoint.z;
128 Eigen::Matrix<double,3,3> M;
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);
139 Eigen::Matrix<double,3,3> eigMat =
toMatrix3d(M);
140 Eigen::Quaterniond q(eigMat);
142 std::vector<float> v(4);
static Eigen::Matrix< double, 3, 3 > toMatrix3d(const cv::Mat &cvMat3)
static cv::Mat toCvSE3(const Eigen::Matrix< double, 3, 3 > &R, const Eigen::Matrix< double, 3, 1 > &t)
static std::vector< float > toQuaternion(const cv::Mat &M)
static cv::Mat toCvMat(const g2o::SE3Quat &SE3)
const Vector3d & translation() const
static Eigen::Matrix< double, 3, 1 > toVector3d(const cv::Mat &cvVector)
static std::vector< cv::Mat > toDescriptorVector(const cv::Mat &Descriptors)
static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT)
const double & scale() const
Matrix< double, 4, 4 > to_homogeneous_matrix() const
const Quaterniond & rotation() const