testLocalOrientedPlane3Factor.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
12 /*
13  * @file testLocalOrientedPlane3Factor.cpp
14  * @date Feb 12, 2021
15  * @author David Wisth
16  * @brief Tests the LocalOrientedPlane3Factor class
17  */
18 
20 
22 #include <gtsam/inference/Symbol.h>
23 #include <gtsam/nonlinear/ISAM2.h>
24 
26 #include "gtsam/base/Vector.h"
28 #include "gtsam/geometry/Pose3.h"
29 
30 using namespace std::placeholders;
31 using namespace gtsam;
32 using namespace std;
33 
36 
37 using symbol_shorthand::P; //< Planes
38 using symbol_shorthand::X; //< Pose3
39 
40 // *************************************************************************
41 TEST(LocalOrientedPlane3Factor, lm_translation_error) {
42  // Tests one pose, two measurements of the landmark that differ in range only.
43  // Normal along -x, 3m away
44  OrientedPlane3 test_lm0(-1.0, 0.0, 0.0, 3.0);
45 
47 
48  // Init pose and prior. Pose Prior is needed since a single plane measurement
49  // does not fully constrain the pose
50  Pose3 init_pose = Pose3::Identity();
51  Pose3 anchor_pose = Pose3::Identity();
52  graph.addPrior(X(0), init_pose, noiseModel::Isotropic::Sigma(6, 0.001));
53  graph.addPrior(X(1), anchor_pose, noiseModel::Isotropic::Sigma(6, 0.001));
54 
55  // Add two landmark measurements, differing in range
56  Vector4 measurement0(-1.0, 0.0, 0.0, 3.0);
57  Vector4 measurement1(-1.0, 0.0, 0.0, 1.0);
59  measurement0, noiseModel::Isotropic::Sigma(3, 0.1), X(0), X(1), P(0));
61  measurement1, noiseModel::Isotropic::Sigma(3, 0.1), X(0), X(1), P(0));
62  graph.add(factor0);
63  graph.add(factor1);
64 
65  // Initial Estimate
66  Values values;
67  values.insert(X(0), init_pose);
68  values.insert(X(1), anchor_pose);
69  values.insert(P(0), test_lm0);
70 
71  // Optimize
72  ISAM2 isam2;
73  isam2.update(graph, values);
74  Values result_values = isam2.calculateEstimate();
75  auto optimized_plane_landmark = result_values.at<OrientedPlane3>(P(0));
76 
77  // Given two noisy measurements of equal weight, expect result between the two
78  OrientedPlane3 expected_plane_landmark(-1.0, 0.0, 0.0, 2.0);
79  EXPECT(assert_equal(optimized_plane_landmark, expected_plane_landmark));
80 }
81 
82 // *************************************************************************
83 // TODO As described in PR #564 after correcting the derivatives in
84 // OrientedPlane3Factor this test fails. It should be debugged and re-enabled.
85 /*
86 TEST (LocalOrientedPlane3Factor, lm_rotation_error) {
87  // Tests one pose, two measurements of the landmark that differ in angle only.
88  // Normal along -x, 3m away
89  OrientedPlane3 test_lm0(-1.0/sqrt(1.01), -0.1/sqrt(1.01), 0.0, 3.0);
90 
91  NonlinearFactorGraph graph;
92 
93  // Init pose and prior. Pose Prior is needed since a single plane measurement
94  // does not fully constrain the pose
95  Pose3 init_pose = Pose3::Identity();
96  graph.addPrior(X(0), init_pose, noiseModel::Isotropic::Sigma(6, 0.001));
97 
98  // Add two landmark measurements, differing in angle
99  Vector4 measurement0(-1.0, 0.0, 0.0, 3.0);
100  Vector4 measurement1(0.0, -1.0, 0.0, 3.0);
101  LocalOrientedPlane3Factor factor0(measurement0,
102  noiseModel::Isotropic::Sigma(3, 0.1), X(0), X(0), P(0));
103  LocalOrientedPlane3Factor factor1(measurement1,
104  noiseModel::Isotropic::Sigma(3, 0.1), X(0), X(0), P(0));
105  graph.add(factor0);
106  graph.add(factor1);
107 
108  // Initial Estimate
109  Values values;
110  values.insert(X(0), init_pose);
111  values.insert(P(0), test_lm0);
112 
113  // Optimize
114  ISAM2 isam2;
115  isam2.update(graph, values);
116  Values result_values = isam2.calculateEstimate();
117  isam2.getDelta().print();
118 
119  auto optimized_plane_landmark = result_values.at<OrientedPlane3>(P(0));
120 
121  values.print();
122  result_values.print();
123 
124  // Given two noisy measurements of equal weight, expect result between the two
125  OrientedPlane3 expected_plane_landmark(-sqrt(2.0) / 2.0, -sqrt(2.0) / 2.0,
126  0.0, 3.0);
127  EXPECT(assert_equal(optimized_plane_landmark, expected_plane_landmark));
128 }
129 */
130 
131 // *************************************************************************
133  // Measurement
134  OrientedPlane3 p(sqrt(2)/2, -sqrt(2)/2, 0, 5);
135 
136  // Linearisation point
137  OrientedPlane3 pLin(sqrt(3)/3, -sqrt(3)/3, sqrt(3)/3, 7);
138  Pose3 poseLin(Rot3::RzRyRx(0.5*M_PI, -0.3*M_PI, 1.4*M_PI), Point3(1, 2, -4));
139  Pose3 anchorPoseLin(Rot3::RzRyRx(-0.1*M_PI, 0.2*M_PI, 1.0), Point3(-5, 0, 1));
140 
141  // Factor
142  Key planeKey(1), poseKey(2), anchorPoseKey(3);
143  SharedGaussian noise = noiseModel::Isotropic::Sigma(3, 0.1);
144  LocalOrientedPlane3Factor factor(p, noise, poseKey, anchorPoseKey, planeKey);
145 
146  // Calculate numerical derivatives
147  auto f = [&factor] (const Pose3& p1, const Pose3& p2, const OrientedPlane3& a_plane) {
148  return factor.evaluateError(p1, p2, a_plane);
149  };
150 
151  Matrix numericalH1 = numericalDerivative31<Vector3, Pose3, Pose3,
152  OrientedPlane3>(f, poseLin, anchorPoseLin, pLin);
153  Matrix numericalH2 = numericalDerivative32<Vector3, Pose3, Pose3,
154  OrientedPlane3>(f, poseLin, anchorPoseLin, pLin);
155  Matrix numericalH3 = numericalDerivative33<Vector3, Pose3, Pose3,
156  OrientedPlane3>(f, poseLin, anchorPoseLin, pLin);
157 
158  // Use the factor to calculate the derivative
159  Matrix actualH1, actualH2, actualH3;
160  factor.evaluateError(poseLin, anchorPoseLin, pLin, actualH1, actualH2,
161  actualH3);
162 
163  // Verify we get the expected error
164  EXPECT(assert_equal(numericalH1, actualH1, 1e-8));
165  EXPECT(assert_equal(numericalH2, actualH2, 1e-8));
166  EXPECT(assert_equal(numericalH3, actualH3, 1e-8));
167 }
168 
169 
170 /* ************************************************************************* */
171 // Simplified version of the test by Marco Camurri to debug issue #561
172 //
173 // This test provides an example of how LocalOrientedPlane3Factor works.
174 // x0 is the current sensor pose, and x1 is the local "anchor pose" - i.e.
175 // a local linearisation point for the plane. The plane is representated and
176 // optimized in x1 frame in the optimization. This greatly improves numerical
177 // stability when the pose is far from the origin.
178 //
179 TEST(LocalOrientedPlane3Factor, Issue561Simplified) {
180  // Typedefs
181  using Plane = OrientedPlane3;
182 
184 
185  // Setup prior factors
186  Pose3 x0(Rot3::Identity(), Vector3(100, 30, 10)); // the "sensor pose"
187  Pose3 x1(Rot3::Identity(), Vector3(90, 40, 5) ); // the "anchor pose"
188 
189  auto x0_noise = noiseModel::Isotropic::Sigma(6, 0.01);
190  auto x1_noise = noiseModel::Isotropic::Sigma(6, 0.01);
191  graph.addPrior<Pose3>(X(0), x0, x0_noise);
192  graph.addPrior<Pose3>(X(1), x1, x1_noise);
193 
194  // Two horizontal planes with different heights, in the world frame.
195  const Plane p1(0, 0, 1, 1), p2(0, 0, 1, 2);
196  // Transform to x1, the "anchor frame" (i.e. local frame)
197  auto p1_in_x1 = p1.transform(x1);
198  auto p2_in_x1 = p2.transform(x1);
199  auto p1_noise = noiseModel::Diagonal::Sigmas(Vector3{1, 1, 5});
200  auto p2_noise = noiseModel::Diagonal::Sigmas(Vector3{1, 1, 5});
201  graph.addPrior<Plane>(P(1), p1_in_x1, p1_noise);
202  graph.addPrior<Plane>(P(2), p2_in_x1, p2_noise);
203 
204  // Add plane factors, with a local linearization point.
205  // transform p1 to pose x0 as a measurement
206  auto p1_measured_from_x0 = p1.transform(x0);
207  // transform p2 to pose x0 as a measurement
208  auto p2_measured_from_x0 = p2.transform(x0);
209  const auto x0_p1_noise = noiseModel::Isotropic::Sigma(3, 0.05);
210  const auto x0_p2_noise = noiseModel::Isotropic::Sigma(3, 0.05);
212  p1_measured_from_x0.planeCoefficients(), x0_p1_noise, X(0), X(1), P(1));
214  p2_measured_from_x0.planeCoefficients(), x0_p2_noise, X(0), X(1), P(2));
215 
216  // Initial values
217  // Just offset the initial pose by 1m. This is what we are trying to optimize.
218  Values initialEstimate;
219  Pose3 x0_initial = x0.compose(Pose3(Rot3::Identity(), Vector3(1, 0, 0)));
220  initialEstimate.insert(P(1), p1_in_x1);
221  initialEstimate.insert(P(2), p2_in_x1);
222  initialEstimate.insert(X(0), x0_initial);
223  initialEstimate.insert(X(1), x1);
224 
225  // Optimize
226  try {
227  ISAM2 isam2;
228  isam2.update(graph, initialEstimate);
229  Values result = isam2.calculateEstimate();
230  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 0.1);
231  EXPECT(x0.equals(result.at<Pose3>(X(0))));
232  EXPECT(p1_in_x1.equals(result.at<Plane>(P(1))));
233  EXPECT(p2_in_x1.equals(result.at<Plane>(P(2))));
234  } catch (const IndeterminantLinearSystemException &e) {
235  cerr << "CAPTURED THE EXCEPTION: "
236  << DefaultKeyFormatter(e.nearbyVariable()) << endl;
237  EXPECT(false); // fail if this happens
238  }
239 }
240 
241 /* ************************************************************************* */
242 int main() {
243  srand(time(nullptr));
244  TestResult tr;
245  return TestRegistry::runAllTests(tr);
246 }
247 /* ************************************************************************* */
const gtsam::Key poseKey
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:196
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector3f p1
const ValueType at(Key j) const
Definition: Values-inl.h:204
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
#define M_PI
Definition: main.h:106
leaf::MyValues values
Definition: BFloat16.h:88
Some functions to compute numerical derivatives.
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const std::optional< FastMap< Key, int > > &constrainedKeys={}, const std::optional< FastList< Key > > &noRelinKeys={}, const std::optional< FastList< Key > > &extraReelimKeys={}, bool force_relinearize=false)
Definition: ISAM2.cpp:400
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
Definition: Pose3.cpp:157
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
Represents an infinite plane in 3D, which is composed of a planar normal and its perpendicular distan...
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:214
Vector evaluateError(const Pose3 &wTwi, const Pose3 &wTwa, const OrientedPlane3 &a_plane, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Values result
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
#define EXPECT(condition)
Definition: Test.h:150
static Point2 measurement1(323.0, 240.0)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
#define time
Array< double, 1, 3 > e(1./3., 0.5, 2.)
double error(const Values &values) const
Class compose(const Class &g) const
Definition: Lie.h:48
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
static Symbol x0('x', 0)
TEST(LocalOrientedPlane3Factor, lm_translation_error)
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
Definition: Manifold.h:177
Pose3 x1
Definition: testPose3.cpp:663
float * p
void insert(Key j, const Value &val)
Definition: Values.cpp:155
static Point3 p2
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
Vector3 Point3
Definition: Point3.h:38
#define X
Definition: icosphere.cpp:20
3D Pose
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Values calculateEstimate() const
Definition: ISAM2.cpp:766
noiseModel::Gaussian::shared_ptr SharedGaussian
Definition: NoiseModel.h:742
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:176


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:38:40