graph_slam.hpp 5.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148
  1. // SPDX-License-Identifier: BSD-2-Clause
  2. #ifndef GRAPH_SLAM_HPP
  3. #define GRAPH_SLAM_HPP
  4. #include <memory>
  5. #include <ros/time.h>
  6. #include <g2o/core/hyper_graph.h>
  7. #include <Eigen/Dense>
  8. namespace g2o {
  9. class VertexSE3;
  10. class VertexPlane;
  11. class VertexPointXYZ;
  12. class EdgeSE3;
  13. class EdgeSE3Plane;
  14. class EdgeSE3PointXYZ;
  15. class EdgeSE3PriorXY;
  16. class EdgeSE3PriorXYZ;
  17. class EdgeSE3PriorVec;
  18. class EdgeSE3PriorQuat;
  19. class EdgePlane;
  20. class EdgePlaneIdentity;
  21. class EdgePlaneParallel;
  22. class EdgePlanePerpendicular;
  23. class EdgePlanePriorNormal;
  24. class EdgePlanePriorDistance;
  25. class RobustKernelFactory;
  26. } // namespace g2o
  27. namespace hdl_graph_slam {
  28. class GraphSLAM {
  29. public:
  30. GraphSLAM(const std::string& solver_type = "lm_var");
  31. virtual ~GraphSLAM();
  32. int num_vertices() const;
  33. int num_edges() const;
  34. void set_solver(const std::string& solver_type);
  35. /**
  36. * @brief add a SE3 node to the graph
  37. * @param pose
  38. * @return registered node
  39. */
  40. g2o::VertexSE3* add_se3_node(const Eigen::Isometry3d& pose);
  41. /**
  42. * @brief add a plane node to the graph
  43. * @param plane_coeffs
  44. * @return registered node
  45. */
  46. g2o::VertexPlane* add_plane_node(const Eigen::Vector4d& plane_coeffs);
  47. /**
  48. * @brief add a point_xyz node to the graph
  49. * @param xyz
  50. * @return registered node
  51. */
  52. g2o::VertexPointXYZ* add_point_xyz_node(const Eigen::Vector3d& xyz);
  53. /**
  54. * @brief add an edge between SE3 nodes
  55. * @param v1 node1
  56. * @param v2 node2
  57. * @param relative_pose relative pose between node1 and node2
  58. * @param information_matrix information matrix (it must be 6x6)
  59. * @return registered edge
  60. */
  61. g2o::EdgeSE3* add_se3_edge(g2o::VertexSE3* v1, g2o::VertexSE3* v2, const Eigen::Isometry3d& relative_pose, const Eigen::MatrixXd& information_matrix);
  62. /**
  63. * @brief add an edge between an SE3 node and a plane node
  64. * @param v_se3 SE3 node
  65. * @param v_plane plane node
  66. * @param plane_coeffs plane coefficients w.r.t. v_se3
  67. * @param information_matrix information matrix (it must be 3x3)
  68. * @return registered edge
  69. */
  70. g2o::EdgeSE3Plane* add_se3_plane_edge(g2o::VertexSE3* v_se3, g2o::VertexPlane* v_plane, const Eigen::Vector4d& plane_coeffs, const Eigen::MatrixXd& information_matrix);
  71. /**
  72. * @brief add an edge between an SE3 node and a point_xyz node
  73. * @param v_se3 SE3 node
  74. * @param v_xyz point_xyz node
  75. * @param xyz xyz coordinate
  76. * @param information information_matrix (it must be 3x3)
  77. * @return registered edge
  78. */
  79. g2o::EdgeSE3PointXYZ* add_se3_point_xyz_edge(g2o::VertexSE3* v_se3, g2o::VertexPointXYZ* v_xyz, const Eigen::Vector3d& xyz, const Eigen::MatrixXd& information_matrix);
  80. /**
  81. * @brief add a prior edge to an SE3 node
  82. * @param v_se3
  83. * @param xy
  84. * @param information_matrix
  85. * @return
  86. */
  87. g2o::EdgePlanePriorNormal* add_plane_normal_prior_edge(g2o::VertexPlane* v, const Eigen::Vector3d& normal, const Eigen::MatrixXd& information_matrix);
  88. g2o::EdgePlanePriorDistance* add_plane_distance_prior_edge(g2o::VertexPlane* v, double distance, const Eigen::MatrixXd& information_matrix);
  89. g2o::EdgeSE3PriorXY* add_se3_prior_xy_edge(g2o::VertexSE3* v_se3, const Eigen::Vector2d& xy, const Eigen::MatrixXd& information_matrix);
  90. g2o::EdgeSE3PriorXYZ* add_se3_prior_xyz_edge(g2o::VertexSE3* v_se3, const Eigen::Vector3d& xyz, const Eigen::MatrixXd& information_matrix);
  91. g2o::EdgeSE3PriorQuat* add_se3_prior_quat_edge(g2o::VertexSE3* v_se3, const Eigen::Quaterniond& quat, const Eigen::MatrixXd& information_matrix);
  92. g2o::EdgeSE3PriorVec* add_se3_prior_vec_edge(g2o::VertexSE3* v_se3, const Eigen::Vector3d& direction, const Eigen::Vector3d& measurement, const Eigen::MatrixXd& information_matrix);
  93. g2o::EdgePlane* add_plane_edge(g2o::VertexPlane* v_plane1, g2o::VertexPlane* v_plane2, const Eigen::Vector4d& measurement, const Eigen::Matrix4d& information);
  94. g2o::EdgePlaneIdentity* add_plane_identity_edge(g2o::VertexPlane* v_plane1, g2o::VertexPlane* v_plane2, const Eigen::Vector4d& measurement, const Eigen::Matrix4d& information);
  95. g2o::EdgePlaneParallel* add_plane_parallel_edge(g2o::VertexPlane* v_plane1, g2o::VertexPlane* v_plane2, const Eigen::Vector3d& measurement, const Eigen::Matrix3d& information);
  96. g2o::EdgePlanePerpendicular* add_plane_perpendicular_edge(g2o::VertexPlane* v_plane1, g2o::VertexPlane* v_plane2, const Eigen::Vector3d& measurement, const Eigen::MatrixXd& information);
  97. void add_robust_kernel(g2o::HyperGraph::Edge* edge, const std::string& kernel_type, double kernel_size);
  98. /**
  99. * @brief perform graph optimization
  100. */
  101. int optimize(int num_iterations);
  102. /**
  103. * @brief save the pose graph to a file
  104. * @param filename output filename
  105. */
  106. void save(const std::string& filename);
  107. /**
  108. * @brief load the pose graph from file
  109. * @param filename output filename
  110. */
  111. bool load(const std::string& filename);
  112. public:
  113. g2o::RobustKernelFactory* robust_kernel_factory;
  114. std::unique_ptr<g2o::HyperGraph> graph; // g2o graph
  115. };
  116. } // namespace hdl_graph_slam
  117. #endif // GRAPH_SLAM_HPP