testRot3Optimization.cpp 1.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. * Atlanta, Georgia 30332-0415
  4. * All Rights Reserved
  5. * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. * See LICENSE for the license information
  7. * -------------------------------------------------------------------------- */
  8. /**
  9. * @file testRot3.cpp
  10. * @brief Unit tests for Rot3Q class
  11. * @author Richard Roberts
  12. */
  13. #include <CppUnitLite/TestHarness.h>
  14. #include <gtsam/base/Testable.h>
  15. #include <boost/math/constants/constants.hpp>
  16. #include <gtsam/base/numericalDerivative.h>
  17. #include <gtsam/base/lieProxies.h>
  18. #include <gtsam/geometry/Point3.h>
  19. #include <gtsam/geometry/Rot3.h>
  20. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  21. #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
  22. #include <gtsam/inference/Symbol.h>
  23. #include <gtsam/slam/BetweenFactor.h>
  24. using namespace gtsam;
  25. typedef BetweenFactor<Rot3> Between;
  26. typedef NonlinearFactorGraph Graph;
  27. /* ************************************************************************* */
  28. TEST(Rot3, optimize) {
  29. // Optimize a circle
  30. Values truth;
  31. Values initial;
  32. Graph fg;
  33. fg.addPrior(Symbol('r',0), Rot3(), noiseModel::Isotropic::Sigma(3, 0.01));
  34. for(int j=0; j<6; ++j) {
  35. truth.insert(Symbol('r',j), Rot3::Rz(M_PI/3.0 * double(j)));
  36. initial.insert(Symbol('r',j), Rot3::Rz(M_PI/3.0 * double(j) + 0.1 * double(j%2)));
  37. fg += Between(Symbol('r',j), Symbol('r',(j+1)%6), Rot3::Rz(M_PI/3.0), noiseModel::Isotropic::Sigma(3, 0.01));
  38. }
  39. Values final = GaussNewtonOptimizer(fg, initial).optimize();
  40. EXPECT(assert_equal(truth, final, 1e-5));
  41. }
  42. /* ************************************************************************* */
  43. int main() {
  44. TestResult tr;
  45. return TestRegistry::runAllTests(tr);
  46. }
  47. /* ************************************************************************* */