WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
frc::Quaternion Class Reference

Represents a quaternion. More...

#include <frc/geometry/Quaternion.h>

Public Member Functions

constexpr Quaternion ()=default
 Constructs a quaternion with a default angle of 0 degrees.
 
constexpr Quaternion (double w, double x, double y, double z)
 Constructs a quaternion with the given components.
 
constexpr Quaternion operator+ (const Quaternion &other) const
 Adds with another quaternion.
 
constexpr Quaternion operator- (const Quaternion &other) const
 Subtracts another quaternion.
 
constexpr Quaternion operator* (double other) const
 Multiples with a scalar value.
 
constexpr Quaternion operator/ (double other) const
 Divides by a scalar value.
 
constexpr Quaternion operator* (const Quaternion &other) const
 Multiply with another quaternion.
 
constexpr bool operator== (const Quaternion &other) const
 Checks equality between this Quaternion and another object.
 
constexpr double Dot (const Quaternion &other) const
 Returns the elementwise product of two quaternions.
 
constexpr Quaternion Conjugate () const
 Returns the conjugate of the quaternion.
 
constexpr Quaternion Inverse () const
 Returns the inverse of the quaternion.
 
constexpr Quaternion Normalize () const
 Normalizes the quaternion.
 
constexpr double Norm () const
 Calculates the L2 norm of the quaternion.
 
constexpr Quaternion Pow (double t) const
 Calculates this quaternion raised to a power.
 
constexpr Quaternion Exp (const Quaternion &other) const
 Matrix exponential of a quaternion.
 
constexpr Quaternion Exp () const
 Matrix exponential of a quaternion.
 
constexpr Quaternion Log (const Quaternion &other) const
 Log operator of a quaternion.
 
constexpr Quaternion Log () const
 Log operator of a quaternion.
 
constexpr double W () const
 Returns W component of the quaternion.
 
constexpr double X () const
 Returns X component of the quaternion.
 
constexpr double Y () const
 Returns Y component of the quaternion.
 
constexpr double Z () const
 Returns Z component of the quaternion.
 
constexpr Eigen::Vector3d ToRotationVector () const
 Returns the rotation vector representation of this quaternion.
 

Static Public Member Functions

static constexpr Quaternion FromRotationVector (const Eigen::Vector3d &rvec)
 Returns the quaternion representation of this rotation vector.
 

Detailed Description

Represents a quaternion.

Constructor & Destructor Documentation

◆ Quaternion() [1/2]

frc::Quaternion::Quaternion ( )
constexprdefault

Constructs a quaternion with a default angle of 0 degrees.

◆ Quaternion() [2/2]

frc::Quaternion::Quaternion ( double w,
double x,
double y,
double z )
inlineconstexpr

Constructs a quaternion with the given components.

Parameters
wW component of the quaternion.
xX component of the quaternion.
yY component of the quaternion.
zZ component of the quaternion.

Member Function Documentation

◆ Conjugate()

Quaternion frc::Quaternion::Conjugate ( ) const
inlineconstexpr

Returns the conjugate of the quaternion.

◆ Dot()

double frc::Quaternion::Dot ( const Quaternion & other) const
inlineconstexpr

Returns the elementwise product of two quaternions.

◆ Exp() [1/2]

Quaternion frc::Quaternion::Exp ( ) const
inlineconstexpr

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

◆ Exp() [2/2]

Quaternion frc::Quaternion::Exp ( const Quaternion & other) const
inlineconstexpr

Matrix exponential of a quaternion.

Parameters
otherthe "Twist" that will be applied to this quaternion.

◆ FromRotationVector()

static constexpr Quaternion frc::Quaternion::FromRotationVector ( const Eigen::Vector3d & rvec)
inlinestaticconstexpr

Returns the quaternion representation of this rotation vector.

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

source: wpimath/algorithms.md

◆ Inverse()

Quaternion frc::Quaternion::Inverse ( ) const
inlineconstexpr

Returns the inverse of the quaternion.

◆ Log() [1/2]

Quaternion frc::Quaternion::Log ( ) const
inlineconstexpr

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

◆ Log() [2/2]

Quaternion frc::Quaternion::Log ( const Quaternion & other) const
inlineconstexpr

Log operator of a quaternion.

Parameters
otherThe quaternion to map this quaternion onto

◆ Norm()

double frc::Quaternion::Norm ( ) const
inlineconstexpr

Calculates the L2 norm of the quaternion.

◆ Normalize()

Quaternion frc::Quaternion::Normalize ( ) const
inlineconstexpr

Normalizes the quaternion.

◆ operator*() [1/2]

Quaternion frc::Quaternion::operator* ( const Quaternion & other) const
inlineconstexpr

Multiply with another quaternion.

Parameters
otherThe other quaternion.

◆ operator*() [2/2]

Quaternion frc::Quaternion::operator* ( double other) const
inlineconstexpr

Multiples with a scalar value.

Parameters
otherthe scalar value

◆ operator+()

Quaternion frc::Quaternion::operator+ ( const Quaternion & other) const
inlineconstexpr

Adds with another quaternion.

Parameters
otherthe other quaternion

◆ operator-()

Quaternion frc::Quaternion::operator- ( const Quaternion & other) const
inlineconstexpr

Subtracts another quaternion.

Parameters
otherthe other quaternion

◆ operator/()

Quaternion frc::Quaternion::operator/ ( double other) const
inlineconstexpr

Divides by a scalar value.

Parameters
otherthe scalar value

◆ operator==()

bool frc::Quaternion::operator== ( const Quaternion & other) const
inlineconstexpr

Checks equality between this Quaternion and another object.

Parameters
otherThe other object.
Returns
Whether the two objects are equal.

◆ Pow()

Quaternion frc::Quaternion::Pow ( double t) const
inlineconstexpr

Calculates this quaternion raised to a power.

Parameters
tthe power to raise this quaternion to.

◆ ToRotationVector()

Eigen::Vector3d frc::Quaternion::ToRotationVector ( ) const
inlineconstexpr

Returns the rotation vector representation of this quaternion.

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

◆ W()

double frc::Quaternion::W ( ) const
inlineconstexpr

Returns W component of the quaternion.

◆ X()

double frc::Quaternion::X ( ) const
inlineconstexpr

Returns X component of the quaternion.

◆ Y()

double frc::Quaternion::Y ( ) const
inlineconstexpr

Returns Y component of the quaternion.

◆ Z()

double frc::Quaternion::Z ( ) const
inlineconstexpr

Returns Z component of the quaternion.


The documentation for this class was generated from the following file: