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 #include <boost/assign/std/vector.hpp>
29 #include <boost/assign/std.hpp>
30 #include <boost/bind.hpp>
31 
32 using namespace boost::assign;
33 using namespace gtsam;
34 using namespace std;
35 
38 
39 using symbol_shorthand::P; //< Planes
40 using symbol_shorthand::X; //< Pose3
41 
42 // *************************************************************************
43 TEST(OrientedPlane3Factor, lm_translation_error) {
44  // Tests one pose, two measurements of the landmark that differ in range only.
45  // Normal along -x, 3m away
46  OrientedPlane3 test_lm0(-1.0, 0.0, 0.0, 3.0);
47 
49 
50  // Init pose and prior. Pose Prior is needed since a single plane measurement
51  // does not fully constrain the pose
52  Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));
53  Vector6 sigmas;
54  sigmas << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001;
55  graph.addPrior(X(0), init_pose, noiseModel::Diagonal::Sigmas(sigmas));
56 
57  // Add two landmark measurements, differing in range
58  Vector3 sigmas3 {0.1, 0.1, 0.1};
59  Vector4 measurement0 {-1.0, 0.0, 0.0, 3.0};
60  OrientedPlane3Factor factor0(
61  measurement0, noiseModel::Diagonal::Sigmas(sigmas3), X(0), P(0));
62  graph.add(factor0);
63  Vector4 measurement1 {-1.0, 0.0, 0.0, 1.0};
64  OrientedPlane3Factor factor1(
65  measurement1, noiseModel::Diagonal::Sigmas(sigmas3), X(0), P(0));
66  graph.add(factor1);
67 
68  // Initial Estimate
69  Values values;
70  values.insert(X(0), init_pose);
71  values.insert(P(0), test_lm0);
72 
73  // Optimize
74  ISAM2 isam2;
75  ISAM2Result result = isam2.update(graph, values);
76  Values result_values = isam2.calculateEstimate();
77  OrientedPlane3 optimized_plane_landmark =
78  result_values.at<OrientedPlane3>(P(0));
79 
80  // Given two noisy measurements of equal weight, expect result between the two
81  OrientedPlane3 expected_plane_landmark(-1.0, 0.0, 0.0, 2.0);
82  EXPECT(assert_equal(optimized_plane_landmark, expected_plane_landmark));
83 }
84 
85 // *************************************************************************
86 // TODO As described in PR #564 after correcting the derivatives in
87 // OrientedPlane3Factor this test fails. It should be debugged and re-enabled.
88 /*
89 TEST (OrientedPlane3Factor, lm_rotation_error) {
90  // Tests one pose, two measurements of the landmark that differ in angle only.
91  // Normal along -x, 3m away
92  OrientedPlane3 test_lm0(-1.0/sqrt(1.01), 0.1/sqrt(1.01), 0.0, 3.0);
93 
94  NonlinearFactorGraph graph;
95 
96  // Init pose and prior. Pose Prior is needed since a single plane measurement does not fully constrain the pose
97  Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));
98  graph.addPrior(X(0), init_pose,
99  noiseModel::Diagonal::Sigmas(
100  (Vector(6) << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001).finished()));
101 
102  // Add two landmark measurements, differing in angle
103  Vector4 measurement0 {-1.0, 0.0, 0.0, 3.0};
104  OrientedPlane3Factor factor0(measurement0,
105  noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1)), X(0), P(0));
106  graph.add(factor0);
107  Vector4 measurement1 {0.0, -1.0, 0.0, 3.0};
108  OrientedPlane3Factor factor1(measurement1,
109  noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1)), X(0), P(0));
110  graph.add(factor1);
111 
112  // Initial Estimate
113  Values values;
114  values.insert(X(0), init_pose);
115  values.insert(P(0), test_lm0);
116 
117  // Optimize
118  ISAM2 isam2;
119  ISAM2Result result = isam2.update(graph, values);
120  Values result_values = isam2.calculateEstimate();
121  auto optimized_plane_landmark = result_values.at<OrientedPlane3>(P(0));
122 
123  // Given two noisy measurements of equal weight, expect result between the two
124  OrientedPlane3 expected_plane_landmark(-sqrt(2.0) / 2.0, -sqrt(2.0) / 2.0,
125  0.0, 3.0);
126  EXPECT(assert_equal(optimized_plane_landmark, expected_plane_landmark));
127 }
128 */
129 
130 // *************************************************************************
131 TEST( OrientedPlane3Factor, Derivatives ) {
132  // Measurement
133  OrientedPlane3 p(sqrt(2)/2, -sqrt(2)/2, 0, 5);
134 
135  // Linearisation point
136  OrientedPlane3 pLin(sqrt(3)/3, -sqrt(3)/3, sqrt(3)/3, 7);
137  gtsam::Point3 pointLin = gtsam::Point3(1, 2, -4);
138  gtsam::Rot3 rotationLin = gtsam::Rot3::RzRyRx(0.5*M_PI, -0.3*M_PI, 1.4*M_PI);
139  Pose3 poseLin(rotationLin, pointLin);
140 
141  // Factor
142  Key planeKey(1), poseKey(2);
143  SharedGaussian noise = noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1));
144  OrientedPlane3Factor factor(p.planeCoefficients(), noise, poseKey, planeKey);
145 
146  // Calculate numerical derivatives
147  boost::function<Vector(const Pose3&, const OrientedPlane3&)> f = boost::bind(
148  &OrientedPlane3Factor::evaluateError, factor, _1, _2, boost::none, boost::none);
149  Matrix numericalH1 = numericalDerivative21<Vector, Pose3, OrientedPlane3>(f, poseLin, pLin);
150  Matrix numericalH2 = numericalDerivative22<Vector, Pose3, OrientedPlane3>(f, poseLin, pLin);
151 
152  // Use the factor to calculate the derivative
153  Matrix actualH1, actualH2;
154  factor.evaluateError(poseLin, pLin, actualH1, actualH2);
155 
156  // Verify we get the expected error
157  EXPECT(assert_equal(numericalH1, actualH1, 1e-8));
158  EXPECT(assert_equal(numericalH2, actualH2, 1e-8));
159 }
160 
161 // *************************************************************************
163 
164  // Example: pitch and roll of aircraft in an ENU Cartesian frame.
165  // If pitch and roll are zero for an aerospace frame,
166  // that means Z is pointing down, i.e., direction of Z = (0,0,-1)
167 
168  Vector4 planeOrientation = (Vector(4) << 0.0, 0.0, -1.0, 10.0).finished(); // all vertical planes directly facing the origin
169 
170  // Factor
171  Key key(1);
172  SharedGaussian model = noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 10.0));
173  OrientedPlane3DirectionPrior factor(key, planeOrientation, model);
174 
175  // Create a linearization point at the zero-error point
176  Vector4 theta1 {0.0, 0.02, -1.2, 10.0};
177  Vector4 theta2 {0.0, 0.1, -0.8, 10.0};
178  Vector4 theta3 {0.0, 0.2, -0.9, 10.0};
179 
180  OrientedPlane3 T1(theta1);
181  OrientedPlane3 T2(theta2);
182  OrientedPlane3 T3(theta3);
183 
184  // Calculate numerical derivatives
185  Matrix expectedH1 = numericalDerivative11<Vector, OrientedPlane3>(
186  boost::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, _1,
187  boost::none), T1);
188 
189  Matrix expectedH2 = numericalDerivative11<Vector, OrientedPlane3>(
190  boost::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, _1,
191  boost::none), T2);
192 
193  Matrix expectedH3 = numericalDerivative11<Vector, OrientedPlane3>(
194  boost::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, _1,
195  boost::none), T3);
196 
197  // Use the factor to calculate the derivative
198  Matrix actualH1, actualH2, actualH3;
199  factor.evaluateError(T1, actualH1);
200  factor.evaluateError(T2, actualH2);
201  factor.evaluateError(T3, actualH3);
202 
203  // Verify we get the expected error
204  EXPECT(assert_equal(expectedH1, actualH1, 1e-8));
205  EXPECT(assert_equal(expectedH2, actualH2, 1e-8));
206  EXPECT(assert_equal(expectedH3, actualH3, 1e-8));
207 }
208 
209 /* ************************************************************************* */
210 // Simplified version of the test by Marco Camurri to debug issue #561
211 TEST(OrientedPlane3Factor, Issue561Simplified) {
212  // Typedefs
213  using Plane = OrientedPlane3;
214 
216 
217  // Setup prior factors
218  // Note: If x0 is too far away from the origin (e.g. x=100) this test can fail.
219  Pose3 x0(Rot3::identity(), Vector3(10, -1, 1));
220  auto x0_noise = noiseModel::Isotropic::Sigma(6, 0.01);
221  graph.addPrior<Pose3>(X(0), x0, x0_noise);
222 
223  // Two horizontal planes with different heights, in the world frame.
224  const Plane p1(0,0,1,1), p2(0,0,1,2);
225  auto p1_noise = noiseModel::Diagonal::Sigmas(Vector3{1, 1, 5});
226  auto p2_noise = noiseModel::Diagonal::Sigmas(Vector3{1, 1, 5});
227  graph.addPrior<Plane>(P(1), p1, p1_noise);
228  graph.addPrior<Plane>(P(2), p2, p2_noise);
229 
230  // Plane factors
231  auto p1_measured_from_x0 = p1.transform(x0); // transform p1 to pose x0 as a measurement
232  auto p2_measured_from_x0 = p2.transform(x0); // transform p2 to pose x0 as a measurement
233  const auto x0_p1_noise = noiseModel::Isotropic::Sigma(3, 0.05);
234  const auto x0_p2_noise = noiseModel::Isotropic::Sigma(3, 0.05);
236  p1_measured_from_x0.planeCoefficients(), x0_p1_noise, X(0), P(1));
238  p2_measured_from_x0.planeCoefficients(), x0_p2_noise, X(0), P(2));
239 
240  // Initial values
241  // Just offset the initial pose by 1m. This is what we are trying to optimize.
242  Values initialEstimate;
243  Pose3 x0_initial = x0.compose(Pose3(Rot3::identity(), Vector3(1,0,0)));
244  initialEstimate.insert(P(1), p1);
245  initialEstimate.insert(P(2), p2);
246  initialEstimate.insert(X(0), x0_initial);
247 
248  // Optimize
249  try {
250  GaussNewtonOptimizer optimizer(graph, initialEstimate);
251  Values result = optimizer.optimize();
252  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 0.1);
253  EXPECT(x0.equals(result.at<Pose3>(X(0))));
254  EXPECT(p1.equals(result.at<Plane>(P(1))));
255  EXPECT(p2.equals(result.at<Plane>(P(2))));
256  } catch (const IndeterminantLinearSystemException &e) {
257  std::cerr << "CAPTURED THE EXCEPTION: " << DefaultKeyFormatter(e.nearbyVariable()) << std::endl;
258  EXPECT(false); // fail if this happens
259  }
260 }
261 
262 /* ************************************************************************* */
263 int main() {
264  srand(time(nullptr));
265  TestResult tr;
266  return TestRegistry::runAllTests(tr);
267 }
268 /* ************************************************************************* */
const gtsam::Key poseKey
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
Definition: Pose3.cpp:114
virtual const Values & optimize()
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector3f p1
noiseModel::Diagonal::shared_ptr model
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
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Definition: Half.h:150
Some functions to compute numerical derivatives.
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
#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)
Values calculateEstimate() const
Definition: ISAM2.cpp:763
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.)
TEST(OrientedPlane3Factor, lm_translation_error)
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
float * p
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
Vector4 planeCoefficients() const
Returns the plane coefficients.
Vector3 Point3
Definition: Point3.h:35
double error(const Values &values) const
Pose2 T1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)))
#define X
Definition: icosphere.cpp:20
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Vector evaluateError(const OrientedPlane3 &plane, boost::optional< Matrix & > H=boost::none) const override
noiseModel::Gaussian::shared_ptr SharedGaussian
Definition: NoiseModel.h:735
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:174
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:48:26