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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:47:59