Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 package org.ros.rosjava_geometry;
00018
00019 import com.google.common.base.Preconditions;
00020 import com.google.common.collect.Lists;
00021
00022 import java.util.List;
00023
00030 public class Quaternion {
00031
00032 private final double x;
00033 private final double y;
00034 private final double z;
00035 private final double w;
00036
00037 public static Quaternion fromAxisAngle(Vector3 axis, double angle) {
00038 Vector3 normalized = axis.normalize();
00039 double sin = Math.sin(angle / 2.0d);
00040 double cos = Math.cos(angle / 2.0d);
00041 return new Quaternion(normalized.getX() * sin, normalized.getY() * sin,
00042 normalized.getZ() * sin, cos);
00043 }
00044
00045 public static Quaternion fromQuaternionMessage(geometry_msgs.Quaternion message) {
00046 return new Quaternion(message.getX(), message.getY(), message.getZ(), message.getW());
00047 }
00048
00049 public static Quaternion rotationBetweenVectors(Vector3 vector1, Vector3 vector2) {
00050 Preconditions.checkArgument(vector1.getMagnitude() > 0,
00051 "Cannot calculate rotation between zero-length vectors.");
00052 Preconditions.checkArgument(vector2.getMagnitude() > 0,
00053 "Cannot calculate rotation between zero-length vectors.");
00054 if (vector1.normalize().equals(vector2.normalize())) {
00055 return identity();
00056 }
00057 double angle =
00058 Math.acos(vector1.dotProduct(vector2) / (vector1.getMagnitude() * vector2.getMagnitude()));
00059 double axisX = vector1.getY() * vector2.getZ() - vector1.getZ() * vector2.getY();
00060 double axisY = vector1.getZ() * vector2.getX() - vector1.getX() * vector2.getZ();
00061 double axisZ = vector1.getX() * vector2.getY() - vector1.getY() * vector2.getX();
00062 return fromAxisAngle(new Vector3(axisX, axisY, axisZ), angle);
00063 }
00064
00065 public static Quaternion identity() {
00066 return new Quaternion(0, 0, 0, 1);
00067 }
00068
00069 public Quaternion(double x, double y, double z, double w) {
00070 this.x = x;
00071 this.y = y;
00072 this.z = z;
00073 this.w = w;
00074 }
00075
00076 public Quaternion scale(double factor) {
00077 return new Quaternion(x * factor, y * factor, z * factor, w * factor);
00078 }
00079
00080 public Quaternion conjugate() {
00081 return new Quaternion(-x, -y, -z, w);
00082 }
00083
00084 public Quaternion invert() {
00085 double mm = getMagnitudeSquared();
00086 Preconditions.checkState(mm != 0);
00087 return conjugate().scale(1 / mm);
00088 }
00089
00090 public Quaternion normalize() {
00091 return scale(1 / getMagnitude());
00092 }
00093
00094 public Quaternion multiply(Quaternion other) {
00095 return new Quaternion(w * other.x + x * other.w + y * other.z - z * other.y, w * other.y + y
00096 * other.w + z * other.x - x * other.z, w * other.z + z * other.w + x * other.y - y
00097 * other.x, w * other.w - x * other.x - y * other.y - z * other.z);
00098 }
00099
00100 public Vector3 rotateAndScaleVector(Vector3 vector) {
00101 Quaternion vectorQuaternion = new Quaternion(vector.getX(), vector.getY(), vector.getZ(), 0);
00102 Quaternion rotatedQuaternion = multiply(vectorQuaternion.multiply(conjugate()));
00103 return new Vector3(rotatedQuaternion.getX(), rotatedQuaternion.getY(), rotatedQuaternion.getZ());
00104 }
00105
00106 public double getX() {
00107 return x;
00108 }
00109
00110 public double getY() {
00111 return y;
00112 }
00113
00114 public double getZ() {
00115 return z;
00116 }
00117
00118 public double getW() {
00119 return w;
00120 }
00121
00122 public double getMagnitudeSquared() {
00123 return x * x + y * y + z * z + w * w;
00124 }
00125
00126 public double getMagnitude() {
00127 return Math.sqrt(getMagnitudeSquared());
00128 }
00129
00130 public boolean isAlmostNeutral(double epsilon) {
00131 return Math.abs(1 - x * x - y * y - z * z - w * w) < epsilon;
00132 }
00133
00134 public geometry_msgs.Quaternion toQuaternionMessage(geometry_msgs.Quaternion result) {
00135 result.setX(x);
00136 result.setY(y);
00137 result.setZ(z);
00138 result.setW(w);
00139 return result;
00140 }
00141
00142 public boolean almostEquals(Quaternion other, double epsilon) {
00143 List<Double> epsilons = Lists.newArrayList();
00144 epsilons.add(x - other.x);
00145 epsilons.add(y - other.y);
00146 epsilons.add(z - other.z);
00147 epsilons.add(w - other.w);
00148 for (double e : epsilons) {
00149 if (Math.abs(e) > epsilon) {
00150 return false;
00151 }
00152 }
00153 return true;
00154 }
00155
00156 @Override
00157 public String toString() {
00158 return String.format("Quaternion<x: %.4f, y: %.4f, z: %.4f, w: %.4f>", x, y, z, w);
00159 }
00160
00161 @Override
00162 public int hashCode() {
00163
00164 double w = this.w == 0 ? 0 : this.w;
00165 double x = this.x == 0 ? 0 : this.x;
00166 double y = this.y == 0 ? 0 : this.y;
00167 double z = this.z == 0 ? 0 : this.z;
00168 final int prime = 31;
00169 int result = 1;
00170 long temp;
00171 temp = Double.doubleToLongBits(w);
00172 result = prime * result + (int) (temp ^ (temp >>> 32));
00173 temp = Double.doubleToLongBits(x);
00174 result = prime * result + (int) (temp ^ (temp >>> 32));
00175 temp = Double.doubleToLongBits(y);
00176 result = prime * result + (int) (temp ^ (temp >>> 32));
00177 temp = Double.doubleToLongBits(z);
00178 result = prime * result + (int) (temp ^ (temp >>> 32));
00179 return result;
00180 }
00181
00182 @Override
00183 public boolean equals(Object obj) {
00184 if (this == obj)
00185 return true;
00186 if (obj == null)
00187 return false;
00188 if (getClass() != obj.getClass())
00189 return false;
00190 Quaternion other = (Quaternion) obj;
00191
00192 double w = this.w == 0 ? 0 : this.w;
00193 double x = this.x == 0 ? 0 : this.x;
00194 double y = this.y == 0 ? 0 : this.y;
00195 double z = this.z == 0 ? 0 : this.z;
00196 double otherW = other.w == 0 ? 0 : other.w;
00197 double otherX = other.x == 0 ? 0 : other.x;
00198 double otherY = other.y == 0 ? 0 : other.y;
00199 double otherZ = other.z == 0 ? 0 : other.z;
00200 if (Double.doubleToLongBits(w) != Double.doubleToLongBits(otherW))
00201 return false;
00202 if (Double.doubleToLongBits(x) != Double.doubleToLongBits(otherX))
00203 return false;
00204 if (Double.doubleToLongBits(y) != Double.doubleToLongBits(otherY))
00205 return false;
00206 if (Double.doubleToLongBits(z) != Double.doubleToLongBits(otherZ))
00207 return false;
00208 return true;
00209 }
00210 }