testPartialPriorFactor.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 
13 #include <gtsam/inference/Symbol.h>
14 #include <gtsam/geometry/Pose2.h>
15 #include <gtsam/geometry/Pose3.h>
19 
20 using namespace std;
21 using namespace gtsam;
22 
23 namespace NM = gtsam::noiseModel;
24 
25 // Pose3 tangent representation is [ Rx Ry Rz Tx Ty Tz ].
26 static const int kIndexRx = 0;
27 static const int kIndexRy = 1;
28 static const int kIndexRz = 2;
29 static const int kIndexTx = 3;
30 static const int kIndexTy = 4;
31 static const int kIndexTz = 5;
32 
35 typedef std::vector<size_t> Indices;
36 
38 namespace gtsam {
39 template<>
40 struct traits<TestPartialPriorFactor2> : public Testable<TestPartialPriorFactor2> {};
41 
42 template<>
43 struct traits<TestPartialPriorFactor3> : public Testable<TestPartialPriorFactor3> {};
44 }
45 
46 /* ************************************************************************* */
47 TEST(PartialPriorFactor, Constructors2) {
48  Key poseKey(1);
49  Pose2 measurement(-13.1, 3.14, -0.73);
50 
51  // Prior on x component of translation.
52  TestPartialPriorFactor2 factor1(poseKey, 0, measurement.x(), NM::Isotropic::Sigma(1, 0.25));
53  CHECK(assert_equal(1, factor1.prior().rows()));
54  CHECK(assert_equal(measurement.x(), factor1.prior()(0)));
55  CHECK(assert_container_equality<Indices>({ 0 }, factor1.indices()));
56 
57  // Prior on full translation vector.
58  const Indices t_indices = { 0, 1 };
59  TestPartialPriorFactor2 factor2(poseKey, t_indices, measurement.translation(), NM::Isotropic::Sigma(2, 0.25));
60  CHECK(assert_equal(2, factor2.prior().rows()));
61  CHECK(assert_equal(measurement.translation(), factor2.prior()));
62  CHECK(assert_container_equality<Indices>(t_indices, factor2.indices()));
63 
64  // Prior on theta.
65  TestPartialPriorFactor2 factor3(poseKey, 2, measurement.theta(), NM::Isotropic::Sigma(1, 0.1));
66  CHECK(assert_equal(1, factor3.prior().rows()));
67  CHECK(assert_equal(measurement.theta(), factor3.prior()(0)));
68  CHECK(assert_container_equality<Indices>({ 2 }, factor3.indices()));
69 }
70 
71 /* ************************************************************************* */
72 TEST(PartialPriorFactor, JacobianPartialTranslation2) {
73  Key poseKey(1);
74  Pose2 measurement(-13.1, 3.14, -0.73);
75 
76  // Prior on x component of translation.
77  TestPartialPriorFactor2 factor(poseKey, 0, measurement.x(), NM::Isotropic::Sigma(1, 0.25));
78 
79  Pose2 pose = measurement; // Zero-error linearization point.
80 
81  // Calculate numerical derivatives.
82  Matrix expectedH1 = numericalDerivative11<Vector, Pose2>(
83  boost::bind(&TestPartialPriorFactor2::evaluateError, &factor, _1, boost::none), pose);
84 
85  // Use the factor to calculate the derivative.
86  Matrix actualH1;
87  factor.evaluateError(pose, actualH1);
88 
89  // Verify we get the expected error.
90  CHECK(assert_equal(expectedH1, actualH1, 1e-5));
91 }
92 
93 /* ************************************************************************* */
94 TEST(PartialPriorFactor, JacobianFullTranslation2) {
95  Key poseKey(1);
96  Pose2 measurement(-6.0, 3.5, 0.123);
97 
98  // Prior on x component of translation.
99  TestPartialPriorFactor2 factor(poseKey, { 0, 1 }, measurement.translation(), NM::Isotropic::Sigma(2, 0.25));
100 
101  Pose2 pose = measurement; // Zero-error linearization point.
102 
103  // Calculate numerical derivatives.
104  Matrix expectedH1 = numericalDerivative11<Vector, Pose2>(
105  boost::bind(&TestPartialPriorFactor2::evaluateError, &factor, _1, boost::none), pose);
106 
107  // Use the factor to calculate the derivative.
108  Matrix actualH1;
109  factor.evaluateError(pose, actualH1);
110 
111  // Verify we get the expected error.
112  CHECK(assert_equal(expectedH1, actualH1, 1e-5));
113 }
114 
115 /* ************************************************************************* */
116 TEST(PartialPriorFactor, JacobianTheta) {
117  Key poseKey(1);
118  Pose2 measurement(-1.0, 0.4, -2.5);
119 
120  // Prior on x component of translation.
121  TestPartialPriorFactor2 factor(poseKey, 2, measurement.theta(), NM::Isotropic::Sigma(1, 0.25));
122 
123  Pose2 pose = measurement; // Zero-error linearization point.
124 
125  // Calculate numerical derivatives.
126  Matrix expectedH1 = numericalDerivative11<Vector, Pose2>(
127  boost::bind(&TestPartialPriorFactor2::evaluateError, &factor, _1, boost::none), pose);
128 
129  // Use the factor to calculate the derivative.
130  Matrix actualH1;
131  factor.evaluateError(pose, actualH1);
132 
133  // Verify we get the expected error.
134  CHECK(assert_equal(expectedH1, actualH1, 1e-5));
135 }
136 
137 /* ************************************************************************* */
138 TEST(PartialPriorFactor, Constructors3) {
139  Key poseKey(1);
140  Pose3 measurement(Rot3::RzRyRx(-0.17, 0.567, M_PI), Point3(10.0, -2.3, 3.14));
141 
142  // Single component of translation.
143  TestPartialPriorFactor3 factor1(poseKey, kIndexTy, measurement.y(),
144  NM::Isotropic::Sigma(1, 0.25));
145  CHECK(assert_equal(1, factor1.prior().rows()));
146  CHECK(assert_equal(measurement.y(), factor1.prior()(0)));
147  CHECK(assert_container_equality<Indices>({ kIndexTy }, factor1.indices()));
148 
149  // Full translation vector.
150  const Indices t_indices = { kIndexTx, kIndexTy, kIndexTz };
151  TestPartialPriorFactor3 factor2(poseKey, t_indices, measurement.translation(),
152  NM::Isotropic::Sigma(3, 0.25));
153  CHECK(assert_equal(3, factor2.prior().rows()));
154  CHECK(assert_equal(measurement.translation(), factor2.prior()));
155  CHECK(assert_container_equality<Indices>(t_indices, factor2.indices()));
156 
157  // Full tangent vector of rotation.
158  const Indices r_indices = { kIndexRx, kIndexRy, kIndexRz };
159  TestPartialPriorFactor3 factor3(poseKey, r_indices, Rot3::Logmap(measurement.rotation()),
160  NM::Isotropic::Sigma(3, 0.1));
161  CHECK(assert_equal(3, factor3.prior().rows()));
162  CHECK(assert_equal(Rot3::Logmap(measurement.rotation()), factor3.prior()));
163  CHECK(assert_container_equality<Indices>(r_indices, factor3.indices()));
164 }
165 
166 /* ************************************************************************* */
167 TEST(PartialPriorFactor, JacobianAtIdentity3) {
168  Key poseKey(1);
169  Pose3 measurement = Pose3::identity();
171 
172  TestPartialPriorFactor3 factor(poseKey, kIndexTy, measurement.translation().y(), model);
173 
174  Pose3 pose = measurement; // Zero-error linearization point.
175 
176  // Calculate numerical derivatives.
177  Matrix expectedH1 = numericalDerivative11<Vector, Pose3>(
178  boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose);
179 
180  // Use the factor to calculate the derivative.
181  Matrix actualH1;
182  factor.evaluateError(pose, actualH1);
183 
184  // Verify we get the expected error.
185  CHECK(assert_equal(expectedH1, actualH1, 1e-5));
186 }
187 
188 /* ************************************************************************* */
189 TEST(PartialPriorFactor, JacobianPartialTranslation3) {
190  Key poseKey(1);
191  Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0));
193 
194  TestPartialPriorFactor3 factor(poseKey, kIndexTy, measurement.translation().y(), model);
195 
196  Pose3 pose = measurement; // Zero-error linearization point.
197 
198  // Calculate numerical derivatives.
199  Matrix expectedH1 = numericalDerivative11<Vector, Pose3>(
200  boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose);
201 
202  // Use the factor to calculate the derivative.
203  Matrix actualH1;
204  factor.evaluateError(pose, actualH1);
205 
206  // Verify we get the expected error.
207  CHECK(assert_equal(expectedH1, actualH1, 1e-5));
208 }
209 
210 /* ************************************************************************* */
211 TEST(PartialPriorFactor, JacobianFullTranslation3) {
212  Key poseKey(1);
213  Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0));
215 
216  std::vector<size_t> translationIndices = { kIndexTx, kIndexTy, kIndexTz };
217  TestPartialPriorFactor3 factor(poseKey, translationIndices, measurement.translation(), model);
218 
219  // Create a linearization point at the zero-error point
220  Pose3 pose = measurement; // Zero-error linearization point.
221 
222  // Calculate numerical derivatives.
223  Matrix expectedH1 = numericalDerivative11<Vector, Pose3>(
224  boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose);
225 
226  // Use the factor to calculate the derivative.
227  Matrix actualH1;
228  factor.evaluateError(pose, actualH1);
229 
230  // Verify we get the expected error.
231  CHECK(assert_equal(expectedH1, actualH1, 1e-5));
232 }
233 
234 /* ************************************************************************* */
235 TEST(PartialPriorFactor, JacobianTxTz3) {
236  Key poseKey(1);
237  Pose3 measurement(Rot3::RzRyRx(-0.17, 0.567, M_PI), Point3(10.0, -2.3, 3.14));
239 
240  std::vector<size_t> translationIndices = { kIndexTx, kIndexTz };
241  TestPartialPriorFactor3 factor(poseKey, translationIndices,
242  (Vector(2) << measurement.x(), measurement.z()).finished(), model);
243 
244  Pose3 pose = measurement; // Zero-error linearization point.
245 
246  // Calculate numerical derivatives.
247  Matrix expectedH1 = numericalDerivative11<Vector, Pose3>(
248  boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose);
249 
250  // Use the factor to calculate the derivative.
251  Matrix actualH1;
252  factor.evaluateError(pose, actualH1);
253 
254  // Verify we get the expected error.
255  CHECK(assert_equal(expectedH1, actualH1, 1e-5));
256 }
257 
258 /* ************************************************************************* */
259 TEST(PartialPriorFactor, JacobianFullRotation3) {
260  Key poseKey(1);
261  Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0));
263 
264  std::vector<size_t> rotationIndices = { kIndexRx, kIndexRy, kIndexRz };
265  TestPartialPriorFactor3 factor(poseKey, rotationIndices, Rot3::Logmap(measurement.rotation()), model);
266 
267  Pose3 pose = measurement; // Zero-error linearization point.
268 
269  // Calculate numerical derivatives.
270  Matrix expectedH1 = numericalDerivative11<Vector, Pose3>(
271  boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose);
272 
273  // Use the factor to calculate the derivative.
274  Matrix actualH1;
275  factor.evaluateError(pose, actualH1);
276 
277  // Verify we get the expected error.
278  CHECK(assert_equal(expectedH1, actualH1, 1e-5));
279 }
280 
281 /* ************************************************************************* */
282 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
283 /* ************************************************************************* */
const gtsam::Key poseKey
Provides additional testing facilities for common data structures.
#define CHECK(condition)
Definition: Test.h:109
PartialPriorFactor< Pose2 > TestPartialPriorFactor2
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
TEST(PartialPriorFactor, Constructors2)
static const int kIndexRz
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define M_PI
Definition: main.h:78
size_t rows() const
double measurement(10.0)
Definition: Half.h:150
static const int kIndexTz
Some functions to compute numerical derivatives.
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
PartialPriorFactor< Pose3 > TestPartialPriorFactor3
const Point2 & translation() const
translation
Definition: Pose2.h:230
Vector evaluateError(const T &p, boost::optional< Matrix & > H=boost::none) const override
JacobianFactor factor3(keyY, A32, keyZ, A33, b3, noiseModel::Isotropic::Sigma(2, sigma3))
static const int kIndexTy
double x() const
get x
Definition: Pose3.h:269
A simple prior factor that allows for setting a prior only on a part of linear parameters.
double theta() const
get theta
Definition: Pose2.h:221
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
double y() const
get y
Definition: Pose3.h:274
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const int kIndexRy
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
double x() const
get x
Definition: Pose2.h:215
static const int kIndexRx
JacobianFactor factor2(keyX, A21, keyY, A22, b2, noiseModel::Isotropic::Sigma(2, sigma2))
std::vector< size_t > Indices
Vector3 Point3
Definition: Point3.h:35
2D Pose
3D Pose
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567
double z() const
get z
Definition: Pose3.h:279
All noise models live in the noiseModel namespace.
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))
static const int kIndexTx


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