WPILibC++ 2024.3.2
|
Represents a quaternion. More...
#include <frc/geometry/Quaternion.h>
Public Member Functions | |
Quaternion ()=default | |
Constructs a quaternion with a default angle of 0 degrees. More... | |
Quaternion (double w, double x, double y, double z) | |
Constructs a quaternion with the given components. More... | |
Quaternion | operator+ (const Quaternion &other) const |
Adds with another quaternion. More... | |
Quaternion | operator- (const Quaternion &other) const |
Subtracts another quaternion. More... | |
Quaternion | operator* (const double other) const |
Multiples with a scalar value. More... | |
Quaternion | operator/ (const double other) const |
Divides by a scalar value. More... | |
Quaternion | operator* (const Quaternion &other) const |
Multiply with another quaternion. More... | |
bool | operator== (const Quaternion &other) const |
Checks equality between this Quaternion and another object. More... | |
double | Dot (const Quaternion &other) const |
Returns the elementwise product of two quaternions. More... | |
Quaternion | Conjugate () const |
Returns the conjugate of the quaternion. More... | |
Quaternion | Inverse () const |
Returns the inverse of the quaternion. More... | |
Quaternion | Normalize () const |
Normalizes the quaternion. More... | |
double | Norm () const |
Calculates the L2 norm of the quaternion. More... | |
Quaternion | Pow (const double t) const |
Calculates this quaternion raised to a power. More... | |
Quaternion | Exp (const Quaternion &other) const |
Matrix exponential of a quaternion. More... | |
Quaternion | Exp () const |
Matrix exponential of a quaternion. More... | |
Quaternion | Log (const Quaternion &other) const |
Log operator of a quaternion. More... | |
Quaternion | Log () const |
Log operator of a quaternion. More... | |
double | W () const |
Returns W component of the quaternion. More... | |
double | X () const |
Returns X component of the quaternion. More... | |
double | Y () const |
Returns Y component of the quaternion. More... | |
double | Z () const |
Returns Z component of the quaternion. More... | |
Eigen::Vector3d | ToRotationVector () const |
Returns the rotation vector representation of this quaternion. More... | |
Static Public Member Functions | |
static Quaternion | FromRotationVector (const Eigen::Vector3d &rvec) |
Returns the quaternion representation of this rotation vector. More... | |
Represents a quaternion.
|
default |
Constructs a quaternion with a default angle of 0 degrees.
frc::Quaternion::Quaternion | ( | double | w, |
double | x, | ||
double | y, | ||
double | z | ||
) |
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. |
Quaternion frc::Quaternion::Conjugate | ( | ) | const |
Returns the conjugate of the quaternion.
double frc::Quaternion::Dot | ( | const Quaternion & | other | ) | const |
Returns the elementwise product of two quaternions.
Quaternion frc::Quaternion::Exp | ( | ) | const |
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
Quaternion frc::Quaternion::Exp | ( | const Quaternion & | other | ) | const |
Matrix exponential of a quaternion.
other | the "Twist" that will be applied to this quaternion. |
|
static |
Returns the quaternion representation of this rotation vector.
This is also the exp operator of 𝖘𝖔(3).
source: wpimath/algorithms.md
Quaternion frc::Quaternion::Inverse | ( | ) | const |
Returns the inverse of the quaternion.
Quaternion frc::Quaternion::Log | ( | ) | const |
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
Quaternion frc::Quaternion::Log | ( | const Quaternion & | other | ) | const |
Log operator of a quaternion.
other | The quaternion to map this quaternion onto |
double frc::Quaternion::Norm | ( | ) | const |
Calculates the L2 norm of the quaternion.
Quaternion frc::Quaternion::Normalize | ( | ) | const |
Normalizes the quaternion.
Quaternion frc::Quaternion::operator* | ( | const double | other | ) | const |
Multiples with a scalar value.
other | the scalar value |
Quaternion frc::Quaternion::operator* | ( | const Quaternion & | other | ) | const |
Multiply with another quaternion.
other | The other quaternion. |
Quaternion frc::Quaternion::operator+ | ( | const Quaternion & | other | ) | const |
Adds with another quaternion.
other | the other quaternion |
Quaternion frc::Quaternion::operator- | ( | const Quaternion & | other | ) | const |
Subtracts another quaternion.
other | the other quaternion |
Quaternion frc::Quaternion::operator/ | ( | const double | other | ) | const |
Divides by a scalar value.
other | the scalar value |
bool frc::Quaternion::operator== | ( | const Quaternion & | other | ) | const |
Checks equality between this Quaternion and another object.
other | The other object. |
Quaternion frc::Quaternion::Pow | ( | const double | t | ) | const |
Calculates this quaternion raised to a power.
t | the power to raise this quaternion to. |
Eigen::Vector3d frc::Quaternion::ToRotationVector | ( | ) | const |
Returns the rotation vector representation of this quaternion.
This is also the log operator of SO(3).
double frc::Quaternion::W | ( | ) | const |
Returns W component of the quaternion.
double frc::Quaternion::X | ( | ) | const |
Returns X component of the quaternion.
double frc::Quaternion::Y | ( | ) | const |
Returns Y component of the quaternion.
double frc::Quaternion::Z | ( | ) | const |
Returns Z component of the quaternion.