ov_type::JPLQuat class

Derived Type class that implements JPL quaternion.

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:

We need to take special care to handle edge cases when converting to and from other rotation formats. All equations are based on the following tech report [40] :

Trawny, Nikolas, and Stergios I. Roumeliotis. "Indirect Kalman filter for 3D attitude estimation." University of Minnesota, Dept. of Comp. Sci. & Eng., Tech. Rep 2 (2005): 2005. http://mars.cs.umn.edu/tr/reports/Trawny05b.pdf

JPL Quaternion Definition

We define the quaternion as the following linear combination:

\[ \bar{q} = q_4+q_1\mathbf{i}+q_2\mathbf{j}+q_3\mathbf{k} \]

Where i,j,k are defined as the following:

\[ \mathbf{i}^2=-1~,~\mathbf{j}^2=-1~,~\mathbf{k}^2=-1 \]
\[ -\mathbf{i}\mathbf{j}=\mathbf{j}\mathbf{i}=\mathbf{k} ~,~ -\mathbf{j}\mathbf{k}=\mathbf{k}\mathbf{j}=\mathbf{i} ~,~ -\mathbf{k}\mathbf{i}=\mathbf{i}\mathbf{k}=\mathbf{j} \]

As noted in [40] this does not correspond to the Hamilton notation, and follows the "JPL Proposed Standard Conventions". The q_4 quantity is the "scalar" portion of the quaternion, while q_1, q_2, q_3 are part of the "vector" portion. We split the 4x1 vector into the following convention:

\[ \bar{q} = \begin{bmatrix}q_1\\q_2\\q_3\\q_4\end{bmatrix} = \begin{bmatrix}\mathbf{q}\\q_4\end{bmatrix} \]

It is also important to note that the quaternion is constrained to the unit circle:

\[ |\bar{q}| = \sqrt{\bar{q}^\top\bar{q}} = \sqrt{|\mathbf{q}|^2+q_4^2} = 1 \]

Error State Definition

It is important to note that one can prove that the left-multiplicative quaternion error is equivalent to the SO(3) error. If one wishes to use the right-hand error, this would need to be implemented as a different type then this class! This is noted in Eq. (71) in [40] . Specifically we have the following:

\begin{align*} {}^{I}_G\bar{q} &\simeq \begin{bmatrix} \frac{1}{2} \delta \boldsymbol{\theta} \\ 1 \end{bmatrix} \otimes {}^{I}_G\hat{\bar{q}} \end{align*}

which is the same as:

\begin{align*} {}^{I}_G \mathbf{R} &\simeq \exp(-\delta \boldsymbol{\theta}) {}^{I}_G \hat{\mathbf{R}} \\ &\simeq (\mathbf{I} - \lfloor \delta \boldsymbol{\theta} \rfloor) {}^{I}_G \hat{\mathbf{R}} \\ \end{align*}

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
\[ \bar{q}=norm\Big(\begin{bmatrix} \frac{1}{2} \delta \boldsymbol{\theta}_{dx} \\ 1 \end{bmatrix}\Big) \otimes \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 (JPL quat as x,y,z,w)

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 (JPL quat as x,y,z,w)

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