class mola::factors::Pose3RotationFactor
Overview
GTSAM factor for observations on the Rot3 part only of a Pose3
#include <Pose3RotationFactor.h> class Pose3RotationFactor: public gtsam::ExpressionFactorN< gtsam::Rot3, gtsam::Pose3, gtsam::Pose3 > { public: // construction Pose3RotationFactor(); Pose3RotationFactor( gtsam::Key kT_enu2map, gtsam::Key kPi, const gtsam::Pose3& sensorPoseOnVehicle, const gtsam::Rot3& observedOrientation, 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
Pose3RotationFactor()
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