Quaternion

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

Bases: pybind11_object

Represents a quaternion.

Overloaded function.

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

Constructs a quaternion with a default angle of 0 degrees.

  1. __init__(self: wpimath._wpimath.Quaternion, w: typing.SupportsFloat | typing.SupportsIndex, x: typing.SupportsFloat | typing.SupportsIndex, y: typing.SupportsFloat | typing.SupportsIndex, z: typing.SupportsFloat | typing.SupportsIndex) -> 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._wpimath.Quaternion

Returns the conjugate of the quaternion.

dot(other: wpimath._wpimath.Quaternion) float

Returns the elementwise product of two quaternions.

exp() wpimath._wpimath.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: Annotated[numpy.typing.ArrayLike, numpy.float64, '[3, 1]']) wpimath._wpimath.Quaternion

Returns the quaternion representation of this rotation vector.

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

source: wpimath/algorithms.md

inverse() wpimath._wpimath.Quaternion

Returns the inverse of the quaternion.

log() wpimath._wpimath.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._wpimath.Quaternion

Normalizes the quaternion.

pow(t: SupportsFloat | SupportsIndex) wpimath._wpimath.Quaternion

Calculates this quaternion raised to a power.

Parameters:

t – the power to raise this quaternion to.

toRotationVector() Annotated[numpy.typing.NDArray[numpy.float64], '[3, 1]']

Returns the rotation vector representation of this quaternion.

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

property w
property x
property y
property z