MagPoseFactor.h
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 
12 #pragma once
13 
17 
18 #include <optional>
19 
20 namespace gtsam {
21 
30 template <class POSE>
31 class MagPoseFactor: public NoiseModelFactorN<POSE> {
32  private:
35  using Point = typename POSE::Translation;
36  using Rot = typename POSE::Rotation;
37 
38  const Point measured_;
39  const Point nM_;
40  const Point bias_;
41  std::optional<POSE> body_P_sensor_;
42 
43  static const int MeasDim = Point::RowsAtCompileTime;
44  static const int PoseDim = traits<POSE>::dimension;
45  static const int RotDim = traits<Rot>::dimension;
46 
48  using shared_ptr = std::shared_ptr<MagPoseFactor<POSE>>;
49 
53 
54  public:
55 
56  // Provide access to the Matrix& version of evaluateError:
57  using Base::evaluateError;
58 
59  ~MagPoseFactor() override {}
60 
63 
74  MagPoseFactor(Key pose_key,
75  const Point& measured,
76  double scale,
77  const Point& direction,
78  const Point& bias,
79  const SharedNoiseModel& model,
80  const std::optional<POSE>& body_P_sensor)
81  : Base(model, pose_key),
82  measured_(body_P_sensor ? body_P_sensor->rotation() * measured : measured),
83  nM_(scale * direction.normalized()),
84  bias_(body_P_sensor ? body_P_sensor->rotation() * bias : bias),
85  body_P_sensor_(body_P_sensor) {}
86 
89  return std::static_pointer_cast<NonlinearFactor>(
90  NonlinearFactor::shared_ptr(new This(*this)));
91  }
92 
94 
95  // Print out the factor.
96  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
97  Base::print(s, keyFormatter);
98  gtsam::print(Vector(nM_), "local field (nM): ");
99  gtsam::print(Vector(measured_), "measured field (bM): ");
100  gtsam::print(Vector(bias_), "magnetometer bias: ");
101  }
102 
104  bool equals(const NonlinearFactor& expected, double tol=1e-9) const override {
105  const This *e = dynamic_cast<const This*> (&expected);
106  return e != nullptr && Base::equals(*e, tol) &&
107  gtsam::equal_with_abs_tol(this->measured_, e->measured_, tol) &&
108  gtsam::equal_with_abs_tol(this->nM_, e->nM_, tol) &&
109  gtsam::equal_with_abs_tol(this->bias_, e->bias_, tol);
110  }
111 
113 
118  Vector evaluateError(const POSE& nPb, OptionalMatrixType H) const override {
119  // Predict the measured magnetic field h(x) in the *body* frame.
120  // If body_P_sensor was given, bias_ will have been rotated into the body frame.
121  Matrix H_rot = Matrix::Zero(MeasDim, RotDim);
122  const Point hx = nPb.rotation().unrotate(nM_, H_rot, OptionalNone) + bias_;
123 
124  if (H) {
125  // Fill in the relevant part of the Jacobian (just rotation columns).
126  *H = Matrix::Zero(MeasDim, PoseDim);
127  const size_t rot_col0 = nPb.rotationInterval().first;
128  (*H).block(0, rot_col0, MeasDim, RotDim) = H_rot;
129  }
130 
131  return (hx - measured_);
132  }
133 
134  private:
135 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
136  friend class boost::serialization::access;
138  template<class ARCHIVE>
139  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
140  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
141  ar & boost::serialization::make_nvp("NoiseModelFactor1",
142  boost::serialization::base_object<Base>(*this));
143  ar & BOOST_SERIALIZATION_NVP(measured_);
144  ar & BOOST_SERIALIZATION_NVP(nM_);
145  ar & BOOST_SERIALIZATION_NVP(bias_);
146  ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
147  }
148 #endif
149 }; // \class MagPoseFactor
150 
151 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Point2 measured(-17, 30)
Rot3_ rotation(const Pose3_ &pose)
MagPoseFactor< POSE > This
Definition: MagPoseFactor.h:33
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:971
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Implement functions needed for Testable.
Definition: MagPoseFactor.h:96
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
const Point nM_
Local magnetic field (mag output units) in the nav frame.
Definition: MagPoseFactor.h:39
static const int RotDim
Definition: MagPoseFactor.h:45
std::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
Definition: MagPoseFactor.h:41
typename POSE::Rotation Rot
Definition: MagPoseFactor.h:36
Vector evaluateError(const POSE &nPb, OptionalMatrixType H) const override
Implement functions needed to derive from Factor.
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 set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange [*:*] noreverse nowriteback set trange [*:*] noreverse nowriteback set urange [*:*] noreverse nowriteback set vrange [*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
#define GTSAM_CONCEPT_TESTABLE_TYPE(T)
Definition: Testable.h:177
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
static const int PoseDim
Definition: MagPoseFactor.h:44
#define OptionalNone
#define GTSAM_CONCEPT_POSE_TYPE(T)
Matrix * OptionalMatrixType
Eigen::VectorXd Vector
Definition: Vector.h:38
typename POSE::Translation Point
Could be a Vector2 or Vector3 depending on POSE.
Definition: MagPoseFactor.h:35
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const Point measured_
The measured magnetometer data in the body frame.
Definition: MagPoseFactor.h:38
RealScalar s
MagPoseFactor(Key pose_key, const Point &measured, double scale, const Point &direction, const Point &bias, const SharedNoiseModel &model, const std::optional< POSE > &body_P_sensor)
Definition: MagPoseFactor.h:74
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:75
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
traits
Definition: chartTesting.h:28
NonlinearFactor::shared_ptr clone() const override
Definition: MagPoseFactor.h:88
Non-linear factor base classes.
MagPoseFactor()
Default constructor - only use for serialization.
Definition: MagPoseFactor.h:62
static double scale(double x, double a, double b, double t1, double t2)
Scale x from [a, b] to [t1, t2].
Definition: Chebyshev.cpp:35
std::shared_ptr< This > shared_ptr
const Point bias_
The bias vector (mag output units) in the body frame.
Definition: MagPoseFactor.h:40
const G double tol
Definition: Group.h:86
static const int MeasDim
Definition: MagPoseFactor.h:43
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Equals function.
~MagPoseFactor() override
Definition: MagPoseFactor.h:59
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:35