#include <GravityFactor.h>
|
Unit3 | bRef () const |
|
virtual gtsam::NonlinearFactor::shared_ptr | clone () const |
|
virtual bool | equals (const NonlinearFactor &expected, double tol=1e-9) const |
|
virtual Vector | evaluateError (const Rot3 &nRb, boost::optional< Matrix &> H=boost::none) const |
|
Unit3 | nZ () const |
|
virtual void | print (const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const |
|
| Rot3GravityFactor () |
|
| Rot3GravityFactor (Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1)) |
| Constructor. More...
|
|
virtual | ~Rot3GravityFactor () |
|
Vector | attitudeError (const Rot3 &p, OptionalJacobian< 2, 3 > H=boost::none) const |
|
| GravityFactor () |
|
| GravityFactor (const Unit3 &nZ, const Unit3 &bRef=Unit3(0, 0, 1)) |
| Constructor. More...
|
|
template<class ARCHIVE > |
void | serialize (ARCHIVE &ar, const unsigned int) |
|
|
typedef NoiseModelFactor1< Rot3 > | Base |
|
|
template<class ARCHIVE > |
void | serialize (ARCHIVE &ar, const unsigned int) |
|
Definition at line 81 of file GravityFactor.h.
◆ Base
◆ shared_ptr
shorthand for a smart pointer to a factor
Definition at line 88 of file GravityFactor.h.
◆ This
◆ Rot3GravityFactor() [1/2]
rtabmap::Rot3GravityFactor::Rot3GravityFactor |
( |
| ) |
|
|
inline |
default constructor - only use for serialization
Definition at line 94 of file GravityFactor.h.
◆ ~Rot3GravityFactor()
virtual rtabmap::Rot3GravityFactor::~Rot3GravityFactor |
( |
| ) |
|
|
inlinevirtual |
◆ Rot3GravityFactor() [2/2]
rtabmap::Rot3GravityFactor::Rot3GravityFactor |
( |
Key |
key, |
|
|
const Unit3 & |
nZ, |
|
|
const SharedNoiseModel & |
model, |
|
|
const Unit3 & |
bRef = Unit3(0, 0, 1) |
|
) |
| |
|
inline |
Constructor.
- Parameters
-
key | of the Rot3 variable that will be constrained |
nZ | measured direction in navigation frame (remove yaw before rotating the gravity vector) |
model | Gaussian noise model |
bRef | reference direction in body frame (default Z-axis) |
Definition at line 107 of file GravityFactor.h.
◆ bRef()
Unit3 rtabmap::Rot3GravityFactor::bRef |
( |
| ) |
const |
|
inline |
◆ clone()
virtual gtsam::NonlinearFactor::shared_ptr rtabmap::Rot3GravityFactor::clone |
( |
| ) |
const |
|
inlinevirtual |
◆ equals()
bool rtabmap::Rot3GravityFactor::equals |
( |
const NonlinearFactor & |
expected, |
|
|
double |
tol = 1e-9 |
|
) |
| const |
|
virtual |
◆ evaluateError()
virtual Vector rtabmap::Rot3GravityFactor::evaluateError |
( |
const Rot3 & |
nRb, |
|
|
boost::optional< Matrix &> |
H = boost::none |
|
) |
| const |
|
inlinevirtual |
◆ nZ()
Unit3 rtabmap::Rot3GravityFactor::nZ |
( |
| ) |
const |
|
inline |
◆ print()
void rtabmap::Rot3GravityFactor::print |
( |
const std::string & |
s, |
|
|
const KeyFormatter & |
keyFormatter = DefaultKeyFormatter |
|
) |
| const |
|
virtual |
◆ serialize()
template<class ARCHIVE >
void rtabmap::Rot3GravityFactor::serialize |
( |
ARCHIVE & |
ar, |
|
|
const unsigned |
int |
|
) |
| |
|
inlineprivate |
◆ boost::serialization::access
friend class boost::serialization::access |
|
friend |
The documentation for this class was generated from the following files: