Converter.h 2.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #ifndef CONVERTER_H
  19. #define CONVERTER_H
  20. #include<opencv2/core/core.hpp>
  21. #include<Eigen/Dense>
  22. #include"Thirdparty/g2o/g2o/types/types_six_dof_expmap.h"
  23. #include"Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h"
  24. namespace ORB_SLAM3
  25. {
  26. class Converter
  27. {
  28. public:
  29. static std::vector<cv::Mat> toDescriptorVector(const cv::Mat &Descriptors);
  30. static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT);
  31. static g2o::SE3Quat toSE3Quat(const g2o::Sim3 &gSim3);
  32. static cv::Mat toCvMat(const g2o::SE3Quat &SE3);
  33. static cv::Mat toCvMat(const g2o::Sim3 &Sim3);
  34. static cv::Mat toCvMat(const Eigen::Matrix<double,4,4> &m);
  35. static cv::Mat toCvMat(const Eigen::Matrix3d &m);
  36. static cv::Mat toCvMat(const Eigen::Matrix<double,3,1> &m);
  37. static cv::Mat toCvMat(const Eigen::MatrixXd &m);
  38. static cv::Mat toCvSE3(const Eigen::Matrix<double,3,3> &R, const Eigen::Matrix<double,3,1> &t);
  39. static cv::Mat tocvSkewMatrix(const cv::Mat &v);
  40. static Eigen::Matrix<double,3,1> toVector3d(const cv::Mat &cvVector);
  41. static Eigen::Matrix<double,3,1> toVector3d(const cv::Point3f &cvPoint);
  42. static Eigen::Matrix<double,3,3> toMatrix3d(const cv::Mat &cvMat3);
  43. static Eigen::Matrix<double,4,4> toMatrix4d(const cv::Mat &cvMat4);
  44. static std::vector<float> toQuaternion(const cv::Mat &M);
  45. static bool isRotationMatrix(const cv::Mat &R);
  46. static std::vector<float> toEuler(const cv::Mat &R);
  47. };
  48. }// namespace ORB_SLAM
  49. #endif // CONVERTER_H