testOrientedPlane3Factor.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 testOrientedPlane3Factor.cpp
14  * @date Dec 19, 2012
15  * @author Alex Trevor
16  * @brief Tests the OrientedPlane3Factor class
17  */
18 
20 
22 #include <gtsam/inference/Symbol.h>
24 #include <gtsam/nonlinear/ISAM2.h>
25 
27 
28 using namespace std::placeholders;
29 using namespace gtsam;
30 using namespace std;
31 
34 
35 using symbol_shorthand::P; //< Planes
36 using symbol_shorthand::X; //< Pose3
37 
38 // *************************************************************************
39 TEST(OrientedPlane3Factor, lm_translation_error) {
40  // Tests one pose, two measurements of the landmark that differ in range only.
41  // Normal along -x, 3m away
42  OrientedPlane3 test_lm0(-1.0, 0.0, 0.0, 3.0);
43 
45 
46  // Init pose and prior. Pose Prior is needed since a single plane measurement
47  // does not fully constrain the pose
48  Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));
49  Vector6 sigmas;
50  sigmas << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001;
51  graph.addPrior(X(0), init_pose, noiseModel::Diagonal::Sigmas(sigmas));
52 
53  // Add two landmark measurements, differing in range
54  Vector3 sigmas3 {0.1, 0.1, 0.1};
55  Vector4 measurement0 {-1.0, 0.0, 0.0, 3.0};
56  OrientedPlane3Factor factor0(
57  measurement0, noiseModel::Diagonal::Sigmas(sigmas3), X(0), P(0));
58  graph.add(factor0);
59  Vector4 measurement1 {-1.0, 0.0, 0.0, 1.0};
61  measurement1, noiseModel::Diagonal::Sigmas(sigmas3), X(0), P(0));
62  graph.add(factor1);
63 
64  // Initial Estimate
65  Values values;
66  values.insert(X(0), init_pose);
67  values.insert(P(0), test_lm0);
68 
69  // Optimize
70  ISAM2 isam2;
71  ISAM2Result result = isam2.update(graph, values);
72  Values result_values = isam2.calculateEstimate();
73  OrientedPlane3 optimized_plane_landmark =
74  result_values.at<OrientedPlane3>(P(0));
75 
76  // Given two noisy measurements of equal weight, expect result between the two
77  OrientedPlane3 expected_plane_landmark(-1.0, 0.0, 0.0, 2.0);
78  EXPECT(assert_equal(optimized_plane_landmark, expected_plane_landmark));
79 }
80 
81 // *************************************************************************
82 // TODO As described in PR #564 after correcting the derivatives in
83 // OrientedPlane3Factor this test fails. It should be debugged and re-enabled.
84 /*
85 TEST (OrientedPlane3Factor, lm_rotation_error) {
86  // Tests one pose, two measurements of the landmark that differ in angle only.
87  // Normal along -x, 3m away
88  OrientedPlane3 test_lm0(-1.0/sqrt(1.01), 0.1/sqrt(1.01), 0.0, 3.0);
89 
90  NonlinearFactorGraph graph;
91 
92  // Init pose and prior. Pose Prior is needed since a single plane measurement does not fully constrain the pose
93  Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));
94  graph.addPrior(X(0), init_pose,
95  noiseModel::Diagonal::Sigmas(
96  (Vector(6) << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001).finished()));
97 
98  // Add two landmark measurements, differing in angle
99  Vector4 measurement0 {-1.0, 0.0, 0.0, 3.0};
100  OrientedPlane3Factor factor0(measurement0,
101  noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1)), X(0), P(0));
102  graph.add(factor0);
103  Vector4 measurement1 {0.0, -1.0, 0.0, 3.0};
104  OrientedPlane3Factor factor1(measurement1,
105  noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1)), X(0), P(0));
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  ISAM2Result result = isam2.update(graph, values);
116  Values result_values = isam2.calculateEstimate();
117  auto optimized_plane_landmark = result_values.at<OrientedPlane3>(P(0));
118 
119  // Given two noisy measurements of equal weight, expect result between the two
120  OrientedPlane3 expected_plane_landmark(-sqrt(2.0) / 2.0, -sqrt(2.0) / 2.0,
121  0.0, 3.0);
122  EXPECT(assert_equal(optimized_plane_landmark, expected_plane_landmark));
123 }
124 */
125 
126 // *************************************************************************
127 TEST( OrientedPlane3Factor, Derivatives ) {
128  // Measurement
129  OrientedPlane3 p(sqrt(2)/2, -sqrt(2)/2, 0, 5);
130 
131  // Linearisation point
132  OrientedPlane3 pLin(sqrt(3)/3, -sqrt(3)/3, sqrt(3)/3, 7);
133  gtsam::Point3 pointLin = gtsam::Point3(1, 2, -4);
134  gtsam::Rot3 rotationLin = gtsam::Rot3::RzRyRx(0.5*M_PI, -0.3*M_PI, 1.4*M_PI);
135  Pose3 poseLin(rotationLin, pointLin);
136 
137  // Factor
138  Key planeKey(1), poseKey(2);
139  SharedGaussian noise = noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1));
140  OrientedPlane3Factor factor(p.planeCoefficients(), noise, poseKey, planeKey);
141 
142  // Calculate numerical derivatives
143  auto f = [&factor](const Pose3& p, const OrientedPlane3& o) {
144  return factor.evaluateError(p, o);
145  };
146  Matrix numericalH1 = numericalDerivative21<Vector, Pose3, OrientedPlane3>(f, poseLin, pLin);
147  Matrix numericalH2 = numericalDerivative22<Vector, Pose3, OrientedPlane3>(f, poseLin, pLin);
148 
149  // Use the factor to calculate the derivative
150  Matrix actualH1, actualH2;
151  factor.evaluateError(poseLin, pLin, actualH1, actualH2);
152 
153  // Verify we get the expected error
154  EXPECT(assert_equal(numericalH1, actualH1, 1e-8));
155  EXPECT(assert_equal(numericalH2, actualH2, 1e-8));
156 }
157 
158 // *************************************************************************
160 
161  // Example: pitch and roll of aircraft in an ENU Cartesian frame.
162  // If pitch and roll are zero for an aerospace frame,
163  // that means Z is pointing down, i.e., direction of Z = (0,0,-1)
164 
165  Vector4 planeOrientation = (Vector(4) << 0.0, 0.0, -1.0, 10.0).finished(); // all vertical planes directly facing the origin
166 
167  // Factor
168  Key key(1);
169  SharedGaussian model = noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 10.0));
170  OrientedPlane3DirectionPrior factor(key, planeOrientation, model);
171 
172  // Create a linearization point at the zero-error point
173  Vector4 theta1 {0.0, 0.02, -1.2, 10.0};
174  Vector4 theta2 {0.0, 0.1, -0.8, 10.0};
175  Vector4 theta3 {0.0, 0.2, -0.9, 10.0};
176 
177  OrientedPlane3 T1(theta1);
178  OrientedPlane3 T2(theta2);
179  OrientedPlane3 T3(theta3);
180 
181  // Calculate numerical derivatives
182  Matrix expectedH1 = numericalDerivative11<Vector, OrientedPlane3>(
183  [&factor](const OrientedPlane3& o) {return factor.evaluateError(o);}, T1);
184 
185  Matrix expectedH2 = numericalDerivative11<Vector, OrientedPlane3>(
186  [&factor](const OrientedPlane3& o) {return factor.evaluateError(o);}, T2);
187 
188  Matrix expectedH3 = numericalDerivative11<Vector, OrientedPlane3>(
189  [&factor](const OrientedPlane3& o) { return factor.evaluateError(o); }, T3);
190 
191  // Use the factor to calculate the derivative
192  Matrix actualH1, actualH2, actualH3;
193  factor.evaluateError(T1, actualH1);
194  factor.evaluateError(T2, actualH2);
195  factor.evaluateError(T3, actualH3);
196 
197  // Verify we get the expected error
198  EXPECT(assert_equal(expectedH1, actualH1, 1e-8));
199  EXPECT(assert_equal(expectedH2, actualH2, 1e-8));
200  EXPECT(assert_equal(expectedH3, actualH3, 1e-8));
201 }
202 
203 /* ************************************************************************* */
204 // Simplified version of the test by Marco Camurri to debug issue #561
205 TEST(OrientedPlane3Factor, Issue561Simplified) {
206  // Typedefs
207  using Plane = OrientedPlane3;
208 
210 
211  // Setup prior factors
212  // Note: If x0 is too far away from the origin (e.g. x=100) this test can fail.
213  Pose3 x0(Rot3::Identity(), Vector3(10, -1, 1));
214  auto x0_noise = noiseModel::Isotropic::Sigma(6, 0.01);
215  graph.addPrior<Pose3>(X(0), x0, x0_noise);
216 
217  // Two horizontal planes with different heights, in the world frame.
218  const Plane p1(0,0,1,1), p2(0,0,1,2);
219  auto p1_noise = noiseModel::Diagonal::Sigmas(Vector3{1, 1, 5});
220  auto p2_noise = noiseModel::Diagonal::Sigmas(Vector3{1, 1, 5});
221  graph.addPrior<Plane>(P(1), p1, p1_noise);
222  graph.addPrior<Plane>(P(2), p2, p2_noise);
223 
224  // Plane factors
225  auto p1_measured_from_x0 = p1.transform(x0); // transform p1 to pose x0 as a measurement
226  auto p2_measured_from_x0 = p2.transform(x0); // transform p2 to pose x0 as a measurement
227  const auto x0_p1_noise = noiseModel::Isotropic::Sigma(3, 0.05);
228  const auto x0_p2_noise = noiseModel::Isotropic::Sigma(3, 0.05);
230  p1_measured_from_x0.planeCoefficients(), x0_p1_noise, X(0), P(1));
232  p2_measured_from_x0.planeCoefficients(), x0_p2_noise, X(0), P(2));
233 
234  // Initial values
235  // Just offset the initial pose by 1m. This is what we are trying to optimize.
236  Values initialEstimate;
237  Pose3 x0_initial = x0.compose(Pose3(Rot3::Identity(), Vector3(1,0,0)));
238  initialEstimate.insert(P(1), p1);
239  initialEstimate.insert(P(2), p2);
240  initialEstimate.insert(X(0), x0_initial);
241 
242  // Optimize
243  try {
244  GaussNewtonOptimizer optimizer(graph, initialEstimate);
245  Values result = optimizer.optimize();
246  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 0.1);
247  EXPECT(x0.equals(result.at<Pose3>(X(0))));
248  EXPECT(p1.equals(result.at<Plane>(P(1))));
249  EXPECT(p2.equals(result.at<Plane>(P(2))));
250  } catch (const IndeterminantLinearSystemException &e) {
251  std::cerr << "CAPTURED THE EXCEPTION: " << DefaultKeyFormatter(e.nearbyVariable()) << std::endl;
252  EXPECT(false); // fail if this happens
253  }
254 }
255 
256 /* ************************************************************************* */
257 int main() {
258  srand(time(nullptr));
259  TestResult tr;
260  return TestRegistry::runAllTests(tr);
261 }
262 /* ************************************************************************* */
const gtsam::Symbol key('X', 0)
const gtsam::Key poseKey
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx={}, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hz={})
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
Definition: Rot3M.cpp:84
virtual const Values & optimize()
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
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
noiseModel::Diagonal::shared_ptr model
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.
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
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
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
#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
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Vector evaluateError(const OrientedPlane3 &plane, OptionalMatrixType H) const override
Values result
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
#define EXPECT(condition)
Definition: Test.h:150
static Point2 measurement1(323.0, 240.0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
#define time
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TEST(OrientedPlane3Factor, lm_translation_error)
double error(const Values &values) const
Class compose(const Class &g) const
Definition: Lie.h:48
traits
Definition: chartTesting.h:28
static Symbol x0('x', 0)
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
Definition: Manifold.h:177
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
Vector4 planeCoefficients() const
Returns the plane coefficients.
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
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
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:53