WPILibC++ 2025.2.1
|
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. | |
Represents a quaternion.
|
constexprdefault |
Constructs a quaternion with a default angle of 0 degrees.
|
inlineconstexpr |
Constructs a quaternion with the given components.
w | W component of the quaternion. |
x | X component of the quaternion. |
y | Y component of the quaternion. |
z | Z component of the quaternion. |
|
inlineconstexpr |
Returns the conjugate of the quaternion.
|
inlineconstexpr |
Returns the elementwise product of two quaternions.
|
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
|
inlineconstexpr |
Matrix exponential of a quaternion.
other | the "Twist" that will be applied to this quaternion. |
|
inlinestaticconstexpr |
Returns the quaternion representation of this rotation vector.
This is also the exp operator of 𝖘𝖔(3).
source: wpimath/algorithms.md
|
inlineconstexpr |
Returns the inverse of the quaternion.
|
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
|
inlineconstexpr |
Log operator of a quaternion.
other | The quaternion to map this quaternion onto |
|
inlineconstexpr |
Calculates the L2 norm of the quaternion.
|
inlineconstexpr |
Normalizes the quaternion.
|
inlineconstexpr |
Multiply with another quaternion.
other | The other quaternion. |
|
inlineconstexpr |
Multiples with a scalar value.
other | the scalar value |
|
inlineconstexpr |
Adds with another quaternion.
other | the other quaternion |
|
inlineconstexpr |
Subtracts another quaternion.
other | the other quaternion |
|
inlineconstexpr |
Divides by a scalar value.
other | the scalar value |
|
inlineconstexpr |
Checks equality between this Quaternion and another object.
other | The other object. |
|
inlineconstexpr |
Calculates this quaternion raised to a power.
t | the power to raise this quaternion to. |
|
inlineconstexpr |
Returns the rotation vector representation of this quaternion.
This is also the log operator of SO(3).
|
inlineconstexpr |
Returns W component of the quaternion.
|
inlineconstexpr |
Returns X component of the quaternion.
|
inlineconstexpr |
Returns Y component of the quaternion.
|
inlineconstexpr |
Returns Z component of the quaternion.