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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:37:57