Quaternion

class wpimath.geometry.Quaternion(*args, **kwargs)

Bases: pybind11_object

Represents a quaternion.

Overloaded function.

  1. __init__(self: wpimath.geometry._geometry.Quaternion) -> None

Constructs a quaternion with a default angle of 0 degrees.

  1. __init__(self: wpimath.geometry._geometry.Quaternion, w: float, x: float, y: float, z: float) -> None

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.

W() float

Returns W component of the quaternion.

WPIStruct = <capsule object "WPyStruct">
X() float

Returns X component of the quaternion.

Y() float

Returns Y component of the quaternion.

Z() float

Returns Z component of the quaternion.

conjugate() wpimath.geometry._geometry.Quaternion

Returns the conjugate of the quaternion.

dot(other: wpimath.geometry._geometry.Quaternion) float

Returns the elementwise product of two quaternions.

exp(*args, **kwargs)

Overloaded function.

  1. exp(self: wpimath.geometry._geometry.Quaternion, other: wpimath.geometry._geometry.Quaternion) -> wpimath.geometry._geometry.Quaternion

Matrix exponential of a quaternion.

Parameters:

other – the “Twist” that will be applied to this quaternion.

  1. exp(self: wpimath.geometry._geometry.Quaternion) -> wpimath.geometry._geometry.Quaternion

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

static fromRotationVector(rvec: numpy.ndarray[numpy.float64[3, 1]]) wpimath.geometry._geometry.Quaternion

Returns the quaternion representation of this rotation vector.

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

source: wpimath/algorithms.md

inverse() wpimath.geometry._geometry.Quaternion

Returns the inverse of the quaternion.

log(*args, **kwargs)

Overloaded function.

  1. log(self: wpimath.geometry._geometry.Quaternion, other: wpimath.geometry._geometry.Quaternion) -> wpimath.geometry._geometry.Quaternion

Log operator of a quaternion.

Parameters:

other – The quaternion to map this quaternion onto

  1. log(self: wpimath.geometry._geometry.Quaternion) -> wpimath.geometry._geometry.Quaternion

Log operator of a quaternion.

source: wpimath/algorithms.md

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

norm() float

Calculates the L2 norm of the quaternion.

normalize() wpimath.geometry._geometry.Quaternion

Normalizes the quaternion.

pow(t: float) wpimath.geometry._geometry.Quaternion

Calculates this quaternion raised to a power.

Parameters:

t – the power to raise this quaternion to.

toRotationVector() numpy.ndarray[numpy.float64[3, 1]]

Returns the rotation vector representation of this quaternion.

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