testGaussMarkov1stOrderFactor.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 
20 #include <gtsam/nonlinear/Values.h>
21 #include <gtsam/inference/Key.h>
25 
26 using namespace std;
27 using namespace gtsam;
28 
31 
32 /* ************************************************************************* */
34  return factor.evaluateError(v1, v2);
35 }
36 
37 /* ************************************************************************* */
39 {
40  // Create two identical factors and make sure they're equal
41  Key x1(1);
42  Key x2(2);
43  double delta_t = 0.10;
44  Vector tau = Vector3(100.0, 150.0, 10.0);
45  SharedGaussian model = noiseModel::Isotropic::Sigma(3, 1.0);
46 
47  GaussMarkovFactor factor1(x1, x2, delta_t, tau, model);
48  GaussMarkovFactor factor2(x1, x2, delta_t, tau, model);
49 
50  CHECK(assert_equal(factor1, factor2));
51 }
52 
53 /* ************************************************************************* */
55 {
56  Values linPoint;
57  Key x1(1);
58  Key x2(2);
59  double delta_t = 0.10;
60  Vector tau = Vector3(100.0, 150.0, 10.0);
61  SharedGaussian model = noiseModel::Isotropic::Sigma(3, 1.0);
62 
63  LieVector v1 = LieVector(Vector3(10.0, 12.0, 13.0));
64  LieVector v2 = LieVector(Vector3(10.0, 15.0, 14.0));
65 
66  // Create two nodes
67  linPoint.insert(x1, v1);
68  linPoint.insert(x2, v2);
69 
70  GaussMarkovFactor factor(x1, x2, delta_t, tau, model);
71  Vector Err1( factor.evaluateError(v1, v2) );
72 
73  // Manually calculate the error
74  Vector alpha(tau.size());
75  Vector alpha_v1(tau.size());
76  for(int i=0; i<tau.size(); i++){
77  alpha(i) = exp(- 1/tau(i)*delta_t );
78  alpha_v1(i) = alpha(i) * v1(i);
79  }
80  Vector Err2( v2 - alpha_v1 );
81 
82  CHECK(assert_equal(Err1, Err2, 1e-9));
83 }
84 
85 /* ************************************************************************* */
86 TEST (GaussMarkovFactor, jacobian ) {
87 
88  Values linPoint;
89  Key x1(1);
90  Key x2(2);
91  double delta_t = 0.10;
92  Vector tau = Vector3(100.0, 150.0, 10.0);
93  SharedGaussian model = noiseModel::Isotropic::Sigma(3, 1.0);
94 
95  GaussMarkovFactor factor(x1, x2, delta_t, tau, model);
96 
97  // Update the linearization point
98  LieVector v1_upd = LieVector(Vector3(0.5, -0.7, 0.3));
99  LieVector v2_upd = LieVector(Vector3(-0.7, 0.4, 0.9));
100 
101  // Calculate the Jacobian matrix using the factor
102  Matrix computed_H1, computed_H2;
103  factor.evaluateError(v1_upd, v2_upd, computed_H1, computed_H2);
104 
105  // Calculate the Jacobian matrices H1 and H2 using the numerical derivative function
106  Matrix numerical_H1, numerical_H2;
107  numerical_H1 = numericalDerivative21<Vector3, Vector3, Vector3>(
108  boost::bind(&predictionError, _1, _2, factor), v1_upd, v2_upd);
109  numerical_H2 = numericalDerivative22<Vector3, Vector3, Vector3>(
110  boost::bind(&predictionError, _1, _2, factor), v1_upd, v2_upd);
111 
112  // Verify they are equal for this choice of state
113  CHECK( assert_equal(numerical_H1, computed_H1, 1e-9));
114  CHECK( assert_equal(numerical_H2, computed_H2, 1e-9));
115 }
116 
117 /* ************************************************************************* */
118 int main()
119 {
120  TestResult tr; return TestRegistry::runAllTests(tr);
121 }
122 /* ************************************************************************* */
123 
#define CHECK(condition)
Definition: Test.h:109
Vector v2
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector v1
A non-templated config holding any types of Manifold-group elements.
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Definition: Half.h:150
Some functions to compute numerical derivatives.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Vector evaluateError(const VALUE &p1, const VALUE &p2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Eigen::VectorXd Vector
Definition: Vector.h:38
RealScalar alpha
GaussMarkov1stOrderFactor< LieVector > GaussMarkovFactor
Factors.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
LieVector predictionError(const LieVector &v1, const LieVector &v2, const GaussMarkovFactor factor)
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Pose3 x1
Definition: testPose3.cpp:588
TEST(GaussMarkovFactor, equals)
JacobianFactor factor2(keyX, A21, keyY, A22, b2, noiseModel::Isotropic::Sigma(2, sigma2))
static double error
Definition: testRot3.cpp:39
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Gaussian::shared_ptr SharedGaussian
Definition: NoiseModel.h:735
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:52