Go to the documentation of this file.
35 using Point =
typename POSE::Translation;
36 using Rot =
typename POSE::Rotation;
43 static const int MeasDim = Point::RowsAtCompileTime;
77 const Point& direction,
89 return std::static_pointer_cast<NonlinearFactor>(
127 const size_t rot_col0 = nPb.rotationInterval().first;
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));
144 ar & BOOST_SERIALIZATION_NVP(
nM_);
145 ar & BOOST_SERIALIZATION_NVP(
bias_);
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
std::shared_ptr< This > shared_ptr
#define GTSAM_CONCEPT_POSE_TYPE(T)
Concept-checking macros for geometric objects Each macro instantiates a concept check structure,...
Array< double, 1, 3 > e(1./3., 0.5, 2.)
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
const Vector3 bias(1, 2, 3)
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Implement functions needed for Testable.
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
std::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
void print(const Matrix &A, const string &s, ostream &stream)
const Point nM_
Local magnetic field (mag output units) in the nav frame.
typename POSE::Rotation Rot
Vector evaluateError(const POSE &nPb, OptionalMatrixType H) const override
Implement functions needed to derive from Factor.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
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)
NonlinearFactor::shared_ptr clone() const override
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
noiseModel::Base::shared_ptr SharedNoiseModel
typename POSE::Translation Point
Could be a Vector2 or Vector3 depending on POSE.
noiseModel::Diagonal::shared_ptr model
const Point measured_
The measured magnetometer data in the body frame.
Non-linear factor base classes.
Rot3_ rotation(const Pose3_ &pose)
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Equals function.
#define GTSAM_CONCEPT_TESTABLE_TYPE(T)
static double scale(double x, double a, double b, double t1, double t2)
Scale x from [a, b] to [t1, t2].
MagPoseFactor()
Default constructor - only use for serialization.
Matrix * OptionalMatrixType
~MagPoseFactor() override
const Point bias_
The bias vector (mag output units) in the body frame.
std::uint64_t Key
Integer nonlinear key type.
MagPoseFactor< POSE > This
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:44