pose_graph_2d.cc 7.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173
  1. // Ceres Solver - A fast non-linear least squares minimizer
  2. // Copyright 2023 Google Inc. All rights reserved.
  3. // http://ceres-solver.org/
  4. //
  5. // Redistribution and use in source and binary forms, with or without
  6. // modification, are permitted provided that the following conditions are met:
  7. //
  8. // * Redistributions of source code must retain the above copyright notice,
  9. // this list of conditions and the following disclaimer.
  10. // * Redistributions in binary form must reproduce the above copyright notice,
  11. // this list of conditions and the following disclaimer in the documentation
  12. // and/or other materials provided with the distribution.
  13. // * Neither the name of Google Inc. nor the names of its contributors may be
  14. // used to endorse or promote products derived from this software without
  15. // specific prior written permission.
  16. //
  17. // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
  18. // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
  19. // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
  20. // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
  21. // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
  22. // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
  23. // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
  24. // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
  25. // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
  26. // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  27. // POSSIBILITY OF SUCH DAMAGE.
  28. //
  29. // Author: vitus@google.com (Michael Vitus)
  30. //
  31. // An example of solving a graph-based formulation of Simultaneous Localization
  32. // and Mapping (SLAM). It reads a 2D pose graph problem definition file in the
  33. // g2o format, formulates and solves the Ceres optimization problem, and outputs
  34. // the original and optimized poses to file for plotting.
  35. #include <fstream>
  36. #include <iostream>
  37. #include <map>
  38. #include <string>
  39. #include <vector>
  40. #include "angle_manifold.h"
  41. #include "ceres/ceres.h"
  42. #include "common/read_g2o.h"
  43. #include "gflags/gflags.h"
  44. #include "glog/logging.h"
  45. #include "pose_graph_2d_error_term.h"
  46. #include "types.h"
  47. DEFINE_string(input, "", "The pose graph definition filename in g2o format.");
  48. namespace ceres::examples {
  49. namespace {
  50. // Constructs the nonlinear least squares optimization problem from the pose
  51. // graph constraints.
  52. void BuildOptimizationProblem(const std::vector<Constraint2d>& constraints,
  53. std::map<int, Pose2d>* poses,
  54. ceres::Problem* problem) {
  55. CHECK(poses != nullptr);
  56. CHECK(problem != nullptr);
  57. if (constraints.empty()) {
  58. LOG(INFO) << "No constraints, no problem to optimize.";
  59. return;
  60. }
  61. ceres::LossFunction* loss_function = nullptr;
  62. ceres::Manifold* angle_manifold = AngleManifold::Create();
  63. for (const auto& constraint : constraints) {
  64. auto pose_begin_iter = poses->find(constraint.id_begin);
  65. CHECK(pose_begin_iter != poses->end())
  66. << "Pose with ID: " << constraint.id_begin << " not found.";
  67. auto pose_end_iter = poses->find(constraint.id_end);
  68. CHECK(pose_end_iter != poses->end())
  69. << "Pose with ID: " << constraint.id_end << " not found.";
  70. const Eigen::Matrix3d sqrt_information =
  71. constraint.information.llt().matrixL();
  72. // Ceres will take ownership of the pointer.
  73. ceres::CostFunction* cost_function = PoseGraph2dErrorTerm::Create(
  74. constraint.x, constraint.y, constraint.yaw_radians, sqrt_information);
  75. problem->AddResidualBlock(cost_function,
  76. loss_function,
  77. &pose_begin_iter->second.x,
  78. &pose_begin_iter->second.y,
  79. &pose_begin_iter->second.yaw_radians,
  80. &pose_end_iter->second.x,
  81. &pose_end_iter->second.y,
  82. &pose_end_iter->second.yaw_radians);
  83. problem->SetManifold(&pose_begin_iter->second.yaw_radians, angle_manifold);
  84. problem->SetManifold(&pose_end_iter->second.yaw_radians, angle_manifold);
  85. }
  86. // The pose graph optimization problem has three DOFs that are not fully
  87. // constrained. This is typically referred to as gauge freedom. You can apply
  88. // a rigid body transformation to all the nodes and the optimization problem
  89. // will still have the exact same cost. The Levenberg-Marquardt algorithm has
  90. // internal damping which mitigate this issue, but it is better to properly
  91. // constrain the gauge freedom. This can be done by setting one of the poses
  92. // as constant so the optimizer cannot change it.
  93. auto pose_start_iter = poses->begin();
  94. CHECK(pose_start_iter != poses->end()) << "There are no poses.";
  95. problem->SetParameterBlockConstant(&pose_start_iter->second.x);
  96. problem->SetParameterBlockConstant(&pose_start_iter->second.y);
  97. problem->SetParameterBlockConstant(&pose_start_iter->second.yaw_radians);
  98. }
  99. // Returns true if the solve was successful.
  100. bool SolveOptimizationProblem(ceres::Problem* problem) {
  101. CHECK(problem != nullptr);
  102. ceres::Solver::Options options;
  103. options.max_num_iterations = 100;
  104. options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
  105. ceres::Solver::Summary summary;
  106. ceres::Solve(options, problem, &summary);
  107. std::cout << summary.FullReport() << '\n';
  108. return summary.IsSolutionUsable();
  109. }
  110. // Output the poses to the file with format: ID x y yaw_radians.
  111. bool OutputPoses(const std::string& filename,
  112. const std::map<int, Pose2d>& poses) {
  113. std::fstream outfile;
  114. outfile.open(filename.c_str(), std::istream::out);
  115. if (!outfile) {
  116. std::cerr << "Error opening the file: " << filename << '\n';
  117. return false;
  118. }
  119. for (const auto& pair : poses) {
  120. outfile << pair.first << " " << pair.second.x << " " << pair.second.y << ' '
  121. << pair.second.yaw_radians << '\n';
  122. }
  123. return true;
  124. }
  125. } // namespace
  126. } // namespace ceres::examples
  127. int main(int argc, char** argv) {
  128. google::InitGoogleLogging(argv[0]);
  129. GFLAGS_NAMESPACE::ParseCommandLineFlags(&argc, &argv, true);
  130. CHECK(FLAGS_input != "") << "Need to specify the filename to read.";
  131. std::map<int, ceres::examples::Pose2d> poses;
  132. std::vector<ceres::examples::Constraint2d> constraints;
  133. CHECK(ceres::examples::ReadG2oFile(FLAGS_input, &poses, &constraints))
  134. << "Error reading the file: " << FLAGS_input;
  135. std::cout << "Number of poses: " << poses.size() << '\n';
  136. std::cout << "Number of constraints: " << constraints.size() << '\n';
  137. CHECK(ceres::examples::OutputPoses("poses_original.txt", poses))
  138. << "Error outputting to poses_original.txt";
  139. ceres::Problem problem;
  140. ceres::examples::BuildOptimizationProblem(constraints, &poses, &problem);
  141. CHECK(ceres::examples::SolveOptimizationProblem(&problem))
  142. << "The solve was not successful, exiting.";
  143. CHECK(ceres::examples::OutputPoses("poses_optimized.txt", poses))
  144. << "Error outputting to poses_original.txt";
  145. return 0;
  146. }