Pose2SLAMStressTest.cpp 2.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283
  1. /**
  2. * @file Pose2SLAMStressTest.cpp
  3. * @brief Test GTSAM on large open-loop chains
  4. * @date May 23, 2018
  5. * @author Wenqiang Zhou
  6. */
  7. // Create N 3D poses, add relative motion between each consecutive poses. (The
  8. // relative motion is simply a unit translation(1, 0, 0), no rotation). For each
  9. // each pose, add some random noise to the x value of the translation part.
  10. // Use gtsam to create a prior factor for the first pose and N-1 between factors
  11. // and run optimization.
  12. #include <gtsam/geometry/Cal3_S2Stereo.h>
  13. #include <gtsam/geometry/Pose3.h>
  14. #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
  15. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  16. #include <gtsam/nonlinear/NonlinearEquality.h>
  17. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  18. #include <gtsam/nonlinear/Values.h>
  19. #include <gtsam/slam/BetweenFactor.h>
  20. #include <gtsam/slam/StereoFactor.h>
  21. #include <random>
  22. using namespace std;
  23. using namespace gtsam;
  24. void testGtsam(int numberNodes) {
  25. std::random_device rd;
  26. std::mt19937 e2(rd());
  27. std::uniform_real_distribution<> dist(0, 1);
  28. vector<Pose3> poses;
  29. for (int i = 0; i < numberNodes; ++i) {
  30. Matrix4 M;
  31. double r = dist(e2);
  32. r = (r - 0.5) / 10 + i;
  33. M << 1, 0, 0, r, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1;
  34. poses.push_back(Pose3(M));
  35. }
  36. // prior factor for the first pose
  37. auto priorModel = noiseModel::Isotropic::Variance(6, 1e-4);
  38. Matrix4 first_M;
  39. first_M << 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1;
  40. Pose3 first = Pose3(first_M);
  41. NonlinearFactorGraph graph;
  42. graph.addPrior(0, first, priorModel);
  43. // vo noise model
  44. auto VOCovarianceModel = noiseModel::Isotropic::Variance(6, 1e-3);
  45. // relative VO motion
  46. Matrix4 vo_M;
  47. vo_M << 1, 0, 0, 1, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1;
  48. Pose3 relativeMotion(vo_M);
  49. for (int i = 0; i < numberNodes - 1; ++i) {
  50. graph.add(
  51. BetweenFactor<Pose3>(i, i + 1, relativeMotion, VOCovarianceModel));
  52. }
  53. // inital values
  54. Values initial;
  55. for (int i = 0; i < numberNodes; ++i) {
  56. initial.insert(i, poses[i]);
  57. }
  58. LevenbergMarquardtParams params;
  59. params.setVerbosity("ERROR");
  60. params.setOrderingType("METIS");
  61. params.setLinearSolverType("MULTIFRONTAL_CHOLESKY");
  62. LevenbergMarquardtOptimizer optimizer(graph, initial, params);
  63. auto result = optimizer.optimize();
  64. }
  65. int main(int args, char* argv[]) {
  66. int numberNodes = stoi(argv[1]);
  67. cout << "number of_nodes: " << numberNodes << endl;
  68. testGtsam(numberNodes);
  69. return 0;
  70. }