gtsam 4.1.1
gtsam
gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY > Class Template Reference
+ Inheritance diagram for gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >:

Public Member Functions

 EquivInertialNavFactor_GlobalVel_NoBias ()
 default constructor - only use for serialization
 
 EquivInertialNavFactor_GlobalVel_NoBias (const Key &Pose1, const Key &Vel1, const Key &Pose2, const Key &Vel2, const Vector &delta_pos_in_t0, const Vector &delta_vel_in_t0, const Vector3 &delta_angles, double dt12, const Vector world_g, const Vector world_rho, const Vector &world_omega_earth, const noiseModel::Gaussian::shared_ptr &model_equivalent, const Matrix &Jacobian_wrt_t0_Overall, boost::optional< POSE > body_P_sensor=boost::none)
 Constructor.
 
virtual void print (const std::string &s="EquivInertialNavFactor_GlobalVel_NoBias", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 implement functions needed for Testable More...
 
bool equals (const NonlinearFactor &expected, double tol=1e-9) const override
 equals More...
 
POSE predictPose (const POSE &Pose1, const VELOCITY &Vel1) const
 
VELOCITY predictVelocity (const POSE &Pose1, const VELOCITY &Vel1) const
 
void predict (const POSE &Pose1, const VELOCITY &Vel1, POSE &Pose2, VELOCITY &Vel2) const
 
POSE evaluatePoseError (const POSE &Pose1, const VELOCITY &Vel1, const POSE &Pose2, const VELOCITY &Vel2) const
 
VELOCITY evaluateVelocityError (const POSE &Pose1, const VELOCITY &Vel1, const POSE &Pose2, const VELOCITY &Vel2) const
 
Vector evaluateError (const POSE &Pose1, const VELOCITY &Vel1, const POSE &Pose2, const VELOCITY &Vel2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none) const
 Override this method to finish implementing a 4-way factor. More...
 
- Public Member Functions inherited from gtsam::NoiseModelFactor4< POSE, VELOCITY, POSE, VELOCITY >
 NoiseModelFactor4 ()
 Default Constructor for I/O.
 
 NoiseModelFactor4 (const SharedNoiseModel &noiseModel, Key j1, Key j2, Key j3, Key j4)
 Constructor. More...
 
Key key1 () const
 methods to retrieve keys
 
Key key2 () const
 
Key key3 () const
 
Key key4 () const
 
Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
 Calls the 4-key specific version of evaluateError, which is pure virtual so must be implemented in the derived class. More...
 
virtual Vector evaluateError (const X1 &, const X2 &, const X3 &, const X4 &, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none) const=0
 Override this method to finish implementing a 4-way factor. 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 clone () const
 Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses. 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
 

Static Public Member Functions

static POSE predictPose_inertial (const POSE &Pose1, const VELOCITY &Vel1, const Vector &delta_pos_in_t0, const Vector3 &delta_angles, const double dt12, const Vector &world_g, const Vector &world_rho, const Vector &world_omega_earth)
 
static VELOCITY predictVelocity_inertial (const POSE &Pose1, const VELOCITY &Vel1, const Vector &delta_vel_in_t0, const double dt12, const Vector &world_g, const Vector &world_rho, const Vector &world_omega_earth)
 
static POSE PredictPoseFromPreIntegration (const POSE &Pose1, const VELOCITY &Vel1, const Vector &delta_pos_in_t0, const Vector3 &delta_angles, double dt12, const Vector world_g, const Vector world_rho, const Vector &world_omega_earth, const Matrix &Jacobian_wrt_t0_Overall)
 
static VELOCITY PredictVelocityFromPreIntegration (const POSE &Pose1, const VELOCITY &Vel1, const Vector &delta_vel_in_t0, double dt12, const Vector world_g, const Vector world_rho, const Vector &world_omega_earth, const Matrix &Jacobian_wrt_t0_Overall)
 
static void PredictFromPreIntegration (const POSE &Pose1, const VELOCITY &Vel1, POSE &Pose2, VELOCITY &Vel2, const Vector &delta_pos_in_t0, const Vector &delta_vel_in_t0, const Vector3 &delta_angles, double dt12, const Vector world_g, const Vector world_rho, const Vector &world_omega_earth, const Matrix &Jacobian_wrt_t0_Overall)
 
static void PreIntegrateIMUObservations (const Vector &msr_acc_t, const Vector &msr_gyro_t, const double msr_dt, Vector &delta_pos_in_t0, Vector3 &delta_angles, Vector &delta_vel_in_t0, double &delta_t, const noiseModel::Gaussian::shared_ptr &model_continuous_overall, Matrix &EquivCov_Overall, Matrix &Jacobian_wrt_t0_Overall, boost::optional< POSE > p_body_P_sensor=boost::none)
 
static Vector PreIntegrateIMUObservations_delta_pos (const double msr_dt, const Vector &delta_pos_in_t0, const Vector &delta_vel_in_t0)
 
static Vector PreIntegrateIMUObservations_delta_vel (const Vector &msr_gyro_t, const Vector &msr_acc_t, const double msr_dt, const Vector3 &delta_angles, const Vector &delta_vel_in_t0, const bool flag_use_body_P_sensor, const POSE &body_P_sensor)
 
static Vector PreIntegrateIMUObservations_delta_angles (const Vector &msr_gyro_t, const double msr_dt, const Vector3 &delta_angles, const bool flag_use_body_P_sensor, const POSE &body_P_sensor)
 
static noiseModel::Gaussian::shared_ptr CalcEquivalentNoiseCov (const noiseModel::Gaussian::shared_ptr &gaussian_acc, const noiseModel::Gaussian::shared_ptr &gaussian_gyro, const noiseModel::Gaussian::shared_ptr &gaussian_process)
 
static void CalcEquivalentNoiseCov_DifferentParts (const noiseModel::Gaussian::shared_ptr &gaussian_acc, const noiseModel::Gaussian::shared_ptr &gaussian_gyro, const noiseModel::Gaussian::shared_ptr &gaussian_process, Matrix &cov_acc, Matrix &cov_gyro, Matrix &cov_process_without_acc_gyro)
 
static void Calc_g_rho_omega_earth_NED (const Vector &Pos_NED, const Vector &Vel_NED, const Vector &LatLonHeight_IC, const Vector &Pos_NED_Initial, Vector &g_NED, Vector &rho_NED, Vector &omega_earth_NED)
 
static void Calc_g_rho_omega_earth_ENU (const Vector &Pos_ENU, const Vector &Vel_ENU, const Vector &LatLonHeight_IC, const Vector &Pos_ENU_Initial, Vector &g_ENU, Vector &rho_ENU, Vector &omega_earth_ENU)
 
static noiseModel::Gaussian::shared_ptr calc_descrete_noise_model (const noiseModel::Gaussian::shared_ptr &model, double delta_t)
 

Public Types

typedef boost::shared_ptr< EquivInertialNavFactor_GlobalVel_NoBiasshared_ptr
 
- Public Types inherited from gtsam::NoiseModelFactor4< POSE, VELOCITY, POSE, VELOCITY >
typedef POSE X1
 
typedef VELOCITY X2
 
typedef POSE X3
 
typedef VELOCITY X4
 
- 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::NoiseModelFactor4< POSE, VELOCITY, POSE, VELOCITY >
typedef NoiseModelFactor Base
 
typedef NoiseModelFactor4< POSE, VELOCITY, POSE, VELOCITY > This
 
- 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.
 

Member Function Documentation

◆ equals()

template<class POSE , class VELOCITY >
bool gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >::equals ( const NonlinearFactor expected,
double  tol = 1e-9 
) const
inlineoverridevirtual

equals

Reimplemented from gtsam::NoiseModelFactor.

◆ evaluateError()

template<class POSE , class VELOCITY >
Vector gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >::evaluateError ( const POSE &  ,
const VELOCITY &  ,
const POSE &  ,
const VELOCITY &  ,
boost::optional< Matrix & >  H1 = boost::none,
boost::optional< Matrix & >  H2 = boost::none,
boost::optional< Matrix & >  H3 = boost::none,
boost::optional< Matrix & >  H4 = boost::none 
) const
inlinevirtual

Override this method to finish implementing a 4-way factor.

If any of the optional Matrix reference arguments are specified, it should compute both the function evaluation and its derivative(s) in X1 (and/or X2, X3).

Implements gtsam::NoiseModelFactor4< POSE, VELOCITY, POSE, VELOCITY >.

◆ print()

template<class POSE , class VELOCITY >
virtual void gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >::print ( const std::string &  s = "EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
inlinevirtual

implement functions needed for Testable

print

Reimplemented from gtsam::NoiseModelFactor.


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