gtsam 4.1.1
gtsam
gtsam::Pose3AttitudeFactor Class Reference
+ Inheritance diagram for gtsam::Pose3AttitudeFactor:

Public Member Functions

 Pose3AttitudeFactor ()
 default constructor - only use for serialization
 
 Pose3AttitudeFactor (Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
 Constructor. More...
 
gtsam::NonlinearFactor::shared_ptr clone () const override
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 print More...
 
bool equals (const NonlinearFactor &expected, double tol=1e-9) const override
 equals More...
 
Vector evaluateError (const Pose3 &nTb, boost::optional< Matrix & > H=boost::none) const override
 vector of errors More...
 
- Public Member Functions inherited from gtsam::NoiseModelFactor1< Pose3 >
 NoiseModelFactor1 ()
 Default constructor for I/O only.
 
 NoiseModelFactor1 (const SharedNoiseModel &noiseModel, Key key1)
 Constructor. More...
 
 ~NoiseModelFactor1 () override
 
Key key () const
 
Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
 Calls the 1-key specific version of evaluateError below, which is pure virtual so must be implemented in the derived class. More...
 
- Public Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor ()
 Default constructor for I/O only.
 
 ~NoiseModelFactor () override
 Destructor.
 
template<typename CONTAINER >
 NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys)
 Constructor.
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 Print. More...
 
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 Check if two factors are equal. More...
 
size_t dim () const override
 get the dimension of the factor (number of rows on linearization) More...
 
const SharedNoiseModelnoiseModel () const
 access to the noise model
 
virtual Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const =0
 Error function without the NoiseModel, \( z-h(x) \). More...
 
Vector whitenedError (const Values &c) const
 Vector of errors, whitened This is the raw error, i.e., i.e. More...
 
Vector unweightedWhitenedError (const Values &c) const
 Vector of errors, whitened, but unweighted by any loss function.
 
double weight (const Values &c) const
 Compute the effective weight of the factor from the noise model.
 
double error (const Values &c) const override
 Calculate the error of the factor. More...
 
boost::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 Linearize a non-linearFactorN to get a GaussianFactor, \( Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z \) Hence \( b = z - h(x) = - \mathtt{error\_vector}(x) \). More...
 
shared_ptr cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const
 Creates a shared_ptr clone of the factor with a new noise model.
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 NonlinearFactor ()
 Default constructor for I/O only.
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 Constructor from a collection of the keys involved in this factor.
 
virtual ~NonlinearFactor ()
 Destructor.
 
virtual bool active (const Values &) const
 Checks whether a factor should be used based on a set of values. More...
 
virtual shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 Creates a shared_ptr clone of the factor with different keys using a map from old->new keys. More...
 
virtual shared_ptr rekey (const KeyVector &new_keys) const
 Clones a factor and fully replaces its keys. More...
 
virtual bool sendable () const
 Should the factor be evaluated in the same thread as the caller This is to enable factors that has shared states (like the Python GIL lock) More...
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor.
 
KeyVectorkeys ()
 
iterator begin ()
 Iterator at beginning of involved variable keys.
 
iterator end ()
 Iterator at end of involved variable keys.
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys More...
 
Key front () const
 First key.
 
Key back () const
 Last key.
 
const_iterator find (Key key) const
 find
 
const KeyVectorkeys () const
 Access the factor's involved variable keys.
 
const_iterator begin () const
 Iterator at beginning of involved variable keys.
 
const_iterator end () const
 Iterator at end of involved variable keys.
 
size_t size () const
 
- Public Member Functions inherited from gtsam::AttitudeFactor
 AttitudeFactor ()
 default constructor - only use for serialization
 
 AttitudeFactor (const Unit3 &nZ, const Unit3 &bRef=Unit3(0, 0, 1))
 Constructor. More...
 
Vector attitudeError (const Rot3 &p, OptionalJacobian< 2, 3 > H=boost::none) const
 vector of errors
 
const Unit3nZ () const
 
const Unit3bRef () const
 
template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int)
 

Public Types

typedef boost::shared_ptr< Pose3AttitudeFactorshared_ptr
 shorthand for a smart pointer to a factor
 
typedef Pose3AttitudeFactor This
 Typedef to this class.
 
- Public Types inherited from gtsam::NoiseModelFactor1< Pose3 >
typedef Pose3 X
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef boost::shared_ptr< Thisshared_ptr
 Noise model.
 
- Public Types inherited from gtsam::NonlinearFactor
typedef boost::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 

Friends

class boost::serialization::access
 Serialization function.
 

Additional Inherited Members

- Protected Types inherited from gtsam::NoiseModelFactor1< Pose3 >
typedef NoiseModelFactor Base
 
typedef NoiseModelFactor1< Pose3This
 
- Protected Types inherited from gtsam::NoiseModelFactor
typedef NonlinearFactor Base
 
typedef NoiseModelFactor This
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 
- Protected Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor (const SharedNoiseModel &noiseModel)
 Constructor - only for subclasses, as this does not set keys.
 
- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 Default constructor for I/O.
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 Construct factor from container of keys. More...
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys. More...
 
bool equals (const This &other, double tol=1e-9) const
 check equality
 
- Static Protected Member Functions inherited from gtsam::Factor
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 Construct factor from container of keys. More...
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys. More...
 
- Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor.
 
- Protected Attributes inherited from gtsam::AttitudeFactor
Unit3 nZ_
 
Unit3 bRef_
 Position measurement in.
 

Constructor & Destructor Documentation

◆ Pose3AttitudeFactor()

gtsam::Pose3AttitudeFactor::Pose3AttitudeFactor ( Key  key,
const Unit3 nZ,
const SharedNoiseModel model,
const Unit3 bRef = Unit3(0, 0, 1) 
)
inline

Constructor.

Parameters
keyof the Pose3 variable that will be constrained
nZmeasured direction in navigation frame
modelGaussian noise model
bRefreference direction in body frame (default Z-axis)

Member Function Documentation

◆ clone()

gtsam::NonlinearFactor::shared_ptr gtsam::Pose3AttitudeFactor::clone ( ) const
inlineoverridevirtual
Returns
a deep copy of this factor

Reimplemented from gtsam::NonlinearFactor.

◆ equals()

bool gtsam::Pose3AttitudeFactor::equals ( const NonlinearFactor expected,
double  tol = 1e-9 
) const
overridevirtual

equals

Reimplemented from gtsam::NonlinearFactor.

◆ evaluateError()

Vector gtsam::Pose3AttitudeFactor::evaluateError ( const Pose3 nTb,
boost::optional< Matrix & >  H = boost::none 
) const
inlineoverridevirtual

vector of errors

Implements gtsam::NoiseModelFactor1< Pose3 >.

◆ print()

void gtsam::Pose3AttitudeFactor::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
overridevirtual

print

Reimplemented from gtsam::Factor.


The documentation for this class was generated from the following files: