Represents a quaternion.
More...
#include <wpi/math/geometry/Quaternion.hpp>
|
| 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 |
| | Matrix exponential 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.
|
◆ Quaternion() [1/2]
| wpi::math::Quaternion::Quaternion |
( |
| ) |
|
|
constexprdefault |
Constructs a quaternion with a default angle of 0 degrees.
◆ Quaternion() [2/2]
| wpi::math::Quaternion::Quaternion |
( |
double | w, |
|
|
double | x, |
|
|
double | y, |
|
|
double | z ) |
|
inlineconstexpr |
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. |
◆ Conjugate()
| Quaternion wpi::math::Quaternion::Conjugate |
( |
| ) |
const |
|
inlineconstexpr |
Returns the conjugate of the quaternion.
◆ Dot()
| double wpi::math::Quaternion::Dot |
( |
const Quaternion & | other | ) |
const |
|
inlineconstexpr |
Returns the elementwise product of two quaternions.
◆ Exp()
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
◆ FromRotationVector()
| constexpr Quaternion wpi::math::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 wpi::math::Quaternion::Inverse |
( |
| ) |
const |
|
inlineconstexpr |
Returns the inverse of the quaternion.
◆ Log()
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()
| double wpi::math::Quaternion::Norm |
( |
| ) |
const |
|
inlineconstexpr |
Calculates the L2 norm of the quaternion.
◆ Normalize()
| Quaternion wpi::math::Quaternion::Normalize |
( |
| ) |
const |
|
inlineconstexpr |
Normalizes the quaternion.
◆ operator*() [1/2]
Multiply with another quaternion.
- Parameters
-
| other | The other quaternion. |
◆ operator*() [2/2]
| Quaternion wpi::math::Quaternion::operator* |
( |
double | other | ) |
const |
|
inlineconstexpr |
Multiples with a scalar value.
- Parameters
-
◆ operator+()
Adds with another quaternion.
- Parameters
-
| other | the other quaternion |
◆ operator-()
Subtracts another quaternion.
- Parameters
-
| other | the other quaternion |
◆ operator/()
| Quaternion wpi::math::Quaternion::operator/ |
( |
double | other | ) |
const |
|
inlineconstexpr |
Divides by a scalar value.
- Parameters
-
◆ operator==()
| bool wpi::math::Quaternion::operator== |
( |
const Quaternion & | other | ) |
const |
|
inlineconstexpr |
Checks equality between this Quaternion and another object.
- Parameters
-
- Returns
- Whether the two objects are equal.
◆ Pow()
| Quaternion wpi::math::Quaternion::Pow |
( |
double | t | ) |
const |
|
inlineconstexpr |
Calculates this quaternion raised to a power.
- Parameters
-
| t | the power to raise this quaternion to. |
◆ ToRotationVector()
| Eigen::Vector3d wpi::math::Quaternion::ToRotationVector |
( |
| ) |
const |
|
inlineconstexpr |
Returns the rotation vector representation of this quaternion.
This is also the log operator of SO(3).
◆ W()
| double wpi::math::Quaternion::W |
( |
| ) |
const |
|
inlineconstexpr |
Returns W component of the quaternion.
◆ X()
| double wpi::math::Quaternion::X |
( |
| ) |
const |
|
inlineconstexpr |
Returns X component of the quaternion.
◆ Y()
| double wpi::math::Quaternion::Y |
( |
| ) |
const |
|
inlineconstexpr |
Returns Y component of the quaternion.
◆ Z()
| double wpi::math::Quaternion::Z |
( |
| ) |
const |
|
inlineconstexpr |
Returns Z component of the quaternion.
The documentation for this class was generated from the following file: