Package edu.wpi.first.math.geometry
Class Quaternion
java.lang.Object
edu.wpi.first.math.geometry.Quaternion
- All Implemented Interfaces:
ProtobufSerializable,StructSerializable,WPISerializable
Represents a quaternion.
-
Field Summary
FieldsModifier and TypeFieldDescriptionstatic final QuaternionProtoQuaternion protobuf for serialization.static final QuaternionStructQuaternion struct for serialization. -
Constructor Summary
ConstructorsConstructorDescriptionConstructs a quaternion with a default angle of 0 degrees.Quaternion(double w, double x, double y, double z) Constructs a quaternion with the given components. -
Method Summary
Modifier and TypeMethodDescriptionReturns the conjugate of the quaternion.divide(double scalar) Divides by a scalar.doubledot(Quaternion other) Returns the elementwise product of two quaternions.booleanChecks equality between this Quaternion and another object.exp()Matrix exponential of a quaternion.exp(Quaternion adjustment) Matrix exponential of a quaternion.static QuaternionfromRotationVector(Vector<N3> rvec) Returns the quaternion representation of this rotation vector.doublegetW()Returns W component of the quaternion.doublegetX()Returns X component of the quaternion.doublegetY()Returns Y component of the quaternion.doublegetZ()Returns Z component of the quaternion.inthashCode()inverse()Returns the inverse of the quaternion.log()The Log operator of a general quaternion.log(Quaternion end) Log operator of a quaternion.minus(Quaternion other) Subtracts another quaternion from this quaternion entrywise.doublenorm()Calculates the L2 norm of the quaternion.Normalizes the quaternion.plus(Quaternion other) Adds another quaternion to this quaternion entrywise.pow(double t) Rational power of a quaternion.times(double scalar) Multiplies with a scalar.times(Quaternion other) Multiply with another quaternion.Returns the rotation vector representation of this quaternion.toString()
-
Field Details
-
proto
Quaternion protobuf for serialization. -
struct
Quaternion struct for serialization.
-
-
Constructor Details
-
Quaternion
public Quaternion()Constructs a quaternion with a default angle of 0 degrees. -
Quaternion
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.
-
-
Method Details
-
plus
Adds another quaternion to this quaternion entrywise.- Parameters:
other- The other quaternion.- Returns:
- The quaternion sum.
-
minus
Subtracts another quaternion from this quaternion entrywise.- Parameters:
other- The other quaternion.- Returns:
- The quaternion difference.
-
divide
Divides by a scalar.- Parameters:
scalar- The value to scale each component by.- Returns:
- The scaled quaternion.
-
times
Multiplies with a scalar.- Parameters:
scalar- The value to scale each component by.- Returns:
- The scaled quaternion.
-
times
Multiply with another quaternion.- Parameters:
other- The other quaternion.- Returns:
- The quaternion product.
-
toString
-
equals
Checks equality between this Quaternion and another object. -
hashCode
-
conjugate
Returns the conjugate of the quaternion.- Returns:
- The conjugate quaternion.
-
dot
Returns the elementwise product of two quaternions.- Parameters:
other- The other quaternion.- Returns:
- The dot product of two quaternions.
-
inverse
Returns the inverse of the quaternion.- Returns:
- The inverse quaternion.
-
norm
Calculates the L2 norm of the quaternion.- Returns:
- The L2 norm.
-
normalize
Normalizes the quaternion.- Returns:
- The normalized quaternion.
-
pow
Rational power of a quaternion.- Parameters:
t- the power to raise this quaternion to.- Returns:
- The quaternion power
-
exp
Matrix exponential of a quaternion.- Parameters:
adjustment- the "Twist" that will be applied to this quaternion.- Returns:
- The quaternion product of exp(adjustment) * this
-
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(edu.wpi.first.math.Vector<edu.wpi.first.math.numbers.N3>)- Returns:
- The Matrix exponential of this quaternion.
-
log
Log operator of a quaternion.- Parameters:
end- The quaternion to map this quaternion onto.- Returns:
- The "Twist" that maps this quaternion to the argument.
-
log
The Log operator of a general quaternion.source: wpimath/algorithms.md
If this quaternion is in SO(3) and you are looking for an element of 𝖘𝖔(3), use
toRotationVector()- Returns:
- The logarithm of this quaternion.
-
getW
Returns W component of the quaternion.- Returns:
- W component of the quaternion.
-
getX
Returns X component of the quaternion.- Returns:
- X component of the quaternion.
-
getY
Returns Y component of the quaternion.- Returns:
- Y component of the quaternion.
-
getZ
Returns Z component of the quaternion.- Returns:
- Z component of the quaternion.
-
fromRotationVector
Returns the quaternion representation of this rotation vector.This is also the exp operator of 𝖘𝖔(3).
source: wpimath/algorithms.md
- Parameters:
rvec- The rotation vector.- Returns:
- The quaternion representation of this rotation vector.
-
toRotationVector
Returns the rotation vector representation of this quaternion.This is also the log operator of SO(3).
- Returns:
- The rotation vector representation of this quaternion.
-