test_pose_graph.cpp 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151
  1. // This file is part of OpenCV project.
  2. // It is subject to the license terms in the LICENSE file found in the top-level directory
  3. // of this distribution and at http://opencv.org/license.html
  4. #include "test_precomp.hpp"
  5. namespace opencv_test { namespace {
  6. using namespace cv;
  7. static Affine3d readAffine(std::istream& input)
  8. {
  9. Vec3d p;
  10. Vec4d q;
  11. input >> p[0] >> p[1] >> p[2];
  12. input >> q[1] >> q[2] >> q[3] >> q[0];
  13. // Normalize the quaternion to account for precision loss due to
  14. // serialization.
  15. return Affine3d(Quatd(q).toRotMat3x3(), p);
  16. };
  17. // Rewritten from Ceres pose graph demo: https://ceres-solver.org/
  18. static Ptr<kinfu::detail::PoseGraph> readG2OFile(const std::string& g2oFileName)
  19. {
  20. Ptr<kinfu::detail::PoseGraph> pg = kinfu::detail::PoseGraph::create();
  21. // for debugging purposes
  22. size_t minId = 0, maxId = 1 << 30;
  23. std::ifstream infile(g2oFileName.c_str());
  24. if (!infile)
  25. {
  26. CV_Error(cv::Error::StsError, "failed to open file");
  27. }
  28. while (infile.good())
  29. {
  30. std::string data_type;
  31. // Read whether the type is a node or a constraint
  32. infile >> data_type;
  33. if (data_type == "VERTEX_SE3:QUAT")
  34. {
  35. size_t id;
  36. infile >> id;
  37. Affine3d pose = readAffine(infile);
  38. if (id < minId || id >= maxId)
  39. continue;
  40. bool fixed = (id == minId);
  41. // Ensure we don't have duplicate poses
  42. if (pg->isNodeExist(id))
  43. {
  44. CV_LOG_INFO(NULL, "duplicated node, id=" << id);
  45. }
  46. pg->addNode(id, pose, fixed);
  47. }
  48. else if (data_type == "EDGE_SE3:QUAT")
  49. {
  50. size_t startId, endId;
  51. infile >> startId >> endId;
  52. Affine3d pose = readAffine(infile);
  53. Matx66d info;
  54. for (int i = 0; i < 6 && infile.good(); ++i)
  55. {
  56. for (int j = i; j < 6 && infile.good(); ++j)
  57. {
  58. infile >> info(i, j);
  59. if (i != j)
  60. {
  61. info(j, i) = info(i, j);
  62. }
  63. }
  64. }
  65. if ((startId >= minId && startId < maxId) && (endId >= minId && endId < maxId))
  66. {
  67. pg->addEdge(startId, endId, pose, info);
  68. }
  69. }
  70. else
  71. {
  72. CV_Error(cv::Error::StsError, "unknown tag");
  73. }
  74. // Clear any trailing whitespace from the line
  75. infile >> std::ws;
  76. }
  77. return pg;
  78. }
  79. TEST( PoseGraph, sphereG2O )
  80. {
  81. // Test takes 15+ sec in Release mode and 400+ sec in Debug mode
  82. applyTestTag(CV_TEST_TAG_LONG, CV_TEST_TAG_DEBUG_VERYLONG);
  83. // The dataset was taken from here: https://lucacarlone.mit.edu/datasets/
  84. // Connected paper:
  85. // L.Carlone, R.Tron, K.Daniilidis, and F.Dellaert.
  86. // Initialization Techniques for 3D SLAM : a Survey on Rotation Estimation and its Use in Pose Graph Optimization.
  87. // In IEEE Intl.Conf.on Robotics and Automation(ICRA), pages 4597 - 4604, 2015.
  88. std::string filename = cvtest::TS::ptr()->get_data_path() + "rgbd/sphere_bignoise_vertex3.g2o";
  89. Ptr<kinfu::detail::PoseGraph> pg = readG2OFile(filename);
  90. #ifdef HAVE_EIGEN
  91. // You may change logging level to view detailed optimization report
  92. // For example, set env. variable like this: OPENCV_LOG_LEVEL=INFO
  93. int iters = pg->optimize();
  94. ASSERT_GE(iters, 0);
  95. ASSERT_LE(iters, 36); // should converge in 36 iterations
  96. double energy = pg->calcEnergy();
  97. ASSERT_LE(energy, 1.47723e+06); // should converge to 1.47722e+06 or less
  98. // Add the "--test_debug" to arguments to see resulting pose graph nodes positions
  99. if (cvtest::debugLevel > 0)
  100. {
  101. // Write edge-only model of how nodes are located in space
  102. std::string fname = "pgout.obj";
  103. std::fstream of(fname, std::fstream::out);
  104. std::vector<size_t> ids = pg->getNodesIds();
  105. for (const size_t& id : ids)
  106. {
  107. Point3d d = pg->getNodePose(id).translation();
  108. of << "v " << d.x << " " << d.y << " " << d.z << std::endl;
  109. }
  110. size_t esz = pg->getNumEdges();
  111. for (size_t i = 0; i < esz; i++)
  112. {
  113. size_t sid = pg->getEdgeStart(i), tid = pg->getEdgeEnd(i);
  114. of << "l " << sid + 1 << " " << tid + 1 << std::endl;
  115. }
  116. of.close();
  117. }
  118. #else
  119. throw SkipTestException("Build with Eigen required for pose graph optimization");
  120. #endif
  121. }
  122. }} // namespace