testPoseToPointFactor.cpp
Go to the documentation of this file.
1 
12 
13 using namespace gtsam;
14 using namespace gtsam::noiseModel;
15 
16 /* ************************************************************************* */
17 // Verify zero error when there is no noise
18 TEST(PoseToPointFactor, errorNoiseless_2D) {
20  Point2 point(1.0, 2.0);
21  Point2 noise(0.0, 0.0);
22  Point2 measured = point + noise;
23 
24  Key pose_key(1);
25  Key point_key(2);
26  PoseToPointFactor<Pose2,Point2> factor(pose_key, point_key, measured,
27  Isotropic::Sigma(2, 0.05));
28  Vector expectedError = Vector2(0.0, 0.0);
29  Vector actualError = factor.evaluateError(pose, point);
30  EXPECT(assert_equal(expectedError, actualError, 1E-5));
31 }
32 
33 /* ************************************************************************* */
34 // Verify expected error in test scenario
35 TEST(PoseToPointFactor, errorNoise_2D) {
37  Point2 point(1.0, 2.0);
38  Point2 noise(-1.0, 0.5);
39  Point2 measured = point + noise;
40 
41  Key pose_key(1);
42  Key point_key(2);
43  PoseToPointFactor<Pose2,Point2> factor(pose_key, point_key, measured,
44  Isotropic::Sigma(2, 0.05));
45  Vector expectedError = -noise;
46  Vector actualError = factor.evaluateError(pose, point);
47  EXPECT(assert_equal(expectedError, actualError, 1E-5));
48 }
49 
50 /* ************************************************************************* */
51 // Check Jacobians are correct
52 TEST(PoseToPointFactor, jacobian_2D) {
53  // Measurement
54  gtsam::Point2 l_meas(1, 2);
55 
56  // Linearisation point
57  gtsam::Point2 p_t(-5, 12);
58  gtsam::Rot2 p_R(1.5 * M_PI);
59  Pose2 p(p_R, p_t);
60 
61  gtsam::Point2 l(3, 0);
62 
63  // Factor
64  Key pose_key(1);
65  Key point_key(2);
67  PoseToPointFactor<Pose2,Point2> factor(pose_key, point_key, l_meas, noise);
68 
69  // Calculate numerical derivatives
70  auto f = [&factor] (const Pose2& pose, const Point2& pt) {
71  return factor.evaluateError(pose, pt);
72  };
73  Matrix numerical_H1 = numericalDerivative21<Vector, Pose2, Point2>(f, p, l);
74  Matrix numerical_H2 = numericalDerivative22<Vector, Pose2, Point2>(f, p, l);
75 
76  // Use the factor to calculate the derivative
77  Matrix actual_H1;
78  Matrix actual_H2;
79  factor.evaluateError(p, l, actual_H1, actual_H2);
80 
81  // Verify we get the expected error
82  EXPECT(assert_equal(numerical_H1, actual_H1, 1e-8));
83  EXPECT(assert_equal(numerical_H2, actual_H2, 1e-8));
84 }
85 
86 /* ************************************************************************* */
87 // Verify zero error when there is no noise
88 TEST(PoseToPointFactor, errorNoiseless_3D) {
90  Point3 point(1.0, 2.0, 3.0);
91  Point3 noise(0.0, 0.0, 0.0);
92  Point3 measured = point + noise;
93 
94  Key pose_key(1);
95  Key point_key(2);
96  PoseToPointFactor<Pose3,Point3> factor(pose_key, point_key, measured,
97  Isotropic::Sigma(3, 0.05));
98  Vector expectedError = Vector3(0.0, 0.0, 0.0);
99  Vector actualError = factor.evaluateError(pose, point);
100  EXPECT(assert_equal(expectedError, actualError, 1E-5));
101 }
102 
103 /* ************************************************************************* */
104 // Verify expected error in test scenario
105 TEST(PoseToPointFactor, errorNoise_3D) {
107  Point3 point(1.0, 2.0, 3.0);
108  Point3 noise(-1.0, 0.5, 0.3);
109  Point3 measured = point + noise;
110 
111  Key pose_key(1);
112  Key point_key(2);
113  PoseToPointFactor<Pose3,Point3> factor(pose_key, point_key, measured,
114  Isotropic::Sigma(3, 0.05));
115  Vector expectedError = -noise;
116  Vector actualError = factor.evaluateError(pose, point);
117  EXPECT(assert_equal(expectedError, actualError, 1E-5));
118 }
119 
120 /* ************************************************************************* */
121 // Check Jacobians are correct
122 TEST(PoseToPointFactor, jacobian_3D) {
123  // Measurement
124  gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3);
125 
126  // Linearisation point
127  gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2);
128  gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5 * M_PI, -0.3 * M_PI, 0.4 * M_PI);
129  Pose3 p(p_R, p_t);
130 
131  gtsam::Point3 l = gtsam::Point3(3, 0, 5);
132 
133  // Factor
134  Key pose_key(1);
135  Key point_key(2);
136  SharedGaussian noise = noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1));
137  PoseToPointFactor<Pose3,Point3> factor(pose_key, point_key, l_meas, noise);
138 
139  // Calculate numerical derivatives
140  auto f = [&factor] (const Pose3& pose, const Point3& pt) {
141  return factor.evaluateError(pose, pt);
142  };
143 
144  Matrix numerical_H1 = numericalDerivative21<Vector, Pose3, Point3>(f, p, l);
145  Matrix numerical_H2 = numericalDerivative22<Vector, Pose3, Point3>(f, p, l);
146 
147  // Use the factor to calculate the derivative
148  Matrix actual_H1;
149  Matrix actual_H2;
150  factor.evaluateError(p, l, actual_H1, actual_H2);
151 
152  // Verify we get the expected error
153  EXPECT(assert_equal(numerical_H1, actual_H1, 1e-8));
154  EXPECT(assert_equal(numerical_H2, actual_H2, 1e-8));
155 }
156 
157 /* ************************************************************************* */
158 int main() {
159  TestResult tr;
160  return TestRegistry::runAllTests(tr);
161 }
162 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:42
TestHarness.h
measured
Point2 measured(-17, 30)
pt
static const Point3 pt(1.0, 2.0, 3.0)
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::noiseModel::Diagonal::Sigmas
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:291
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::Pose3::Identity
static Pose3 Identity()
identity for group operation
Definition: Pose3.h:106
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
numericalDerivative.h
Some functions to compute numerical derivatives.
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
l
static const Line3 l(Rot3(), 1, 1)
gtsam::PoseToPointFactor::evaluateError
Vector evaluateError(const POSE &w_T_b, const POINT &w_P, OptionalMatrixType H1, OptionalMatrixType H2) const override
Error = w_T_b.inverse()*w_P - measured_.
Definition: PoseToPointFactor.h:84
gtsam::Pose2::Identity
static Pose2 Identity()
identity for group operation
Definition: Pose2.h:125
gtsam::SharedGaussian
noiseModel::Gaussian::shared_ptr SharedGaussian
Definition: NoiseModel.h:763
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
main
int main()
Definition: testPoseToPointFactor.cpp:158
TestResult
Definition: TestResult.h:26
E
DiscreteKey E(5, 2)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::Rot2
Definition: Rot2.h:35
gtsam
traits
Definition: SFMdata.h:40
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
PoseToPointFactor.h
This factor can be used to model relative position measurements from a (2D or 3D) pose to a landmark.
gtsam::noiseModel
All noise models live in the noiseModel namespace.
Definition: LossFunctions.cpp:28
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:624
gtsam::PoseToPointFactor
Definition: PoseToPointFactor.h:24
M_PI
#define M_PI
Definition: mconf.h:117
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::Rot3::RzRyRx
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,...
Definition: Rot3M.cpp:84
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:11