ov_type::JPLQuat class

Derived Type class that implements JPL quaternion.

Contents

This quaternion uses a left-multiplicative error state and follows the "JPL convention". Please checkout our utility functions in the quat_ops.h file. We recommend that people new quaternions check out the following resources:

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.
auto clone() -> Type* override
Create a clone of this variable.
void set_fej(const Eigen::MatrixXd new_value) override
Sets the fej value and recomputes the fej rotation matrix.
auto Rot() const -> Eigen::Matrix<double, 3, 3>
Rotation access.
auto Rot_fej() const -> Eigen::Matrix<double, 3, 3>
FEJ Rotation access.

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
\[ \bar{q}=norm\Big(\begin{bmatrix} 0.5*\mathbf{\theta_{dx}} \\ 1 \end{bmatrix}\Big) \hat{\bar{q}} \]

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