35 using Point =
typename POSE::Translation;
36 using Rot =
typename POSE::Rotation;
43 static const int MeasDim = Point::RowsAtCompileTime;
77 const Point& direction,
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) {}
121 Matrix H_rot = Matrix::Zero(MeasDim, RotDim);
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;
131 return (hx - measured_);
135 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 136 friend class boost::serialization::access; 138 template<
class ARCHIVE>
139 void serialize(ARCHIVE & ar,
const unsigned int ) {
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_);
void print(const Matrix &A, const string &s, ostream &stream)
Rot3_ rotation(const Pose3_ &pose)
MagPoseFactor< POSE > This
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
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.
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.
std::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
typename POSE::Rotation Rot
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)
static const KeyFormatter DefaultKeyFormatter
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
#define GTSAM_CONCEPT_POSE_TYPE(T)
Matrix * OptionalMatrixType
typename POSE::Translation Point
Could be a Vector2 or Vector3 depending on POSE.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const Point measured_
The measured magnetometer data in the body frame.
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)
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
NonlinearFactor::shared_ptr clone() const override
Non-linear factor base classes.
MagPoseFactor()
Default constructor - only use for serialization.
static double scale(double x, double a, double b, double t1, double t2)
Scale x from [a, b] to [t1, t2].
std::shared_ptr< This > shared_ptr
const Point bias_
The bias vector (mag output units) in the body frame.
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Equals function.
~MagPoseFactor() override
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel