testBoundingConstraint.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276
  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 testBoundingConstraint.cpp
  10. * @brief test of nonlinear inequality constraints on scalar bounds
  11. * @author Alex Cunningham
  12. */
  13. #include <tests/simulated2DConstraints.h>
  14. #include <gtsam/inference/Symbol.h>
  15. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  16. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  17. #include <CppUnitLite/TestHarness.h>
  18. namespace iq2D = simulated2D::inequality_constraints;
  19. using namespace std;
  20. using namespace gtsam;
  21. static const double tol = 1e-5;
  22. SharedDiagonal soft_model2 = noiseModel::Unit::Create(2);
  23. SharedDiagonal soft_model2_alt = noiseModel::Isotropic::Sigma(2, 0.1);
  24. SharedDiagonal hard_model1 = noiseModel::Constrained::All(1);
  25. // some simple inequality constraints
  26. gtsam::Key key = 1;
  27. double mu = 10.0;
  28. // greater than
  29. iq2D::PoseXInequality constraint1(key, 1.0, true, mu);
  30. iq2D::PoseYInequality constraint2(key, 2.0, true, mu);
  31. // less than
  32. iq2D::PoseXInequality constraint3(key, 1.0, false, mu);
  33. iq2D::PoseYInequality constraint4(key, 2.0, false, mu);
  34. /* ************************************************************************* */
  35. TEST( testBoundingConstraint, unary_basics_inactive1 ) {
  36. Point2 pt1(2.0, 3.0);
  37. Values config;
  38. config.insert(key, pt1);
  39. EXPECT(!constraint1.active(config));
  40. EXPECT(!constraint2.active(config));
  41. EXPECT_DOUBLES_EQUAL(1.0, constraint1.threshold(), tol);
  42. EXPECT_DOUBLES_EQUAL(2.0, constraint2.threshold(), tol);
  43. EXPECT(constraint1.isGreaterThan());
  44. EXPECT(constraint2.isGreaterThan());
  45. EXPECT(assert_equal(I_1x1, constraint1.evaluateError(pt1), tol));
  46. EXPECT(assert_equal(I_1x1, constraint2.evaluateError(pt1), tol));
  47. EXPECT(assert_equal(Z_1x1, constraint1.unwhitenedError(config), tol));
  48. EXPECT(assert_equal(Z_1x1, constraint2.unwhitenedError(config), tol));
  49. EXPECT_DOUBLES_EQUAL(0.0, constraint1.error(config), tol);
  50. EXPECT_DOUBLES_EQUAL(0.0, constraint2.error(config), tol);
  51. }
  52. /* ************************************************************************* */
  53. TEST( testBoundingConstraint, unary_basics_inactive2 ) {
  54. Point2 pt2(-2.0, -3.0);
  55. Values config;
  56. config.insert(key, pt2);
  57. EXPECT(!constraint3.active(config));
  58. EXPECT(!constraint4.active(config));
  59. EXPECT_DOUBLES_EQUAL(1.0, constraint3.threshold(), tol);
  60. EXPECT_DOUBLES_EQUAL(2.0, constraint4.threshold(), tol);
  61. EXPECT(!constraint3.isGreaterThan());
  62. EXPECT(!constraint4.isGreaterThan());
  63. EXPECT(assert_equal(Vector::Constant(1, 3.0), constraint3.evaluateError(pt2), tol));
  64. EXPECT(assert_equal(Vector::Constant(1, 5.0), constraint4.evaluateError(pt2), tol));
  65. EXPECT(assert_equal(Z_1x1, constraint3.unwhitenedError(config), tol));
  66. EXPECT(assert_equal(Z_1x1, constraint4.unwhitenedError(config), tol));
  67. EXPECT_DOUBLES_EQUAL(0.0, constraint3.error(config), tol);
  68. EXPECT_DOUBLES_EQUAL(0.0, constraint4.error(config), tol);
  69. }
  70. /* ************************************************************************* */
  71. TEST( testBoundingConstraint, unary_basics_active1 ) {
  72. Point2 pt2(-2.0, -3.0);
  73. Values config;
  74. config.insert(key, pt2);
  75. EXPECT(constraint1.active(config));
  76. EXPECT(constraint2.active(config));
  77. EXPECT(assert_equal(Vector::Constant(1,-3.0), constraint1.evaluateError(pt2), tol));
  78. EXPECT(assert_equal(Vector::Constant(1,-5.0), constraint2.evaluateError(pt2), tol));
  79. EXPECT(assert_equal(Vector::Constant(1,-3.0), constraint1.unwhitenedError(config), tol));
  80. EXPECT(assert_equal(Vector::Constant(1,-5.0), constraint2.unwhitenedError(config), tol));
  81. EXPECT_DOUBLES_EQUAL(45.0, constraint1.error(config), tol);
  82. EXPECT_DOUBLES_EQUAL(125.0, constraint2.error(config), tol);
  83. }
  84. /* ************************************************************************* */
  85. TEST( testBoundingConstraint, unary_basics_active2 ) {
  86. Point2 pt1(2.0, 3.0);
  87. Values config;
  88. config.insert(key, pt1);
  89. EXPECT(constraint3.active(config));
  90. EXPECT(constraint4.active(config));
  91. EXPECT(assert_equal(-1.0 * I_1x1, constraint3.evaluateError(pt1), tol));
  92. EXPECT(assert_equal(-1.0 * I_1x1, constraint4.evaluateError(pt1), tol));
  93. EXPECT(assert_equal(-1.0 * I_1x1, constraint3.unwhitenedError(config), tol));
  94. EXPECT(assert_equal(-1.0 * I_1x1, constraint4.unwhitenedError(config), tol));
  95. EXPECT_DOUBLES_EQUAL(5.0, constraint3.error(config), tol);
  96. EXPECT_DOUBLES_EQUAL(5.0, constraint4.error(config), tol);
  97. }
  98. /* ************************************************************************* */
  99. TEST( testBoundingConstraint, unary_linearization_inactive) {
  100. Point2 pt1(2.0, 3.0);
  101. Values config1;
  102. config1.insert(key, pt1);
  103. GaussianFactor::shared_ptr actual1 = constraint1.linearize(config1);
  104. GaussianFactor::shared_ptr actual2 = constraint2.linearize(config1);
  105. EXPECT(!actual1);
  106. EXPECT(!actual2);
  107. }
  108. /* ************************************************************************* */
  109. TEST( testBoundingConstraint, unary_linearization_active) {
  110. Point2 pt2(-2.0, -3.0);
  111. Values config2;
  112. config2.insert(key, pt2);
  113. GaussianFactor::shared_ptr actual1 = constraint1.linearize(config2);
  114. GaussianFactor::shared_ptr actual2 = constraint2.linearize(config2);
  115. JacobianFactor expected1(key, (Matrix(1, 2) << 1.0, 0.0).finished(), Vector::Constant(1, 3.0), hard_model1);
  116. JacobianFactor expected2(key, (Matrix(1, 2) << 0.0, 1.0).finished(), Vector::Constant(1, 5.0), hard_model1);
  117. EXPECT(assert_equal((const GaussianFactor&)expected1, *actual1, tol));
  118. EXPECT(assert_equal((const GaussianFactor&)expected2, *actual2, tol));
  119. }
  120. /* ************************************************************************* */
  121. TEST( testBoundingConstraint, unary_simple_optimization1) {
  122. // create a single-node graph with a soft and hard constraint to
  123. // ensure that the hard constraint overrides the soft constraint
  124. Point2 goal_pt(1.0, 2.0);
  125. Point2 start_pt(0.0, 1.0);
  126. NonlinearFactorGraph graph;
  127. Symbol x1('x',1);
  128. graph += iq2D::PoseXInequality(x1, 1.0, true);
  129. graph += iq2D::PoseYInequality(x1, 2.0, true);
  130. graph += simulated2D::Prior(start_pt, soft_model2, x1);
  131. Values initValues;
  132. initValues.insert(x1, start_pt);
  133. Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
  134. Values expected;
  135. expected.insert(x1, goal_pt);
  136. CHECK(assert_equal(expected, actual, tol));
  137. }
  138. /* ************************************************************************* */
  139. TEST( testBoundingConstraint, unary_simple_optimization2) {
  140. // create a single-node graph with a soft and hard constraint to
  141. // ensure that the hard constraint overrides the soft constraint
  142. Point2 goal_pt(1.0, 2.0);
  143. Point2 start_pt(2.0, 3.0);
  144. NonlinearFactorGraph graph;
  145. graph += iq2D::PoseXInequality(key, 1.0, false);
  146. graph += iq2D::PoseYInequality(key, 2.0, false);
  147. graph += simulated2D::Prior(start_pt, soft_model2, key);
  148. Values initValues;
  149. initValues.insert(key, start_pt);
  150. Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
  151. Values expected;
  152. expected.insert(key, goal_pt);
  153. CHECK(assert_equal(expected, actual, tol));
  154. }
  155. /* ************************************************************************* */
  156. TEST( testBoundingConstraint, MaxDistance_basics) {
  157. gtsam::Key key1 = 1, key2 = 2;
  158. Point2 pt1(0,0), pt2(1.0, 0.0), pt3(2.0, 0.0), pt4(3.0, 0.0);
  159. iq2D::PoseMaxDistConstraint rangeBound(key1, key2, 2.0, mu);
  160. EXPECT_DOUBLES_EQUAL(2.0, rangeBound.threshold(), tol);
  161. EXPECT(!rangeBound.isGreaterThan());
  162. EXPECT(rangeBound.dim() == 1);
  163. EXPECT(assert_equal((Vector(1) << 2.0).finished(), rangeBound.evaluateError(pt1, pt1)));
  164. EXPECT(assert_equal(I_1x1, rangeBound.evaluateError(pt1, pt2)));
  165. EXPECT(assert_equal(Z_1x1, rangeBound.evaluateError(pt1, pt3)));
  166. EXPECT(assert_equal(-1.0*I_1x1, rangeBound.evaluateError(pt1, pt4)));
  167. Values config1;
  168. config1.insert(key1, pt1);
  169. config1.insert(key2, pt1);
  170. EXPECT(!rangeBound.active(config1));
  171. EXPECT(assert_equal(Z_1x1, rangeBound.unwhitenedError(config1)));
  172. EXPECT(!rangeBound.linearize(config1));
  173. EXPECT_DOUBLES_EQUAL(0.0, rangeBound.error(config1), tol);
  174. config1.update(key2, pt2);
  175. EXPECT(!rangeBound.active(config1));
  176. EXPECT(assert_equal(Z_1x1, rangeBound.unwhitenedError(config1)));
  177. EXPECT(!rangeBound.linearize(config1));
  178. EXPECT_DOUBLES_EQUAL(0.0, rangeBound.error(config1), tol);
  179. config1.update(key2, pt3);
  180. EXPECT(rangeBound.active(config1));
  181. EXPECT(assert_equal(Z_1x1, rangeBound.unwhitenedError(config1)));
  182. EXPECT_DOUBLES_EQUAL(0.0, rangeBound.error(config1), tol);
  183. config1.update(key2, pt4);
  184. EXPECT(rangeBound.active(config1));
  185. EXPECT(assert_equal(-1.0*I_1x1, rangeBound.unwhitenedError(config1)));
  186. EXPECT_DOUBLES_EQUAL(0.5*mu, rangeBound.error(config1), tol);
  187. }
  188. /* ************************************************************************* */
  189. TEST( testBoundingConstraint, MaxDistance_simple_optimization) {
  190. Point2 pt1(0,0), pt2_init(5.0, 0.0), pt2_goal(2.0, 0.0);
  191. Symbol x1('x',1), x2('x',2);
  192. NonlinearFactorGraph graph;
  193. graph += simulated2D::equality_constraints::UnaryEqualityConstraint(pt1, x1);
  194. graph += simulated2D::Prior(pt2_init, soft_model2_alt, x2);
  195. graph += iq2D::PoseMaxDistConstraint(x1, x2, 2.0);
  196. Values initial_state;
  197. initial_state.insert(x1, pt1);
  198. initial_state.insert(x2, pt2_init);
  199. Values expected;
  200. expected.insert(x1, pt1);
  201. expected.insert(x2, pt2_goal);
  202. // FAILS: VectorValues assertion failure
  203. // Optimizer::shared_values actual = Optimizer::optimizeLM(graph, initial_state);
  204. // EXPECT(assert_equal(expected, *actual, tol));
  205. }
  206. /* ************************************************************************* */
  207. TEST( testBoundingConstraint, avoid_demo) {
  208. Symbol x1('x',1), x2('x',2), x3('x',3), l1('l',1);
  209. double radius = 1.0;
  210. Point2 x1_pt(0,0), x2_init(2.0, 0.5), x2_goal(2.0, 1.0), x3_pt(4.0, 0.0), l1_pt(2.0, 0.0);
  211. Point2 odo(2.0, 0.0);
  212. NonlinearFactorGraph graph;
  213. graph += simulated2D::equality_constraints::UnaryEqualityConstraint(x1_pt, x1);
  214. graph += simulated2D::Odometry(odo, soft_model2_alt, x1, x2);
  215. graph += iq2D::LandmarkAvoid(x2, l1, radius);
  216. graph += simulated2D::equality_constraints::UnaryEqualityPointConstraint(l1_pt, l1);
  217. graph += simulated2D::Odometry(odo, soft_model2_alt, x2, x3);
  218. graph += simulated2D::equality_constraints::UnaryEqualityConstraint(x3_pt, x3);
  219. Values init, expected;
  220. init.insert(x1, x1_pt);
  221. init.insert(x3, x3_pt);
  222. init.insert(l1, l1_pt);
  223. expected = init;
  224. init.insert(x2, x2_init);
  225. expected.insert(x2, x2_goal);
  226. // FAILS: segfaults on optimization
  227. // Optimizer::shared_values actual = Optimizer::optimizeLM(graph, init);
  228. // EXPECT(assert_equal(expected, *actual, tol));
  229. }
  230. /* ************************************************************************* */
  231. int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
  232. /* ************************************************************************* */