testLinearEquality.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 
23 
24 #include <boost/assign/std/vector.hpp>
25 #include <boost/assign/list_of.hpp>
26 
27 using namespace std;
28 using namespace gtsam;
29 using namespace boost::assign;
30 
32 
33 namespace {
34 namespace simple {
35 // Terms we'll use
36 const vector<pair<Key, Matrix> > terms = list_of < pair<Key, Matrix>
37  > (make_pair(5, Matrix3::Identity()))(
38  make_pair(10, 2 * Matrix3::Identity()))(
39  make_pair(15, 3 * Matrix3::Identity()));
40 
41 // RHS and sigmas
42 const Vector b = (Vector(3) << 1., 2., 3.).finished();
43 const SharedDiagonal noise = noiseModel::Constrained::All(3);
44 }
45 }
46 
47 /* ************************************************************************* */
48 TEST(LinearEquality, constructors_and_accessors)
49 {
50  using namespace simple;
51 
52  // Test for using different numbers of terms
53  {
54  // One term constructor
56  boost::make_iterator_range(terms.begin(), terms.begin() + 1), b, 0);
57  LinearEquality actual(terms[0].first, terms[0].second, b, 0);
58  EXPECT(assert_equal(expected, actual));
59  LONGS_EQUAL((long)terms[0].first, (long)actual.keys().back());
60  EXPECT(assert_equal(terms[0].second, actual.getA(actual.end() - 1)));
61  EXPECT(assert_equal(b, expected.getb()));
62  EXPECT(assert_equal(b, actual.getb()));
63  EXPECT(assert_equal(*noise, *actual.get_model()));
64  }
65  {
66  // Two term constructor
68  boost::make_iterator_range(terms.begin(), terms.begin() + 2), b, 0);
69  LinearEquality actual(terms[0].first, terms[0].second,
70  terms[1].first, terms[1].second, b, 0);
71  EXPECT(assert_equal(expected, actual));
72  LONGS_EQUAL((long)terms[1].first, (long)actual.keys().back());
73  EXPECT(assert_equal(terms[1].second, actual.getA(actual.end() - 1)));
74  EXPECT(assert_equal(b, expected.getb()));
75  EXPECT(assert_equal(b, actual.getb()));
76  EXPECT(assert_equal(*noise, *actual.get_model()));
77  }
78  {
79  // Three term constructor
81  boost::make_iterator_range(terms.begin(), terms.begin() + 3), b, 0);
82  LinearEquality actual(terms[0].first, terms[0].second,
83  terms[1].first, terms[1].second, terms[2].first, terms[2].second, b, 0);
84  EXPECT(assert_equal(expected, actual));
85  LONGS_EQUAL((long)terms[2].first, (long)actual.keys().back());
86  EXPECT(assert_equal(terms[2].second, actual.getA(actual.end() - 1)));
87  EXPECT(assert_equal(b, expected.getb()));
88  EXPECT(assert_equal(b, actual.getb()));
89  EXPECT(assert_equal(*noise, *actual.get_model()));
90  }
91 }
92 
93 /* ************************************************************************* */
94 TEST(LinearEquality, Hessian_conversion) {
95  HessianFactor hessian(0, (Matrix(4,4) <<
96  1.57, 2.695, -1.1, -2.35,
97  2.695, 11.3125, -0.65, -10.225,
98  -1.1, -0.65, 1, 0.5,
99  -2.35, -10.225, 0.5, 9.25).finished(),
100  (Vector(4) << -7.885, -28.5175, 2.75, 25.675).finished(),
101  73.1725);
102 
103  try {
104  LinearEquality actual(hessian);
105  EXPECT(false);
106  }
107  catch (const std::runtime_error& exception) {
108  EXPECT(true);
109  }
110 }
111 
112 /* ************************************************************************* */
114 {
115  LinearEquality factor(simple::terms, simple::b, 0);
116 
118  values.insert(5, Vector::Constant(3, 1.0));
119  values.insert(10, Vector::Constant(3, 0.5));
120  values.insert(15, Vector::Constant(3, 1.0/3.0));
121 
122  Vector expected_unwhitened(3); expected_unwhitened << 2.0, 1.0, 0.0;
123  Vector actual_unwhitened = factor.unweighted_error(values);
124  EXPECT(assert_equal(expected_unwhitened, actual_unwhitened));
125 
126  // whitened is meaningless in constraints
127  Vector expected_whitened(3); expected_whitened = expected_unwhitened;
128  Vector actual_whitened = factor.error_vector(values);
129  EXPECT(assert_equal(expected_whitened, actual_whitened));
130 
131  double expected_error = 0.0;
132  double actual_error = factor.error(values);
133  DOUBLES_EQUAL(expected_error, actual_error, 1e-10);
134 }
135 
136 /* ************************************************************************* */
137 TEST(LinearEquality, matrices_NULL)
138 {
139  // Make sure everything works with nullptr noise model
140  LinearEquality factor(simple::terms, simple::b, 0);
141 
142  Matrix AExpected(3, 9);
143  AExpected << simple::terms[0].second, simple::terms[1].second, simple::terms[2].second;
144  Vector rhsExpected = simple::b;
145  Matrix augmentedJacobianExpected(3, 10);
146  augmentedJacobianExpected << AExpected, rhsExpected;
147 
148  // Whitened Jacobian
149  EXPECT(assert_equal(AExpected, factor.jacobian().first));
150  EXPECT(assert_equal(rhsExpected, factor.jacobian().second));
151  EXPECT(assert_equal(augmentedJacobianExpected, factor.augmentedJacobian()));
152 
153  // Unwhitened Jacobian
154  EXPECT(assert_equal(AExpected, factor.jacobianUnweighted().first));
155  EXPECT(assert_equal(rhsExpected, factor.jacobianUnweighted().second));
156  EXPECT(assert_equal(augmentedJacobianExpected, factor.augmentedJacobianUnweighted()));
157 }
158 
159 /* ************************************************************************* */
161 {
162  // And now witgh a non-unit noise model
163  LinearEquality factor(simple::terms, simple::b, 0);
164 
165  Matrix jacobianExpected(3, 9);
166  jacobianExpected << simple::terms[0].second, simple::terms[1].second, simple::terms[2].second;
167  Vector rhsExpected = simple::b;
168  Matrix augmentedJacobianExpected(3, 10);
169  augmentedJacobianExpected << jacobianExpected, rhsExpected;
170 
171  Matrix augmentedHessianExpected =
172  augmentedJacobianExpected.transpose() * simple::noise->R().transpose()
173  * simple::noise->R() * augmentedJacobianExpected;
174 
175  // Whitened Jacobian
176  EXPECT(assert_equal(jacobianExpected, factor.jacobian().first));
177  EXPECT(assert_equal(rhsExpected, factor.jacobian().second));
178  EXPECT(assert_equal(augmentedJacobianExpected, factor.augmentedJacobian()));
179 
180  // Unwhitened Jacobian
181  EXPECT(assert_equal(jacobianExpected, factor.jacobianUnweighted().first));
182  EXPECT(assert_equal(rhsExpected, factor.jacobianUnweighted().second));
183  EXPECT(assert_equal(augmentedJacobianExpected, factor.augmentedJacobianUnweighted()));
184 }
185 
186 /* ************************************************************************* */
187 TEST(LinearEquality, operators )
188 {
189  Matrix I = I_2x2;
190  Vector b = (Vector(2) << 0.2,-0.1).finished();
191  LinearEquality lf(1, -I, 2, I, b, 0);
192 
193  VectorValues c;
194  c.insert(1, (Vector(2) << 10.,20.).finished());
195  c.insert(2, (Vector(2) << 30.,60.).finished());
196 
197  // test A*x
198  Vector expectedE = (Vector(2) << 20.,40.).finished();
199  Vector actualE = lf * c;
200  EXPECT(assert_equal(expectedE, actualE));
201 
202  // test A^e
203  VectorValues expectedX;
204  expectedX.insert(1, (Vector(2) << -20.,-40.).finished());
205  expectedX.insert(2, (Vector(2) << 20., 40.).finished());
206  VectorValues actualX = VectorValues::Zero(expectedX);
207  lf.transposeMultiplyAdd(1.0, actualE, actualX);
208  EXPECT(assert_equal(expectedX, actualX));
209 
210  // test gradient at zero
211  Matrix A; Vector b2; boost::tie(A,b2) = lf.jacobian();
212  VectorValues expectedG;
213  expectedG.insert(1, (Vector(2) << 0.2, -0.1).finished());
214  expectedG.insert(2, (Vector(2) << -0.2, 0.1).finished());
215  VectorValues actualG = lf.gradientAtZero();
216  EXPECT(assert_equal(expectedG, actualG));
217 }
218 
219 /* ************************************************************************* */
220 TEST(LinearEquality, default_error )
221 {
223  double actual = f.error(VectorValues());
224  DOUBLES_EQUAL(0.0, actual, 1e-15);
225 }
226 
227 //* ************************************************************************* */
229 {
230  // create an empty factor
232  EXPECT(f.empty());
233 }
234 
235 /* ************************************************************************* */
236 int main() {
237  TestResult tr;
238  return TestRegistry::runAllTests(tr);
239 }
240 /* ************************************************************************* */
Provides additional testing facilities for common data structures.
Scalar * b
Definition: benchVecAdd.cpp:17
Vector unweighted_error(const VectorValues &c) const
std::pair< Matrix, Vector > jacobianUnweighted() const
Returns (dense) A,b pair associated with factor, does not bake in weights.
static int runAllTests(TestResult &result)
Matrix expected
Definition: testMatrix.cpp:974
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:142
double error(const VectorValues &c) const override
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
const_iterator end() const
Definition: Factor.h:130
leaf::MyValues values
std::pair< Matrix, Vector > jacobian() const override
Returns (dense) A,b pair associated with factor, bakes in the weights.
Definition: Half.h:150
LinearEquality derived from Base with constrained noise model.
Factor Graph Values.
constexpr int first(int i)
Implementation details for constexpr functions.
Eigen::VectorXd Vector
Definition: Vector.h:38
const constBVector getb() const
#define EXPECT(condition)
Definition: Test.h:151
Vector2 b2(4,-5)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Contains the HessianFactor class, a general quadratic factor.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Matrix augmentedJacobian() const override
bool empty() const override
int main()
static const Matrix I
Definition: lago.cpp:35
constABlock getA(const_iterator variable) const
Vector error_vector(const VectorValues &c) const
const SharedDiagonal & get_model() const
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:135
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
TEST(LinearEquality, constructors_and_accessors)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Matrix augmentedJacobianUnweighted() const
const KeyVector & keys() const
Access the factor&#39;s involved variable keys.
Definition: Factor.h:124
A Gaussian factor using the canonical parameters (information form)
static double error
Definition: testRot3.cpp:39
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
void transposeMultiplyAdd(double alpha, const Vector &e, VectorValues &x) const
VectorValues gradientAtZero() const override
A&#39;*b for Jacobian.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
iterator insert(const std::pair< Key, Vector > &key_value)
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:174


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