Pose3SLAMExampleExpressions_BearingRangeWithTransform.cpp 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102
  1. /**
  2. * @file Pose3SLAMExampleExpressions_BearingRangeWithTransform.cpp
  3. * @brief A simultaneous optimization of trajectory, landmarks and sensor-pose with respect to body-pose using bearing-range measurements done with Expressions
  4. * @author Thomas Horstink
  5. * @date January 4th, 2019
  6. */
  7. #include <gtsam/inference/Symbol.h>
  8. #include <gtsam/geometry/BearingRange.h>
  9. #include <gtsam/slam/expressions.h>
  10. #include <gtsam/nonlinear/ExpressionFactorGraph.h>
  11. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  12. #include <gtsam/nonlinear/Values.h>
  13. #include <examples/SFMdata.h>
  14. using namespace gtsam;
  15. typedef BearingRange<Pose3, Point3> BearingRange3D;
  16. /* ************************************************************************* */
  17. int main(int argc, char* argv[]) {
  18. // Move around so the whole state (including the sensor tf) is observable
  19. Pose3 init_pose = Pose3();
  20. Pose3 delta_pose1 = Pose3(Rot3().Yaw(2*M_PI/8).Pitch(M_PI/8), Point3(1, 0, 0));
  21. Pose3 delta_pose2 = Pose3(Rot3().Pitch(-M_PI/8), Point3(1, 0, 0));
  22. Pose3 delta_pose3 = Pose3(Rot3().Yaw(-2*M_PI/8), Point3(1, 0, 0));
  23. int steps = 4;
  24. auto poses = createPoses(init_pose, delta_pose1, steps);
  25. auto poses2 = createPoses(init_pose, delta_pose2, steps);
  26. auto poses3 = createPoses(init_pose, delta_pose3, steps);
  27. // Concatenate poses to create trajectory
  28. poses.insert( poses.end(), poses2.begin(), poses2.end() );
  29. poses.insert( poses.end(), poses3.begin(), poses3.end() ); // std::vector of Pose3
  30. auto points = createPoints(); // std::vector of Point3
  31. // (ground-truth) sensor pose in body frame, further an unknown variable
  32. Pose3 body_T_sensor_gt(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0));
  33. // The graph
  34. ExpressionFactorGraph graph;
  35. // Specify uncertainty on first pose prior and also for between factor (simplicity reasons)
  36. auto poseNoise = noiseModel::Diagonal::Sigmas((Vector(6)<<0.3,0.3,0.3,0.1,0.1,0.1).finished());
  37. // Uncertainty bearing range measurement;
  38. auto bearingRangeNoise = noiseModel::Diagonal::Sigmas((Vector(3)<<0.01,0.03,0.05).finished());
  39. // Expressions for body-frame at key 0 and sensor-tf
  40. Pose3_ x_('x', 0);
  41. Pose3_ body_T_sensor_('T', 0);
  42. // Add a prior on the body-pose
  43. graph.addExpressionFactor(x_, poses[0], poseNoise);
  44. // Simulated measurements from pose
  45. for (size_t i = 0; i < poses.size(); ++i) {
  46. auto world_T_sensor = poses[i].compose(body_T_sensor_gt);
  47. for (size_t j = 0; j < points.size(); ++j) {
  48. // This expression is the key feature of this example: it creates a differentiable expression of the measurement after being displaced by sensor transform.
  49. auto prediction_ = Expression<BearingRange3D>( BearingRange3D::Measure, Pose3_('x',i)*body_T_sensor_, Point3_('l',j));
  50. // Create a *perfect* measurement
  51. auto measurement = BearingRange3D(world_T_sensor.bearing(points[j]), world_T_sensor.range(points[j]));
  52. // Add factor
  53. graph.addExpressionFactor(prediction_, measurement, bearingRangeNoise);
  54. }
  55. // and add a between factor to the graph
  56. if (i > 0)
  57. {
  58. // And also we have a *perfect* measurement for the between factor.
  59. graph.addExpressionFactor(between(Pose3_('x', i-1),Pose3_('x', i)), poses[i-1].between(poses[i]), poseNoise);
  60. }
  61. }
  62. // Create perturbed initial
  63. Values initial;
  64. Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
  65. for (size_t i = 0; i < poses.size(); ++i)
  66. initial.insert(Symbol('x', i), poses[i].compose(delta));
  67. for (size_t j = 0; j < points.size(); ++j)
  68. initial.insert<Point3>(Symbol('l', j), points[j] + Point3(-0.25, 0.20, 0.15));
  69. // Initialize body_T_sensor wrongly (because we do not know!)
  70. initial.insert<Pose3>(Symbol('T',0), Pose3());
  71. std::cout << "initial error: " << graph.error(initial) << std::endl;
  72. Values result = LevenbergMarquardtOptimizer(graph, initial).optimize();
  73. std::cout << "final error: " << graph.error(result) << std::endl;
  74. initial.at<Pose3>(Symbol('T',0)).print("\nInitial estimate body_T_sensor\n"); /* initial sensor_P_body estimate */
  75. result.at<Pose3>(Symbol('T',0)).print("\nFinal estimate body_T_sensor\n"); /* optimized sensor_P_body estimate */
  76. body_T_sensor_gt.print("\nGround truth body_T_sensor\n"); /* sensor_P_body ground truth */
  77. return 0;
  78. }
  79. /* ************************************************************************* */