class
JPLQuatDerived Type class that implements JPL quaternion.
Contents
- Reference
This quaternion uses a left-multiplicative error state and follows the "JPL convention". Please checkout our utility functions in the quat_
- http:/
/ mars.cs.umn.edu/ tr/ reports/ Trawny05b.pdf - ftp://naif.jpl.nasa.gov/pub/naif/misc/Quaternion_
White_ Paper/Quaternions_ White_ Paper.pdf
Base classes
- class Type
- Base class for estimated variables.
Public functions
- void update(const Eigen::VectorXd& dx) override
- Implements update operation by left-multiplying the current quaternion with a quaternion built from a small axis-angle perturbation.
- void set_value(const Eigen::MatrixXd& new_value) override
- Sets the value of the estimate and recomputes the internal rotation matrix.
- void set_fej(const Eigen::MatrixXd& new_value) override
- Sets the fej value and recomputes the fej rotation matrix.
- auto clone() -> std::shared_ptr<Type> override
- Create a clone of this variable.
- auto Rot() const -> Eigen::Matrix<double, 3, 3>
- Rotation access.
- auto Rot_fej() const -> Eigen::Matrix<double, 3, 3>
- FEJ Rotation access.
Protected functions
- void set_value_internal(const Eigen::MatrixXd& new_value)
- Sets the value of the estimate and recomputes the internal rotation matrix.
- void set_fej_internal(const Eigen::MatrixXd& new_value)
- Sets the fej value and recomputes the fej rotation matrix.
Function documentation
void ov_type:: JPLQuat:: update(const Eigen::VectorXd& dx) override
Implements update operation by left-multiplying the current quaternion with a quaternion built from a small axis-angle perturbation.
Parameters | |
---|---|
dx | Axis-angle representation of the perturbing quaternion |
void ov_type:: JPLQuat:: set_value(const Eigen::MatrixXd& new_value) override
Sets the value of the estimate and recomputes the internal rotation matrix.
Parameters | |
---|---|
new_value | New value for the quaternion estimate |
void ov_type:: JPLQuat:: set_fej(const Eigen::MatrixXd& new_value) override
Sets the fej value and recomputes the fej rotation matrix.
Parameters | |
---|---|
new_value | New value for the quaternion estimate |
void ov_type:: JPLQuat:: set_value_internal(const Eigen::MatrixXd& new_value) protected
Sets the value of the estimate and recomputes the internal rotation matrix.
Parameters | |
---|---|
new_value | New value for the quaternion estimate |
void ov_type:: JPLQuat:: set_fej_internal(const Eigen::MatrixXd& new_value) protected
Sets the fej value and recomputes the fej rotation matrix.
Parameters | |
---|---|
new_value | New value for the quaternion estimate |