testSimulated2DOriented.cpp 2.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172
  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 testSimulated2DOriented.cpp
  10. * @date Jun 10, 2010
  11. * @author nikai
  12. * @brief unit tests for simulated2DOriented
  13. */
  14. #include <tests/simulated2D.h>
  15. #include <tests/simulated2DOriented.h>
  16. #include <gtsam/inference/Symbol.h>
  17. #include <gtsam/base/Testable.h>
  18. #include <gtsam/base/numericalDerivative.h>
  19. using namespace std;
  20. using namespace gtsam;
  21. #include <iostream>
  22. #include <CppUnitLite/TestHarness.h>
  23. // Convenience for named keys
  24. using symbol_shorthand::X;
  25. using symbol_shorthand::L;
  26. /* ************************************************************************* */
  27. TEST( simulated2DOriented, Dprior )
  28. {
  29. Pose2 x(1,-9, 0.1);
  30. Matrix numerical = numericalDerivative11(simulated2DOriented::prior,x);
  31. Matrix computed;
  32. simulated2DOriented::prior(x,computed);
  33. CHECK(assert_equal(numerical,computed,1e-9));
  34. }
  35. /* ************************************************************************* */
  36. TEST( simulated2DOriented, DOdo )
  37. {
  38. Pose2 x1(1,-9,0.1),x2(-5,6,0.2);
  39. Matrix H1,H2;
  40. simulated2DOriented::odo(x1,x2,H1,H2);
  41. Matrix A1 = numericalDerivative21(simulated2DOriented::odo,x1,x2);
  42. CHECK(assert_equal(A1,H1,1e-9));
  43. Matrix A2 = numericalDerivative22(simulated2DOriented::odo,x1,x2);
  44. CHECK(assert_equal(A2,H2,1e-9));
  45. }
  46. /* ************************************************************************* */
  47. TEST( simulated2DOriented, constructor )
  48. {
  49. Pose2 measurement(0.2, 0.3, 0.1);
  50. SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector3(1., 1., 1.));
  51. simulated2DOriented::Odometry factor(measurement, model, X(1), X(2));
  52. simulated2DOriented::Values config;
  53. config.insert(X(1), Pose2(1., 0., 0.2));
  54. config.insert(X(2), Pose2(2., 0., 0.1));
  55. boost::shared_ptr<GaussianFactor> lf = factor.linearize(config);
  56. }
  57. /* ************************************************************************* */
  58. int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
  59. /* ************************************************************************* */