Go to the documentation of this file.
68 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43
69 [[deprecated(
"Use nRef() instead")]]
72 [[deprecated(
"Use bMeasured() instead")]]
73 const Unit3& bRef()
const {
return bMeasured_; }
76 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
78 friend class boost::serialization::access;
79 template <
class ARCHIVE>
80 void serialize(ARCHIVE& ar,
const unsigned int ) {
81 ar& boost::serialization::make_nvp(
"nRef_",
nRef_);
82 ar& boost::serialization::make_nvp(
"bMeasured_",
bMeasured_);
97 using Base::evaluateError;
123 return std::static_pointer_cast<gtsam::NonlinearFactor>(
133 double tol = 1
e-9)
const override;
137 return attitudeError(
nRb,
H);
141 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
143 friend class boost::serialization::access;
144 template <
class ARCHIVE>
145 void serialize(ARCHIVE& ar,
const unsigned int ) {
147 ar& boost::serialization::make_nvp(
148 "NoiseModelFactor1", boost::serialization::base_object<Base>(*
this));
149 ar& boost::serialization::make_nvp(
151 boost::serialization::base_object<AttitudeFactor>(*
this));
173 using Base::evaluateError;
199 return std::static_pointer_cast<gtsam::NonlinearFactor>(
209 double tol = 1
e-9)
const override;
216 *
H = Matrix::Zero(2, 6);
217 H->block<2, 3>(0, 0) = H23;
223 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
225 friend class boost::serialization::access;
226 template <
class ARCHIVE>
227 void serialize(ARCHIVE& ar,
const unsigned int ) {
229 ar& boost::serialization::make_nvp(
230 "NoiseModelFactor1", boost::serialization::base_object<Base>(*
this));
231 ar& boost::serialization::make_nvp(
233 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
Vector attitudeError(const Rot3 &p, OptionalJacobian< 2, 3 > H={}) const
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
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.
Base class for an attitude factor that constrains the rotation between body and navigation frames.
const Unit3 & nRef() const
const Unit3 & bMeasured() const
noiseModel::Base::shared_ptr SharedNoiseModel
noiseModel::Diagonal::shared_ptr model
const gtsam::Symbol key('X', 0)
Non-linear factor base classes.
Pose3AttitudeFactor(Key key, const Unit3 &nRef, const SharedNoiseModel &model, const Unit3 &bMeasured=Unit3(0, 0, 1))
Constructor.
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Vector evaluateError(const Pose3 &nTb, OptionalMatrixType H) const override
~Rot3AttitudeFactor() override
Rot3AttitudeFactor(Key key, const Unit3 &nRef, const SharedNoiseModel &model, const Unit3 &bMeasured=Unit3(0, 0, 1))
Constructor.
Rot3AttitudeFactor This
Typedef to this class.
Unit3 bMeasured_
Position measurement in.
Matrix * OptionalMatrixType
Represents a 3D point on a unit sphere.
AttitudeFactor(const Unit3 &nRef, const Unit3 &bMeasured=Unit3(0, 0, 1))
Constructor.
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
3D Pose manifold SO(3) x R^3 and group SE(3)
Vector evaluateError(const Rot3 &nRb, OptionalMatrixType H) const override
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:09