public class Quaternion
extends java.lang.Object
Constructor and Description |
---|
Quaternion(double x,
double y,
double z,
double w) |
Modifier and Type | Method and Description |
---|---|
boolean |
almostEquals(Quaternion other,
double epsilon) |
Quaternion |
conjugate() |
boolean |
equals(java.lang.Object obj) |
static Quaternion |
fromAxisAngle(Vector3 axis,
double angle) |
static Quaternion |
fromQuaternionMessage(geometry_msgs.Quaternion message) |
double |
getMagnitude() |
double |
getMagnitudeSquared() |
double |
getW() |
double |
getX() |
double |
getY() |
double |
getZ() |
int |
hashCode() |
static Quaternion |
identity() |
Quaternion |
invert() |
boolean |
isAlmostNeutral(double epsilon) |
Quaternion |
multiply(Quaternion other) |
Quaternion |
normalize() |
Vector3 |
rotateAndScaleVector(Vector3 vector) |
static Quaternion |
rotationBetweenVectors(Vector3 vector1,
Vector3 vector2) |
Quaternion |
scale(double factor) |
geometry_msgs.Quaternion |
toQuaternionMessage(geometry_msgs.Quaternion result) |
java.lang.String |
toString() |
public static Quaternion fromAxisAngle(Vector3 axis, double angle)
public static Quaternion fromQuaternionMessage(geometry_msgs.Quaternion message)
public static Quaternion rotationBetweenVectors(Vector3 vector1, Vector3 vector2)
public static Quaternion identity()
public Quaternion scale(double factor)
public Quaternion conjugate()
public Quaternion invert()
public Quaternion normalize()
public Quaternion multiply(Quaternion other)
public double getX()
public double getY()
public double getZ()
public double getW()
public double getMagnitudeSquared()
public double getMagnitude()
public boolean isAlmostNeutral(double epsilon)
public geometry_msgs.Quaternion toQuaternionMessage(geometry_msgs.Quaternion result)
public boolean almostEquals(Quaternion other, double epsilon)
public java.lang.String toString()
toString
in class java.lang.Object
public int hashCode()
hashCode
in class java.lang.Object
public boolean equals(java.lang.Object obj)
equals
in class java.lang.Object