class mola::FactorAngularVelocityIntegration
Overview
Factor for angular velocity integration model, equivalent to expressions:
gtsam::Expression<gtsam::Point3> deltaWi = dt * bWi; gtsam::Expression<gtsam::Rot3> expmap_(>sam::Rot3::Expmap, deltaWi);
gtsam::between( gtsam::compose(Ri, expmap_), Rj ) = Rot_Identity
#include <FactorAngularVelocityIntegration.h> class FactorAngularVelocityIntegration: public gtsam::ExpressionFactorN< gtsam::Rot3, gtsam::Rot3, gtsam::Point3, gtsam::Rot3 > { public: // construction FactorAngularVelocityIntegration(); FactorAngularVelocityIntegration( gtsam::Key kRi, gtsam::Key kbWi, gtsam::Key kRj, const double dt, const gtsam::SharedNoiseModel& model ); // methods gtsam::NonlinearFactor::shared_ptr clone() const; gtsam::Expression<gtsam::Rot3> expression(const std::array<gtsam::Key, NARY_EXPRESSION_SIZE>& keys) const; void print( const std::string& s, const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter ) const; bool equals(const gtsam::NonlinearFactor& expected, double tol = 1e-9) const; };
Construction
FactorAngularVelocityIntegration()
default constructor
Methods
gtsam::NonlinearFactor::shared_ptr clone() const
Returns:
a deep copy of this factor
void print( const std::string& s, const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter ) const
implement functions needed for Testable print
bool equals(const gtsam::NonlinearFactor& expected, double tol = 1e-9) const
equals