Go to the documentation of this file.
48 using Base::evaluateError;
74 return std::static_pointer_cast<gtsam::NonlinearFactor>(
98 static std::pair<Pose3, Vector3> EstimateState(
double t1,
const Point3& NED1,
99 double t2,
const Point3& NED2,
double timestamp);
103 #if GTSAM_ENABLE_BOOST_SERIALIZATION
104 friend class boost::serialization::access;
106 template<
class ARCHIVE>
107 void serialize(ARCHIVE & ar,
const unsigned int ) {
110 & boost::serialization::make_nvp(
"NoiseModelFactor1",
111 boost::serialization::base_object<Base>(*
this));
112 ar & BOOST_SERIALIZATION_NVP(nT_);
137 using Base::evaluateError;
162 return std::static_pointer_cast<gtsam::NonlinearFactor>(
207 using Base::evaluateError;
233 return std::static_pointer_cast<gtsam::NonlinearFactor>(
271 using Base::evaluateError;
295 return std::static_pointer_cast<gtsam::NonlinearFactor>(
316 #if GTSAM_ENABLE_BOOST_SERIALIZATION
317 friend class boost::serialization::access;
319 template<
class ARCHIVE>
320 void serialize(ARCHIVE & ar,
const unsigned int ) {
323 & boost::serialization::make_nvp(
"NoiseModelFactor1",
324 boost::serialization::base_object<Base>(*
this));
325 ar & BOOST_SERIALIZATION_NVP(nT_);
350 using Base::evaluateError;
375 return std::static_pointer_cast<gtsam::NonlinearFactor>(
419 using Base::evaluateError;
444 return std::static_pointer_cast<gtsam::NonlinearFactor>(
const Symbol key1('v', 1)
GPSFactorArm(Key key, const Point3 &gpsIn, const Point3 &leverArm, const SharedNoiseModel &model)
gtsam::NonlinearFactor::shared_ptr clone() const override
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
~GPSFactor2Arm() override
NoiseModelFactorN< Pose3 > Base
const Point3 & measurementIn() const
return the measurement, in the navigation frame
GPSFactor2Arm()
default constructor - only use for serialization
GPSFactor This
Typedef to this class.
GPSFactor2Arm(Key key, const Point3 &gpsIn, const Point3 &leverArm, const SharedNoiseModel &model)
NoiseModelFactorN< NavState > Base
std::shared_ptr< GPSFactor2ArmCalib > shared_ptr
shorthand for a smart pointer to a factor
const Point3 & measurementIn() const
return the measurement, in the navigation frame
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::shared_ptr< GPSFactor > shared_ptr
shorthand for a smart pointer to a factor
const Point3 & measurementIn() const
return the measurement, in the navigation frame
const Point3 & measurementIn() const
return the measurement, in the navigation frame
GPSFactor2ArmCalib(Key key1, Key key2, const Point3 &gpsIn, const SharedNoiseModel &model)
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
NoiseModelFactorN< Pose3, Point3 > Base
std::shared_ptr< GPSFactorArm > shared_ptr
shorthand for a smart pointer to a factor
GPSFactor(Key key, const Point3 &gpsIn, const SharedNoiseModel &model)
Constructor from a measurement in a Cartesian frame. Use GeographicLib to convert from geographic (la...
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
~GPSFactor2ArmCalib() override
GPSFactor2()
default constructor - only use for serialization
gtsam::NonlinearFactor::shared_ptr clone() const override
std::shared_ptr< GPSFactor2 > shared_ptr
shorthand for a smart pointer to a factor
void print(const Matrix &A, const string &s, ostream &stream)
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
const Symbol key2('v', 2)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
GPSFactorArmCalib()
default constructor - only use for serialization
Navigation state composing of attitude, position, and velocity.
const Point3 & leverArm() const
return the lever arm, a position in the body frame
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
gtsam::NonlinearFactor::shared_ptr clone() const override
NoiseModelFactorN< NavState, Point3 > Base
noiseModel::Base::shared_ptr SharedNoiseModel
NoiseModelFactorN< Pose3 > Base
std::shared_ptr< GPSFactorArmCalib > shared_ptr
shorthand for a smart pointer to a factor
GPSFactor2ArmCalib()
default constructor - only use for serialization
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
noiseModel::Diagonal::shared_ptr model
const gtsam::Symbol key('X', 0)
Non-linear factor base classes.
GPSFactor2ArmCalib This
Typedef to this class.
~GPSFactorArmCalib() override
GPSFactor2Arm This
Typedef to this class.
gtsam::NonlinearFactor::shared_ptr clone() const override
const Point3 & leverArm() const
return the lever arm, a position in the body frame
GPSFactorArmCalib(Key key1, Key key2, const Point3 &gpsIn, const SharedNoiseModel &model)
gtsam::NonlinearFactor::shared_ptr clone() const override
GPSFactor2(Key key, const Point3 &gpsIn, const SharedNoiseModel &model)
const Point3 & measurementIn() const
return the measurement, in the navigation frame
Matrix * OptionalMatrixType
NoiseModelFactorN< NavState > Base
static const Point3 leverArm(0.1, 0.2, 0.3)
std::shared_ptr< GPSFactor2Arm > shared_ptr
shorthand for a smart pointer to a factor
GPSFactorArm This
Typedef to this class.
std::uint64_t Key
Integer nonlinear key type.
const Point3 & measurementIn() const
return the measurement, in the navigation frame
gtsam::NonlinearFactor::shared_ptr clone() const override
GPSFactorArm()
default constructor - only use for serialization
GPSFactorArmCalib This
Typedef to this class.
3D Pose manifold SO(3) x R^3 and group SE(3)
GPSFactor2 This
Typedef to this class.
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:01:45