org.ros.rosjava_geometry
Class Quaternion
java.lang.Object
org.ros.rosjava_geometry.Quaternion
public class Quaternion
- extends java.lang.Object
A quaternion.
Constructor Summary |
Quaternion(double x,
double y,
double z,
double w)
|
Methods inherited from class java.lang.Object |
clone, finalize, getClass, notify, notifyAll, wait, wait, wait |
Quaternion
public Quaternion(double x,
double y,
double z,
double w)
newFromAxisAngle
public static Quaternion newFromAxisAngle(Vector3 axis,
double angle)
newFromQuaternionMessage
public static Quaternion newFromQuaternionMessage(geometry_msgs.Quaternion message)
rotationBetweenVectors
public static Quaternion rotationBetweenVectors(Vector3 vector1,
Vector3 vector2)
newIdentityQuaternion
public static Quaternion newIdentityQuaternion()
getAngle
public double getAngle()
getAxis
public Vector3 getAxis()
invert
public Quaternion invert()
multiply
public Quaternion multiply(Quaternion other)
rotateVector
public Vector3 rotateVector(Vector3 vector)
toQuaternionMessage
public geometry_msgs.Quaternion toQuaternionMessage(geometry_msgs.Quaternion result)
getX
public double getX()
setX
public void setX(double x)
getY
public double getY()
setY
public void setY(double y)
getZ
public double getZ()
setZ
public void setZ(double z)
getW
public double getW()
setW
public void setW(double w)
hashCode
public int hashCode()
- Overrides:
hashCode
in class java.lang.Object
equals
public boolean equals(java.lang.Object obj)
- Overrides:
equals
in class java.lang.Object
toString
public java.lang.String toString()
- Overrides:
toString
in class java.lang.Object