testBiasedGPSFactor.cpp
Go to the documentation of this file.
1 
9 #include <gtsam/geometry/Pose3.h>
10 #include <gtsam/inference/Symbol.h>
13 
14 using namespace gtsam;
15 using namespace gtsam::symbol_shorthand;
16 using namespace gtsam::noiseModel;
17 // Convenience for named keys
18 
21 
22 TEST(BiasedGPSFactor, errorNoiseless) {
23 
24  Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3);
25  Point3 t(1.0, 0.5, 0.2);
26  Pose3 pose(R,t);
27  Point3 bias(0.0,0.0,0.0);
28  Point3 noise(0.0,0.0,0.0);
29  Point3 measured = t + noise;
30 
31  BiasedGPSFactor factor(X(1), B(1), measured, Isotropic::Sigma(3, 0.05));
32  Vector expectedError = Vector3(0.0, 0.0, 0.0 );
33  Vector actualError = factor.evaluateError(pose,bias);
34  EXPECT(assert_equal(expectedError,actualError, 1E-5));
35 }
36 
37 TEST(BiasedGPSFactor, errorNoisy) {
38 
39  Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3);
40  Point3 t(1.0, 0.5, 0.2);
41  Pose3 pose(R,t);
42  Point3 bias(0.0,0.0,0.0);
43  Point3 noise(1.0,2.0,3.0);
44  Point3 measured = t - noise;
45 
46  BiasedGPSFactor factor(X(1), B(1), measured, Isotropic::Sigma(3, 0.05));
47  Vector expectedError = Vector3(1.0, 2.0, 3.0 );
48  Vector actualError = factor.evaluateError(pose,bias);
49  EXPECT(assert_equal(expectedError,actualError, 1E-5));
50 }
51 
52 TEST(BiasedGPSFactor, jacobian) {
53 
54  Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3);
55  Point3 t(1.0, 0.5, 0.2);
56  Pose3 pose(R,t);
57  Point3 bias(0.0,0.0,0.0);
58 
59  Point3 noise(0.0,0.0,0.0);
60  Point3 measured = t + noise;
61 
62  BiasedGPSFactor factor(X(1), B(1), measured, Isotropic::Sigma(3, 0.05));
63 
64  Matrix actualH1, actualH2;
65  factor.evaluateError(pose,bias, actualH1, actualH2);
66 
67  Matrix numericalH1 = numericalDerivative21(
68  boost::function<Vector(const Pose3&, const Point3&)>(boost::bind(
69  &BiasedGPSFactor::evaluateError, factor, _1, _2, boost::none,
70  boost::none)), pose, bias, 1e-5);
71  EXPECT(assert_equal(numericalH1,actualH1, 1E-5));
72 
73  Matrix numericalH2 = numericalDerivative22(
74  boost::function<Vector(const Pose3&, const Point3&)>(boost::bind(
75  &BiasedGPSFactor::evaluateError, factor, _1, _2, boost::none,
76  boost::none)), pose, bias, 1e-5);
77  EXPECT(assert_equal(numericalH2,actualH2, 1E-5));
78 }
79 
80 /* ************************************************************************* */
81 int main() {
82  TestResult tr;
83  return TestRegistry::runAllTests(tr);
84 }
85 /* ************************************************************************* */
Key E(std::uint64_t j)
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Some functions to compute numerical derivatives.
Key X(std::uint64_t j)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
static Rot3 Rodrigues(const Vector3 &w)
Definition: Rot3.h:243
Eigen::VectorXd Vector
Definition: Vector.h:38
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Point3 bias(10,-10, 50)
traits
Definition: chartTesting.h:28
Key B(std::uint64_t j)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Vector evaluateError(const Pose3 &pose, const Point3 &bias, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Key R(std::uint64_t j)
TEST(LPInitSolver, InfiniteLoopSingleVar)
int main()
Vector3 Point3
Definition: Point3.h:35
Point3 measured
3D Pose
Point2 t(10, 10)
All noise models live in the noiseModel namespace.


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