testLinearContainerFactor.cpp
Go to the documentation of this file.
1 
13 #include <gtsam/geometry/Pose2.h>
14 #include <gtsam/geometry/Point3.h>
16 #include <boost/assign/std/vector.hpp>
17 
18 using namespace std;
19 using namespace boost::assign;
20 using namespace gtsam;
21 
22 const gtsam::noiseModel::Diagonal::shared_ptr diag_model2 = noiseModel::Diagonal::Sigmas(Vector2(1.0, 1.0));
23 const double tol = 1e-5;
24 
25 gtsam::Key l1 = 101, l2 = 102, x1 = 1, x2 = 2;
26 
27 Point2 landmark1(5.0, 1.5), landmark2(7.0, 1.5);
28 Pose2 poseA1(0.0, 0.0, 0.0), poseA2(2.0, 0.0, 0.0);
29 
30 /* ************************************************************************* */
31 TEST( testLinearContainerFactor, generic_jacobian_factor ) {
32 
33  Matrix A1 = (Matrix(2, 2) <<
34  2.74222, -0.0067457,
35  0.0, 2.63624).finished();
36  Matrix A2 = (Matrix(2, 2) <<
37  -0.0455167, -0.0443573,
38  -0.0222154, -0.102489).finished();
39  Vector b = Vector2(0.0277052,
40  -0.0533393);
41 
42  JacobianFactor expLinFactor(l1, A1, l2, A2, b, diag_model2);
43 
44  LinearContainerFactor actFactor(expLinFactor);
45  EXPECT_LONGS_EQUAL(2, actFactor.size());
46  EXPECT(actFactor.isJacobian());
47  EXPECT(!actFactor.isHessian());
48 
49  // check keys
50  EXPECT(assert_container_equality({l1, l2}, actFactor.keys()));
51 
52  Values values;
53  values.insert(l1, landmark1);
54  values.insert(l2, landmark2);
55  values.insert(x1, poseA1);
56  values.insert(x2, poseA2);
57 
58  // Check reconstruction
59  GaussianFactor::shared_ptr actLinearizationA = actFactor.linearize(values);
60  EXPECT(assert_equal(*expLinFactor.clone(), *actLinearizationA, tol));
61 }
62 
63 /* ************************************************************************* */
64 TEST( testLinearContainerFactor, jacobian_factor_withlinpoints ) {
65 
66  Matrix A1 = (Matrix(2, 2) <<
67  2.74222, -0.0067457,
68  0.0, 2.63624).finished();
69  Matrix A2 = (Matrix(2, 2) <<
70  -0.0455167, -0.0443573,
71  -0.0222154, -0.102489).finished();
72  Vector b = Vector2(0.0277052,
73  -0.0533393);
74 
75  JacobianFactor expLinFactor(l1, A1, l2, A2, b, diag_model2);
76 
77  Values values;
78  values.insert(l1, landmark1);
79  values.insert(l2, landmark2);
80  values.insert(x1, poseA1);
81  values.insert(x2, poseA2);
82 
83  LinearContainerFactor actFactor(expLinFactor, values);
84  LinearContainerFactor actFactorNolin(expLinFactor);
85 
86  EXPECT(assert_equal(actFactor, actFactor, tol));
87  EXPECT(assert_inequal(actFactor, actFactorNolin, tol));
88  EXPECT(assert_inequal(actFactorNolin, actFactor, tol));
89 
90  // Check contents
91  Values expLinPoint;
92  expLinPoint.insert(l1, landmark1);
93  expLinPoint.insert(l2, landmark2);
94  CHECK(actFactor.linearizationPoint());
95  EXPECT(actFactor.hasLinearizationPoint());
96  EXPECT(assert_equal(expLinPoint, *actFactor.linearizationPoint()));
97 
98  // Check error evaluation
99  Vector delta_l1 = Vector2(1.0, 2.0);
100  Vector delta_l2 = Vector2(3.0, 4.0);
101 
102  VectorValues delta = values.zeroVectors();
103  delta.at(l1) = delta_l1;
104  delta.at(l2) = delta_l2;
105  Values noisyValues = values.retract(delta);
106  double expError = expLinFactor.error(delta);
107  EXPECT_DOUBLES_EQUAL(expError, actFactor.error(noisyValues), tol);
108  EXPECT_DOUBLES_EQUAL(expLinFactor.error(values.zeroVectors()), actFactor.error(values), tol);
109 
110  // Check linearization with corrections for updated linearization point
111  GaussianFactor::shared_ptr actLinearizationB = actFactor.linearize(noisyValues);
112  Vector bprime = b - A1 * delta_l1 - A2 * delta_l2;
113  JacobianFactor expLinFactor2(l1, A1, l2, A2, bprime, diag_model2);
114  EXPECT(assert_equal(*expLinFactor2.clone(), *actLinearizationB, tol));
115 }
116 
117 /* ************************************************************************* */
118 TEST( testLinearContainerFactor, generic_hessian_factor ) {
119  Matrix G11 = (Matrix(1, 1) << 1.0).finished();
120  Matrix G12 = (Matrix(1, 2) << 2.0, 4.0).finished();
121  Matrix G13 = (Matrix(1, 3) << 3.0, 6.0, 9.0).finished();
122 
123  Matrix G22 = (Matrix(2, 2) << 3.0, 5.0,
124  0.0, 6.0).finished();
125  Matrix G23 = (Matrix(2, 3) << 4.0, 6.0, 8.0,
126  1.0, 2.0, 4.0).finished();
127 
128  Matrix G33 = (Matrix(3, 3) << 1.0, 2.0, 3.0,
129  0.0, 5.0, 6.0,
130  0.0, 0.0, 9.0).finished();
131 
132  Vector g1 = (Vector(1) << -7.0).finished();
133  Vector g2 = Vector2(-8.0, -9.0);
134  Vector g3 = Vector3(1.0, 2.0, 3.0);
135 
136  double f = 10.0;
137 
138  HessianFactor initFactor(x1, x2, l1,
139  G11, G12, G13, g1, G22, G23, g2, G33, g3, f);
140 
141  Values values;
142  values.insert(l1, landmark1);
143  values.insert(l2, landmark2);
144  values.insert(x1, poseA1);
145  values.insert(x2, poseA2);
146 
147  LinearContainerFactor actFactor(initFactor);
148  EXPECT(!actFactor.isJacobian());
149  EXPECT(actFactor.isHessian());
150 
151  GaussianFactor::shared_ptr actLinearization1 = actFactor.linearize(values);
152  EXPECT(assert_equal(*initFactor.clone(), *actLinearization1, tol));
153 }
154 
155 /* ************************************************************************* */
156 TEST( testLinearContainerFactor, hessian_factor_withlinpoints ) {
157  // 2 variable example, one pose, one landmark (planar)
158  // Initial ordering: x1, l1
159 
160  Matrix G11 = (Matrix(3, 3) <<
161  1.0, 2.0, 3.0,
162  0.0, 5.0, 6.0,
163  0.0, 0.0, 9.0).finished();
164  Matrix G12 = (Matrix(3, 2) <<
165  1.0, 2.0,
166  3.0, 5.0,
167  4.0, 6.0).finished();
168  Vector g1 = Vector3(1.0, 2.0, 3.0);
169 
170  Matrix G22 = (Matrix(2, 2) <<
171  0.5, 0.2,
172  0.0, 0.6).finished();
173 
174  Vector g2 = Vector2(-8.0, -9.0);
175 
176  double f = 10.0;
177 
178  // Construct full matrices
179  Matrix G(5,5);
180  G << G11, G12, Matrix::Zero(2,3), G22;
181 
182  HessianFactor initFactor(x1, l1, G11, G12, g1, G22, g2, f);
183 
184  Values linearizationPoint, expLinPoints;
185  linearizationPoint.insert(l1, landmark1);
186  linearizationPoint.insert(x1, poseA1);
187  expLinPoints = linearizationPoint;
188  linearizationPoint.insert(x2, poseA2);
189 
190  LinearContainerFactor actFactor(initFactor, linearizationPoint);
191  EXPECT(!actFactor.isJacobian());
192  EXPECT(actFactor.isHessian());
193 
194  EXPECT(actFactor.hasLinearizationPoint());
195  Values actLinPoint = *actFactor.linearizationPoint();
196  EXPECT(assert_equal(expLinPoints, actLinPoint));
197 
198  // Create delta
199  Vector delta_l1 = Vector2(1.0, 2.0);
200  Vector delta_x1 = Vector3(3.0, 4.0, 0.5);
201  Vector delta_x2 = Vector3(6.0, 7.0, 0.3);
202 
203  // Check error calculation
204  VectorValues delta = linearizationPoint.zeroVectors();
205  delta.at(l1) = delta_l1;
206  delta.at(x1) = delta_x1;
207  delta.at(x2) = delta_x2;
208  EXPECT(assert_equal((Vector(5) << 3.0, 4.0, 0.5, 1.0, 2.0).finished(), delta.vector(initFactor.keys())));
209  Values noisyValues = linearizationPoint.retract(delta);
210 
211  double expError = initFactor.error(delta);
212  EXPECT_DOUBLES_EQUAL(expError, actFactor.error(noisyValues), tol);
213  EXPECT_DOUBLES_EQUAL(initFactor.error(linearizationPoint.zeroVectors()), actFactor.error(linearizationPoint), tol);
214 
215  // Compute updated versions
216  Vector dv = (Vector(5) << 3.0, 4.0, 0.5, 1.0, 2.0).finished();
217  Vector g(5); g << g1, g2;
218  Vector g_prime = g - G.selfadjointView<Eigen::Upper>() * dv;
219 
220  // Check linearization with corrections for updated linearization point
221  Vector g1_prime = g_prime.head(3);
222  Vector g2_prime = g_prime.tail(2);
223  double f_prime = f + dv.transpose() * G.selfadjointView<Eigen::Upper>() * dv - 2.0 * dv.transpose() * g;
224  HessianFactor expNewFactor(x1, l1, G11, G12, g1_prime, G22, g2_prime, f_prime);
225  EXPECT(assert_equal(*expNewFactor.clone(), *actFactor.linearize(noisyValues), tol));
226 }
227 
228 /* ************************************************************************* */
229 TEST( testLinearContainerFactor, creation ) {
230  // Create a set of local keys (No robot label)
231  Key l1 = 11, l3 = 13, l5 = 15;
232 
233  // create a linear factor
234  SharedDiagonal model = noiseModel::Unit::Create(2);
235  JacobianFactor::shared_ptr linear_factor(new JacobianFactor(
236  l3, I_2x2, l5, 2.0 * I_2x2, Z_2x1, model));
237 
238  // create a set of values - build with full set of values
239  gtsam::Values full_values, exp_values;
240  full_values.insert(l3, Point2(1.0, 2.0));
241  full_values.insert(l5, Point2(4.0, 3.0));
242  exp_values = full_values;
243  full_values.insert(l1, Point2(3.0, 7.0));
244 
245  LinearContainerFactor actual(linear_factor, full_values);
246 
247  // Verify the keys
248  EXPECT(assert_container_equality({l3, l5}, actual.keys()));
249 
250  // Verify subset of linearization points
251  EXPECT(assert_equal(exp_values, actual.linearizationPoint(), tol));
252 }
253 
254 /* ************************************************************************* */
255 TEST( testLinearContainerFactor, jacobian_relinearize )
256 {
257  // Create a Between Factor from a Point3. This is actually a linear factor.
258  gtsam::Key key1(1);
259  gtsam::Key key2(2);
260  gtsam::Values linpoint1;
261  linpoint1.insert(key1, gtsam::Point3(-22.4, +8.5, +2.4));
262  linpoint1.insert(key2, gtsam::Point3(-21.0, +5.0, +21.0));
263 
264  gtsam::Point3 measured(1.0, -2.5, 17.8);
266  gtsam::BetweenFactor<gtsam::Point3> betweenFactor(key1, key2, measured, model);
267 
268  // Create a jacobian container factor at linpoint 1
269  gtsam::JacobianFactor::shared_ptr jacobian(new gtsam::JacobianFactor(*betweenFactor.linearize(linpoint1)));
270  gtsam::LinearContainerFactor jacobianContainer(jacobian, linpoint1);
271 
272  // Create a second linearization point
273  gtsam::Values linpoint2;
274  linpoint2.insert(key1, gtsam::Point3(+18.0, -0.25, +1.11));
275  linpoint2.insert(key2, gtsam::Point3(-10.0, +11.2, +0.05));
276 
277  // Check the error at linpoint2 versus the original factor
278  double expected_error = betweenFactor.error(linpoint2);
279  double actual_error = jacobianContainer.error(linpoint2);
280  EXPECT_DOUBLES_EQUAL(expected_error, actual_error, 1e-9 );
281 
282  // Re-linearize around the new point and check the factors
283  gtsam::GaussianFactor::shared_ptr expected_factor = betweenFactor.linearize(linpoint2);
284  gtsam::GaussianFactor::shared_ptr actual_factor = jacobianContainer.linearize(linpoint2);
285  CHECK(gtsam::assert_equal(*expected_factor, *actual_factor));
286 }
287 
288 /* ************************************************************************* */
289 TEST( testLinearContainerFactor, hessian_relinearize )
290 {
291  // Create a Between Factor from a Point3. This is actually a linear factor.
292  gtsam::Key key1(1);
293  gtsam::Key key2(2);
294  gtsam::Values linpoint1;
295  linpoint1.insert(key1, gtsam::Point3(-22.4, +8.5, +2.4));
296  linpoint1.insert(key2, gtsam::Point3(-21.0, +5.0, +21.0));
297 
298  gtsam::Point3 measured(1.0, -2.5, 17.8);
300  gtsam::BetweenFactor<gtsam::Point3> betweenFactor(key1, key2, measured, model);
301 
302  // Create a hessian container factor at linpoint 1
303  gtsam::HessianFactor::shared_ptr hessian(new gtsam::HessianFactor(*betweenFactor.linearize(linpoint1)));
304  gtsam::LinearContainerFactor hessianContainer(hessian, linpoint1);
305 
306  // Create a second linearization point
307  gtsam::Values linpoint2;
308  linpoint2.insert(key1, gtsam::Point3(+18.0, -0.25, +1.11));
309  linpoint2.insert(key2, gtsam::Point3(-10.0, +11.2, +0.05));
310 
311  // Check the error at linpoint2 versus the original factor
312  double expected_error = betweenFactor.error(linpoint2);
313  double actual_error = hessianContainer.error(linpoint2);
314  EXPECT_DOUBLES_EQUAL(expected_error, actual_error, 1e-9 );
315 
316  // Re-linearize around the new point and check the factors
318  gtsam::GaussianFactor::shared_ptr actual_factor = hessianContainer.linearize(linpoint2);
319  CHECK(gtsam::assert_equal(*expected_factor, *actual_factor));
320 }
321 
322 /* ************************************************************************* */
323 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
324 /* ************************************************************************* */
325 
Provides additional testing facilities for common data structures.
#define CHECK(condition)
Definition: Test.h:109
boost::shared_ptr< GaussianFactor > linearize(const Values &x) const override
double error(const Values &c) const override
const gtsam::noiseModel::Diagonal::shared_ptr diag_model2
Pose2 poseA2(2.0, 0.0, 0.0)
Scalar * b
Definition: benchVecAdd.cpp:17
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Pose2 poseA1(0.0, 0.0, 0.0)
VectorValues zeroVectors() const
Definition: Values.cpp:216
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
JacobiRotation< float > G
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector2 Point2
Definition: Point2.h:27
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
gtsam::Key l2
GaussianFactor::shared_ptr clone() const override
leaf::MyValues values
Definition: Half.h:150
Values retract(const VectorValues &delta) const
Definition: Values.cpp:109
gtsam::Key x1
Vector & at(Key j)
Definition: VectorValues.h:137
Point2 landmark1(5.0, 1.5)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
void g(const string &key, int i)
Definition: testBTree.cpp:43
bool assert_container_equality(const std::map< size_t, V2 > &expected, const std::map< size_t, V2 > &actual)
double error(const VectorValues &c) const override
const Symbol key1('v', 1)
Factor Graph Values.
Point2 landmark2(7.0, 1.5)
Eigen::VectorXd Vector
Definition: Vector.h:38
GaussianFactor::shared_ptr clone() const override
GTSAM_EXPORT bool isHessian() const
#define EXPECT(condition)
Definition: Test.h:151
const boost::optional< Values > & linearizationPoint() const
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
static const Symbol l3('l', 3)
Contains the HessianFactor class, a general quadratic factor.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TEST(testLinearContainerFactor, generic_jacobian_factor)
boost::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:301
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
gtsam::Key l1
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Eigen::Vector2d Vector2
Definition: Vector.h:42
size_t size() const
Definition: Factor.h:135
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
const KeyVector & keys() const
Access the factor&#39;s involved variable keys.
Definition: Factor.h:124
GTSAM_EXPORT bool isJacobian() const
const Symbol key2('v', 2)
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
3D Point
bool assert_inequal(const Matrix &A, const Matrix &B, double tol)
Definition: Matrix.cpp:62
double error(const VectorValues &c) const override
gtsam::Key x2
A Gaussian factor using the canonical parameters (information form)
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
Vector3 Point3
Definition: Point3.h:35
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
2D Pose
Point3 measured
Pose3 g2(g1.expmap(h *V1_g1))
GTSAM_EXPORT GaussianFactor::shared_ptr linearize(const Values &c) const override
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
GTSAM_EXPORT double error(const Values &c) const override
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
Definition: Vector.h:45
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
const double tol
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567
Vector vector() const


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