OptimizableTypes.h 6.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2021 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 ORB_SLAM3_OPTIMIZABLETYPES_H
  19. #define ORB_SLAM3_OPTIMIZABLETYPES_H
  20. #include "Thirdparty/g2o/g2o/core/base_unary_edge.h"
  21. #include <Thirdparty/g2o/g2o/types/types_six_dof_expmap.h>
  22. #include <Thirdparty/g2o/g2o/types/sim3.h>
  23. #include <Eigen/Geometry>
  24. #include <include/CameraModels/GeometricCamera.h>
  25. namespace ORB_SLAM3 {
  26. class EdgeSE3ProjectXYZOnlyPose: public g2o::BaseUnaryEdge<2, Eigen::Vector2d, g2o::VertexSE3Expmap>{
  27. public:
  28. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  29. EdgeSE3ProjectXYZOnlyPose(){}
  30. bool read(std::istream& is);
  31. bool write(std::ostream& os) const;
  32. void computeError() {
  33. const g2o::VertexSE3Expmap* v1 = static_cast<const g2o::VertexSE3Expmap*>(_vertices[0]);
  34. Eigen::Vector2d obs(_measurement);
  35. _error = obs-pCamera->project(v1->estimate().map(Xw));
  36. }
  37. bool isDepthPositive() {
  38. const g2o::VertexSE3Expmap* v1 = static_cast<const g2o::VertexSE3Expmap*>(_vertices[0]);
  39. return (v1->estimate().map(Xw))(2)>0.0;
  40. }
  41. virtual void linearizeOplus();
  42. Eigen::Vector3d Xw;
  43. GeometricCamera* pCamera;
  44. };
  45. class EdgeSE3ProjectXYZOnlyPoseToBody: public g2o::BaseUnaryEdge<2, Eigen::Vector2d, g2o::VertexSE3Expmap>{
  46. public:
  47. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  48. EdgeSE3ProjectXYZOnlyPoseToBody(){}
  49. bool read(std::istream& is);
  50. bool write(std::ostream& os) const;
  51. void computeError() {
  52. const g2o::VertexSE3Expmap* v1 = static_cast<const g2o::VertexSE3Expmap*>(_vertices[0]);
  53. Eigen::Vector2d obs(_measurement);
  54. _error = obs-pCamera->project((mTrl * v1->estimate()).map(Xw));
  55. }
  56. bool isDepthPositive() {
  57. const g2o::VertexSE3Expmap* v1 = static_cast<const g2o::VertexSE3Expmap*>(_vertices[0]);
  58. return ((mTrl * v1->estimate()).map(Xw))(2)>0.0;
  59. }
  60. virtual void linearizeOplus();
  61. Eigen::Vector3d Xw;
  62. GeometricCamera* pCamera;
  63. g2o::SE3Quat mTrl;
  64. };
  65. class EdgeSE3ProjectXYZ: public g2o::BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, g2o::VertexSE3Expmap>{
  66. public:
  67. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  68. EdgeSE3ProjectXYZ();
  69. bool read(std::istream& is);
  70. bool write(std::ostream& os) const;
  71. void computeError() {
  72. const g2o::VertexSE3Expmap* v1 = static_cast<const g2o::VertexSE3Expmap*>(_vertices[1]);
  73. const g2o::VertexSBAPointXYZ* v2 = static_cast<const g2o::VertexSBAPointXYZ*>(_vertices[0]);
  74. Eigen::Vector2d obs(_measurement);
  75. _error = obs-pCamera->project(v1->estimate().map(v2->estimate()));
  76. }
  77. bool isDepthPositive() {
  78. const g2o::VertexSE3Expmap* v1 = static_cast<const g2o::VertexSE3Expmap*>(_vertices[1]);
  79. const g2o::VertexSBAPointXYZ* v2 = static_cast<const g2o::VertexSBAPointXYZ*>(_vertices[0]);
  80. return ((v1->estimate().map(v2->estimate()))(2)>0.0);
  81. }
  82. virtual void linearizeOplus();
  83. GeometricCamera* pCamera;
  84. };
  85. class EdgeSE3ProjectXYZToBody: public g2o::BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, g2o::VertexSE3Expmap>{
  86. public:
  87. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  88. EdgeSE3ProjectXYZToBody();
  89. bool read(std::istream& is);
  90. bool write(std::ostream& os) const;
  91. void computeError() {
  92. const g2o::VertexSE3Expmap* v1 = static_cast<const g2o::VertexSE3Expmap*>(_vertices[1]);
  93. const g2o::VertexSBAPointXYZ* v2 = static_cast<const g2o::VertexSBAPointXYZ*>(_vertices[0]);
  94. Eigen::Vector2d obs(_measurement);
  95. _error = obs-pCamera->project((mTrl * v1->estimate()).map(v2->estimate()));
  96. }
  97. bool isDepthPositive() {
  98. const g2o::VertexSE3Expmap* v1 = static_cast<const g2o::VertexSE3Expmap*>(_vertices[1]);
  99. const g2o::VertexSBAPointXYZ* v2 = static_cast<const g2o::VertexSBAPointXYZ*>(_vertices[0]);
  100. return ((mTrl * v1->estimate()).map(v2->estimate()))(2)>0.0;
  101. }
  102. virtual void linearizeOplus();
  103. GeometricCamera* pCamera;
  104. g2o::SE3Quat mTrl;
  105. };
  106. class VertexSim3Expmap : public g2o::BaseVertex<7, g2o::Sim3>
  107. {
  108. public:
  109. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  110. VertexSim3Expmap();
  111. virtual bool read(std::istream& is);
  112. virtual bool write(std::ostream& os) const;
  113. virtual void setToOriginImpl() {
  114. _estimate = g2o::Sim3();
  115. }
  116. virtual void oplusImpl(const double* update_)
  117. {
  118. Eigen::Map<g2o::Vector7d> update(const_cast<double*>(update_));
  119. if (_fix_scale)
  120. update[6] = 0;
  121. g2o::Sim3 s(update);
  122. setEstimate(s*estimate());
  123. }
  124. GeometricCamera* pCamera1, *pCamera2;
  125. bool _fix_scale;
  126. };
  127. class EdgeSim3ProjectXYZ : public g2o::BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, ORB_SLAM3::VertexSim3Expmap>
  128. {
  129. public:
  130. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  131. EdgeSim3ProjectXYZ();
  132. virtual bool read(std::istream& is);
  133. virtual bool write(std::ostream& os) const;
  134. void computeError()
  135. {
  136. const ORB_SLAM3::VertexSim3Expmap* v1 = static_cast<const ORB_SLAM3::VertexSim3Expmap*>(_vertices[1]);
  137. const g2o::VertexSBAPointXYZ* v2 = static_cast<const g2o::VertexSBAPointXYZ*>(_vertices[0]);
  138. Eigen::Vector2d obs(_measurement);
  139. _error = obs-v1->pCamera1->project(v1->estimate().map(v2->estimate()));
  140. }
  141. // virtual void linearizeOplus();
  142. };
  143. class EdgeInverseSim3ProjectXYZ : public g2o::BaseBinaryEdge<2, Eigen::Vector2d, g2o::VertexSBAPointXYZ, VertexSim3Expmap>
  144. {
  145. public:
  146. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  147. EdgeInverseSim3ProjectXYZ();
  148. virtual bool read(std::istream& is);
  149. virtual bool write(std::ostream& os) const;
  150. void computeError()
  151. {
  152. const ORB_SLAM3::VertexSim3Expmap* v1 = static_cast<const ORB_SLAM3::VertexSim3Expmap*>(_vertices[1]);
  153. const g2o::VertexSBAPointXYZ* v2 = static_cast<const g2o::VertexSBAPointXYZ*>(_vertices[0]);
  154. Eigen::Vector2d obs(_measurement);
  155. _error = obs-v1->pCamera2->project((v1->estimate().inverse().map(v2->estimate())));
  156. }
  157. // virtual void linearizeOplus();
  158. };
  159. }
  160. #endif //ORB_SLAM3_OPTIMIZABLETYPES_H