testMagPoseFactor.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 
15 #include <gtsam/geometry/Pose2.h>
16 #include <gtsam/geometry/Pose3.h>
17 #include <gtsam/inference/Symbol.h>
19 
20 using namespace std::placeholders;
21 using namespace gtsam;
22 
23 namespace {
24 // Magnetic field in the nav frame (NED), with units of nT.
25 Point3 nM(22653.29982, -1956.83010, 44202.47862);
26 
27 // Assumed scale factor (scales a unit vector to magnetometer units of nT).
28 double scale = 255.0 / 50000.0;
29 
30 // Ground truth Pose2/Pose3 in the nav frame.
31 Pose3 n_P3_b = Pose3(Rot3::Yaw(-0.1), Point3(-3, 12, 5));
32 Pose2 n_P2_b = Pose2(Rot2(-0.1), Point2(-3, 12));
33 Rot3 n_R3_b = n_P3_b.rotation();
34 Rot2 n_R2_b = n_P2_b.rotation();
35 
36 // Sensor bias (nT).
37 Point3 bias3(10, -10, 50);
38 Point2 bias2 = bias3.head(2);
39 
40 Point3 dir3(nM.normalized());
41 Point2 dir2(nM.head(2).normalized());
42 
43 // Compute the measured field in the sensor frame.
44 Point3 measured3 = n_R3_b.inverse() * (scale * dir3) + bias3;
45 
46 // The 2D magnetometer will measure the "NE" field components.
47 Point2 measured2 = n_R2_b.inverse() * (scale * dir2) + bias2;
48 
49 SharedNoiseModel model2 = noiseModel::Isotropic::Sigma(2, 0.25);
50 SharedNoiseModel model3 = noiseModel::Isotropic::Sigma(3, 0.25);
51 
52 // Make up a rotation and offset of the sensor in the body frame.
53 Pose2 body_P2_sensor(Rot2(-0.30), Point2(1.0, -2.0));
54 Pose3 body_P3_sensor(Rot3::RzRyRx(Vector3(1.5, 0.9, -1.15)),
55  Point3(-0.1, 0.2, 0.3));
56 } // namespace
57 
58 // *****************************************************************************
59 TEST(MagPoseFactor, Constructors) {
60  MagPoseFactor<Pose2> f2a(Symbol('X', 0), measured2, scale, dir2, bias2, model2, {});
61  MagPoseFactor<Pose3> f3a(Symbol('X', 0), measured3, scale, dir3, bias3, model3, {});
62 
63  // Try constructing with a body_P_sensor set.
65  Symbol('X', 0), measured2, scale, dir2, bias2, model2, body_P2_sensor);
67  Symbol('X', 0), measured3, scale, dir3, bias3, model3, body_P3_sensor);
68 
69  f2b.print();
70  f3b.print();
71 }
72 
73 // *****************************************************************************
74 TEST(MagPoseFactor, JacobianPose2) {
75  Matrix H2;
76 
77  // Error should be zero at the groundtruth pose.
78  MagPoseFactor<Pose2> f(Symbol('X', 0), measured2, scale, dir2, bias2, model2, {});
79  CHECK(gtsam::assert_equal(Z_2x1, f.evaluateError(n_P2_b, H2), 1e-5));
80  CHECK(gtsam::assert_equal(gtsam::numericalDerivative11<Vector, Pose2> //
81  ([&f] (const Pose2& p) {return f.evaluateError(p);},
82  n_P2_b),
83  H2, 1e-7));
84 }
85 
86 // *****************************************************************************
87 TEST(MagPoseFactor, JacobianPose3) {
88  Matrix H3;
89 
90  // Error should be zero at the groundtruth pose.
91  MagPoseFactor<Pose3> f(Symbol('X', 0), measured3, scale, dir3, bias3, model3, {});
92  CHECK(gtsam::assert_equal(Z_3x1, f.evaluateError(n_P3_b, H3), 1e-5));
93  CHECK(gtsam::assert_equal(gtsam::numericalDerivative11<Vector, Pose3> //
94  ([&f] (const Pose3& p) {return f.evaluateError(p);},
95  n_P3_b),
96  H3, 1e-7));
97 }
98 
99 // *****************************************************************************
100 TEST(MagPoseFactor, body_P_sensor2) {
101  Matrix H2;
102 
103  // Because body_P_sensor is specified, we need to rotate the raw measurement
104  // from the body frame into the sensor frame "s".
105  const Rot2 nRs = n_R2_b * body_P2_sensor.rotation();
106  const Point2 sM = nRs.inverse() * (scale * dir2) + bias2;
107  MagPoseFactor<Pose2> f = MagPoseFactor<Pose2>(Symbol('X', 0), sM, scale, dir2, bias2, model2, body_P2_sensor);
108  CHECK(gtsam::assert_equal(Z_2x1, f.evaluateError(n_P2_b, H2), 1e-5));
109  CHECK(gtsam::assert_equal(gtsam::numericalDerivative11<Vector, Pose2> //
110  ([&f] (const Pose2& p) {return f.evaluateError(p);},n_P2_b), H2, 1e-7));
111 }
112 
113 // *****************************************************************************
114 TEST(MagPoseFactor, body_P_sensor3) {
115  Matrix H3;
116 
117  // Because body_P_sensor is specified, we need to rotate the raw measurement
118  // from the body frame into the sensor frame "s".
119  const Rot3 nRs = n_R3_b * body_P3_sensor.rotation();
120  const Point3 sM = nRs.inverse() * (scale * dir3) + bias3;
121  MagPoseFactor<Pose3> f = MagPoseFactor<Pose3>(Symbol('X', 0), sM, scale, dir3, bias3, model3, body_P3_sensor);
122  CHECK(gtsam::assert_equal(Z_3x1, f.evaluateError(n_P3_b, H3), 1e-5));
123  CHECK(gtsam::assert_equal(gtsam::numericalDerivative11<Vector, Pose3> //
124  ([&f] (const Pose3& p) {return f.evaluateError(p);}, n_P3_b), H3, 1e-7));
125 }
126 
127 // *****************************************************************************
128 int main() {
129  TestResult tr;
130  return TestRegistry::runAllTests(tr);
131 }
132 // *****************************************************************************
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
Pose2.h
2D Pose
model2
auto model2
Definition: testFunctorizedFactor.cpp:40
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::Z_3x1
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
TestHarness.h
gtsam::Pose2::rotation
const Rot2 & rotation(OptionalJacobian< 1, 3 > Hself={}) const
rotation
Definition: Pose2.h:270
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::MagPoseFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Implement functions needed for Testable.
Definition: MagPoseFactor.h:96
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
bias2
Bias bias2(biasAcc2, biasGyro2)
TestableAssertions.h
Provides additional testing facilities for common data structures.
numericalDerivative.h
Some functions to compute numerical derivatives.
scale
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics scale
Definition: gnuplot_common_settings.hh:54
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
TEST
TEST(MagPoseFactor, Constructors)
Definition: testMagPoseFactor.cpp:59
Symbol.h
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
gtsam::Rot3::inverse
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:308
TestResult
Definition: TestResult.h:26
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::Rot2
Definition: Rot2.h:35
gtsam::Pose3::rotation
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:315
main
int main()
Definition: testMagPoseFactor.cpp:128
gtsam
traits
Definition: chartTesting.h:28
CHECK
#define CHECK(condition)
Definition: Test.h:108
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Z_2x1
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
Definition: Vector.h:45
gtsam::MagPoseFactor
Definition: MagPoseFactor.h:31
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
MagPoseFactor.h
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
model3
const SharedNoiseModel model3
Definition: testPoseRotationPrior.cpp:22
gtsam::Rot2::inverse
Rot2 inverse() const
Definition: Rot2.h:113
Pose3.h
3D Pose
gtsam::Pose2
Definition: Pose2.h:39
gtsam::Symbol
Definition: inference/Symbol.h:37


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:06:15