Class Quaternion


  • public class Quaternion
    extends Rotation3DVector
    A Quaternion \mathbf{q}\in \mathbb{R}^4 a complex
    number used to describe rotations in 3-dimensional space.
    q_w+{\bf i}\ q_x+ {\bf j} q_y+ {\bf k}\ q_z

    Quaternions can be added and multiplied in a similar way as usual
    algebraic numbers. Though there are differences. Quaternion
    multiplication is not commutative which means
    Q\cdot P \neq P\cdot Q
    • Constructor Detail

      • Quaternion

        public Quaternion​(long cPtr,
                          boolean cMemoryOwn)
      • Quaternion

        public Quaternion()
        constuct Quaterinion of {0,0,0,1}
      • Quaternion

        public Quaternion​(double qx,
                          double qy,
                          double qz,
                          double qw)
        Creates a Quaternion
        Parameters:
        qx - [in] q_x
        qy - [in] q_y
        qz - [in] q_z
        qw - [in] q_w
      • Quaternion

        public Quaternion​(Quaternion quat)
        Creates a Quaternion from another Quaternion
        Parameters:
        quat - [in] Quaternion
      • Quaternion

        public Quaternion​(Rotation3DVector rot)
        Creates a Quaternion from another Rotation3DVector type
        Parameters:
        rot - [in] The Rotation3DVector type
      • Quaternion

        public Quaternion​(Rotation3D rot)
        Extracts a Quaternion from Rotation matrix using
        setRotation(const Rotation3D<R>& rot)
        Parameters:
        rot - [in] A 3x3 rotation matrix \mathbf{rot}
      • Quaternion

        public Quaternion​(EigenQuaterniond r)
        Creates a Quaternion from a Eigen quaternion
        Parameters:
        r - [in] a boost quaternion
    • Method Detail

      • getCPtr

        public static long getCPtr​(Quaternion obj)
      • getQx

        public double getQx()
        get method for the x component
        Returns:
        the x component of the quaternion
      • getQy

        public double getQy()
        get method for the y component
        Returns:
        the y component of the quaternion
      • getQz

        public double getQz()
        get method for the z component
        Returns:
        the z component of the quaternion
      • getQw

        public double getQw()
        get method for the w component
        Returns:
        the w component of the quaternion
      • get

        public double get​(long i)
      • set

        public void set​(long i,
                        double d)
      • size

        public long size()
        The dimension of the quaternion (i.e. 4).
        This method is provided to help support generic algorithms using
        size() and operator[].
      • e

        public EigenQuaterniond e()
        Convert to an Eigen Quaternion.
        Returns:
        Eigen Quaternion representation.
      • negate

        public Quaternion negate()
        Unary minus.
      • multiply

        public Quaternion multiply​(double s)
        Scalar multiplication.
      • divide

        public Quaternion divide​(double s)
        Scalar Devision.
      • elemDivide

        public Quaternion elemDivide​(double lhs)
        element whise division
        Parameters:
        lhs - [in] the scalar to devide with
        Returns:
        the result of elementwise devision
      • getLength

        public double getLength()
        get length of quaternion
        \sqrt{q_x^2+q_y^2+q_z^2+q_w^2}
        Returns:
        the length og this quaternion
      • getLengthSquared

        public double getLengthSquared()
        get squared length of quaternion
        q_x^2+q_y^2+q_z^2+q_w^2
        Returns:
        the length og this quaternion
      • normalize

        public void normalize()
        normalizes this quaternion so that
        normalze(Q)=\frac{Q}{\sqrt{q_x^2+q_y^2+q_z^2+q_w^2}}
      • slerp

        public Quaternion slerp​(Quaternion v,
                                double t)
        Calculates a slerp interpolation between this and v.

        The slerp interpolation ensures a constant velocity across the interpolation.
        For t=0 the result is this and for t=1 it is v.

        Note: Algorithm and implementation is thanks to euclideanspace.com
      • inverse

        public Quaternion inverse()
        Calculate the inverse Quaternion
        Returns:
        the inverse quaternion
      • ln

        public Quaternion ln()
        calculates the natural logerithm of this quaternion
        Returns:
        natural logetihm
      • pow

        public Quaternion pow​(double power)
        calculates the quaternion lifted to the power of power
        Parameters:
        power - [in] the power the quaternion is lifted to
        Returns:
        Quaternion^power
      • copy

        public void copy​(EigenQuaterniond r)
        copy a boost quaternion to this Quaternion
        Parameters:
        r - [in] - boost quaternion
      • multiplyAssign

        public Quaternion multiplyAssign​(double s)
        Scalar multiplication.
      • equals

        public boolean equals​(Quaternion r)
        Comparison (equals) operator
      • notEqual

        public boolean notEqual​(Quaternion r)
        Comparison (not equals) operator
      • toString

        public java.lang.String toString()
        Overrides:
        toString in class java.lang.Object