Go to the documentation of this file.
66 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
68 friend class boost::serialization::access;
69 template<
class ARCHIVE>
70 void serialize(ARCHIVE & ar,
const unsigned int ) {
71 ar & boost::serialization::make_nvp(
"nZ_",
nZ_);
72 ar & boost::serialization::make_nvp(
"bRef_",
bRef_);
88 using Base::evaluateError;
117 return std::static_pointer_cast<gtsam::NonlinearFactor>(
130 return attitudeError(
nRb,
H);
135 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
137 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::make_nvp(
"AttitudeFactor",
144 boost::serialization::base_object<AttitudeFactor>(*
this));
167 using Base::evaluateError;
196 return std::static_pointer_cast<gtsam::NonlinearFactor>(
212 *
H = Matrix::Zero(2,6);
213 H->block<2,3>(0,0) = H23;
220 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
222 friend class boost::serialization::access;
223 template<
class ARCHIVE>
224 void serialize(ARCHIVE & ar,
const unsigned int ) {
226 ar & boost::serialization::make_nvp(
"NoiseModelFactor1",
227 boost::serialization::base_object<Base>(*
this));
228 ar & boost::serialization::make_nvp(
"AttitudeFactor",
229 boost::serialization::base_object<AttitudeFactor>(*
this));
~Pose3AttitudeFactor() 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
gtsam::NonlinearFactor::shared_ptr clone() const override
NoiseModelFactorN< Pose3 > Base
Pose3AttitudeFactor This
Typedef to this class.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::shared_ptr< Rot3AttitudeFactor > shared_ptr
shorthand for a smart pointer to a factor
NoiseModelFactorN< Rot3 > Base
Unit3 bRef_
Position measurement in.
Vector attitudeError(const Rot3 &p, OptionalJacobian< 2, 3 > H={}) const
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Pose3AttitudeFactor(Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
void print(const Matrix &A, const string &s, ostream &stream)
gtsam::NonlinearFactor::shared_ptr clone() const override
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
const Unit3 & bRef() const
noiseModel::Base::shared_ptr SharedNoiseModel
noiseModel::Diagonal::shared_ptr model
AttitudeFactor(const Unit3 &nZ, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
const gtsam::Symbol key('X', 0)
Non-linear factor base classes.
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Vector evaluateError(const Pose3 &nTb, OptionalMatrixType H) const override
~Rot3AttitudeFactor() override
Rot3AttitudeFactor This
Typedef to this class.
Matrix * OptionalMatrixType
Represents a 3D point on a unit sphere.
std::uint64_t Key
Integer nonlinear key type.
std::shared_ptr< Pose3AttitudeFactor > shared_ptr
shorthand for a smart pointer to a factor
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Vector evaluateError(const Rot3 &nRb, OptionalMatrixType H) const override
Rot3AttitudeFactor(Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:00:29