Class Quaternion

java.lang.Object
edu.wpi.first.math.geometry.Quaternion
All Implemented Interfaces:
ProtobufSerializable, StructSerializable, WPISerializable

public class Quaternion
extends Object
implements ProtobufSerializable, StructSerializable
Represents a quaternion.
  • Field Details

  • Constructor Details

    • Quaternion

      public Quaternion()
      Constructs a quaternion with a default angle of 0 degrees.
    • Quaternion

      public Quaternion​(double w, double x, double y, double z)
      Constructs a quaternion with the given components.
      Parameters:
      w - W component of the quaternion.
      x - X component of the quaternion.
      y - Y component of the quaternion.
      z - Z component of the quaternion.
  • Method Details

    • plus

      public Quaternion plus​(Quaternion other)
      Adds another quaternion to this quaternion entrywise.
      Parameters:
      other - The other quaternion.
      Returns:
      The quaternion sum.
    • minus

      public Quaternion minus​(Quaternion other)
      Subtracts another quaternion from this quaternion entrywise.
      Parameters:
      other - The other quaternion.
      Returns:
      The quaternion difference.
    • divide

      public Quaternion divide​(double scalar)
      Divides by a scalar.
      Parameters:
      scalar - The value to scale each component by.
      Returns:
      The scaled quaternion.
    • times

      public Quaternion times​(double scalar)
      Multiplies with a scalar.
      Parameters:
      scalar - The value to scale each component by.
      Returns:
      The scaled quaternion.
    • times

      public Quaternion times​(Quaternion other)
      Multiply with another quaternion.
      Parameters:
      other - The other quaternion.
      Returns:
      The quaternion product.
    • toString

      public String toString()
      Overrides:
      toString in class Object
    • equals

      public boolean equals​(Object obj)
      Checks equality between this Quaternion and another object.
      Overrides:
      equals in class Object
      Parameters:
      obj - The other object.
      Returns:
      Whether the two objects are equal or not.
    • hashCode

      public int hashCode()
      Overrides:
      hashCode in class Object
    • conjugate

      Returns the conjugate of the quaternion.
      Returns:
      The conjugate quaternion.
    • dot

      public double dot​(Quaternion other)
      Returns the elementwise product of two quaternions.
      Parameters:
      other - The other quaternion.
      Returns:
      The dot product of two quaternions.
    • inverse

      public Quaternion inverse()
      Returns the inverse of the quaternion.
      Returns:
      The inverse quaternion.
    • norm

      public double norm()
      Calculates the L2 norm of the quaternion.
      Returns:
      The L2 norm.
    • normalize

      Normalizes the quaternion.
      Returns:
      The normalized quaternion.
    • pow

      public Quaternion pow​(double t)
      Rational power of a quaternion.
      Parameters:
      t - the power to raise this quaternion to.
      Returns:
      The quaternion power
    • exp

      public Quaternion exp​(Quaternion adjustment)
      Matrix exponential of a quaternion.
      Parameters:
      adjustment - the "Twist" that will be applied to this quaternion.
      Returns:
      The quaternion product of exp(adjustment) * this
    • exp

      public Quaternion exp()
      Matrix exponential of a quaternion.

      source: wpimath/algorithms.md

      If this quaternion is in 𝖘𝖔(3) and you are looking for an element of SO(3), use fromRotationVector(edu.wpi.first.math.Vector<edu.wpi.first.math.numbers.N3>)

      Returns:
      The Matrix exponential of this quaternion.
    • log

      public Quaternion log​(Quaternion end)
      Log operator of a quaternion.
      Parameters:
      end - The quaternion to map this quaternion onto.
      Returns:
      The "Twist" that maps this quaternion to the argument.
    • log

      public Quaternion log()
      The Log operator of a general quaternion.

      source: wpimath/algorithms.md

      If this quaternion is in SO(3) and you are looking for an element of 𝖘𝖔(3), use toRotationVector()

      Returns:
      The logarithm of this quaternion.
    • getW

      public double getW()
      Returns W component of the quaternion.
      Returns:
      W component of the quaternion.
    • getX

      public double getX()
      Returns X component of the quaternion.
      Returns:
      X component of the quaternion.
    • getY

      public double getY()
      Returns Y component of the quaternion.
      Returns:
      Y component of the quaternion.
    • getZ

      public double getZ()
      Returns Z component of the quaternion.
      Returns:
      Z component of the quaternion.
    • fromRotationVector

      public static Quaternion fromRotationVector​(Vector<N3> rvec)
      Returns the quaternion representation of this rotation vector.

      This is also the exp operator of 𝖘𝖔(3).

      source: wpimath/algorithms.md

      Parameters:
      rvec - The rotation vector.
      Returns:
      The quaternion representation of this rotation vector.
    • toRotationVector

      Returns the rotation vector representation of this quaternion.

      This is also the log operator of SO(3).

      Returns:
      The rotation vector representation of this quaternion.