001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.math.geometry;
006
007import com.fasterxml.jackson.annotation.JsonAutoDetect;
008import com.fasterxml.jackson.annotation.JsonCreator;
009import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
010import com.fasterxml.jackson.annotation.JsonProperty;
011import edu.wpi.first.math.MatBuilder;
012import edu.wpi.first.math.MathSharedStore;
013import edu.wpi.first.math.MathUtil;
014import edu.wpi.first.math.Matrix;
015import edu.wpi.first.math.Nat;
016import edu.wpi.first.math.VecBuilder;
017import edu.wpi.first.math.Vector;
018import edu.wpi.first.math.interpolation.Interpolatable;
019import edu.wpi.first.math.numbers.N3;
020import java.util.Objects;
021import org.ejml.dense.row.factory.DecompositionFactory_DDRM;
022
023/** A rotation in a 3D coordinate frame represented by a quaternion. */
024@JsonIgnoreProperties(ignoreUnknown = true)
025@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
026public class Rotation3d implements Interpolatable<Rotation3d> {
027  private Quaternion m_q = new Quaternion();
028
029  /** Constructs a Rotation3d with a default angle of 0 degrees. */
030  public Rotation3d() {}
031
032  /**
033   * Constructs a Rotation3d from a quaternion.
034   *
035   * @param q The quaternion.
036   */
037  @JsonCreator
038  public Rotation3d(@JsonProperty(required = true, value = "quaternion") Quaternion q) {
039    m_q = q.normalize();
040  }
041
042  /**
043   * Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
044   *
045   * <p>Extrinsic rotations occur in that order around the axes in the fixed global frame rather
046   * than the body frame.
047   *
048   * <p>Angles are measured counterclockwise with the rotation axis pointing "out of the page". If
049   * you point your right thumb along the positive axis direction, your fingers curl in the
050   * direction of positive rotation.
051   *
052   * @param roll The counterclockwise rotation angle around the X axis (roll) in radians.
053   * @param pitch The counterclockwise rotation angle around the Y axis (pitch) in radians.
054   * @param yaw The counterclockwise rotation angle around the Z axis (yaw) in radians.
055   */
056  public Rotation3d(double roll, double pitch, double yaw) {
057    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Euler_angles_to_quaternion_conversion
058    double cr = Math.cos(roll * 0.5);
059    double sr = Math.sin(roll * 0.5);
060
061    double cp = Math.cos(pitch * 0.5);
062    double sp = Math.sin(pitch * 0.5);
063
064    double cy = Math.cos(yaw * 0.5);
065    double sy = Math.sin(yaw * 0.5);
066
067    m_q =
068        new Quaternion(
069            cr * cp * cy + sr * sp * sy,
070            sr * cp * cy - cr * sp * sy,
071            cr * sp * cy + sr * cp * sy,
072            cr * cp * sy - sr * sp * cy);
073  }
074
075  /**
076   * Constructs a Rotation3d with the given rotation vector representation. This representation is
077   * equivalent to axis-angle, where the normalized axis is multiplied by the rotation around the
078   * axis in radians.
079   *
080   * @param rvec The rotation vector.
081   */
082  public Rotation3d(Vector<N3> rvec) {
083    this(rvec, rvec.norm());
084  }
085
086  /**
087   * Constructs a Rotation3d with the given axis-angle representation. The axis doesn't have to be
088   * normalized.
089   *
090   * @param axis The rotation axis.
091   * @param angleRadians The rotation around the axis in radians.
092   */
093  public Rotation3d(Vector<N3> axis, double angleRadians) {
094    double norm = axis.norm();
095    if (norm == 0.0) {
096      return;
097    }
098
099    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Definition
100    var v = axis.times(1.0 / norm).times(Math.sin(angleRadians / 2.0));
101    m_q = new Quaternion(Math.cos(angleRadians / 2.0), v.get(0, 0), v.get(1, 0), v.get(2, 0));
102  }
103
104  /**
105   * Constructs a Rotation3d from a rotation matrix.
106   *
107   * @param rotationMatrix The rotation matrix.
108   * @throws IllegalArgumentException if the rotation matrix isn't special orthogonal.
109   */
110  public Rotation3d(Matrix<N3, N3> rotationMatrix) {
111    final var R = rotationMatrix;
112
113    // Require that the rotation matrix is special orthogonal. This is true if
114    // the matrix is orthogonal (RRᵀ = I) and normalized (determinant is 1).
115    if (R.times(R.transpose()).minus(Matrix.eye(Nat.N3())).normF() > 1e-9) {
116      var builder = new StringBuilder("Rotation matrix isn't orthogonal\n\nR =\n");
117      builder.append(R.getStorage().toString()).append('\n');
118
119      var msg = builder.toString();
120      MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
121      throw new IllegalArgumentException(msg);
122    }
123    if (Math.abs(R.det() - 1.0) > 1e-9) {
124      var builder =
125          new StringBuilder("Rotation matrix is orthogonal but not special orthogonal\n\nR =\n");
126      builder.append(R.getStorage().toString()).append('\n');
127
128      var msg = builder.toString();
129      MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
130      throw new IllegalArgumentException(msg);
131    }
132
133    // Turn rotation matrix into a quaternion
134    // https://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/
135    double trace = R.get(0, 0) + R.get(1, 1) + R.get(2, 2);
136    double w;
137    double x;
138    double y;
139    double z;
140
141    if (trace > 0.0) {
142      double s = 0.5 / Math.sqrt(trace + 1.0);
143      w = 0.25 / s;
144      x = (R.get(2, 1) - R.get(1, 2)) * s;
145      y = (R.get(0, 2) - R.get(2, 0)) * s;
146      z = (R.get(1, 0) - R.get(0, 1)) * s;
147    } else {
148      if (R.get(0, 0) > R.get(1, 1) && R.get(0, 0) > R.get(2, 2)) {
149        double s = 2.0 * Math.sqrt(1.0 + R.get(0, 0) - R.get(1, 1) - R.get(2, 2));
150        w = (R.get(2, 1) - R.get(1, 2)) / s;
151        x = 0.25 * s;
152        y = (R.get(0, 1) + R.get(1, 0)) / s;
153        z = (R.get(0, 2) + R.get(2, 0)) / s;
154      } else if (R.get(1, 1) > R.get(2, 2)) {
155        double s = 2.0 * Math.sqrt(1.0 + R.get(1, 1) - R.get(0, 0) - R.get(2, 2));
156        w = (R.get(0, 2) - R.get(2, 0)) / s;
157        x = (R.get(0, 1) + R.get(1, 0)) / s;
158        y = 0.25 * s;
159        z = (R.get(1, 2) + R.get(2, 1)) / s;
160      } else {
161        double s = 2.0 * Math.sqrt(1.0 + R.get(2, 2) - R.get(0, 0) - R.get(1, 1));
162        w = (R.get(1, 0) - R.get(0, 1)) / s;
163        x = (R.get(0, 2) + R.get(2, 0)) / s;
164        y = (R.get(1, 2) + R.get(2, 1)) / s;
165        z = 0.25 * s;
166      }
167    }
168
169    m_q = new Quaternion(w, x, y, z);
170  }
171
172  /**
173   * Constructs a Rotation3d that rotates the initial vector onto the final vector.
174   *
175   * <p>This is useful for turning a 3D vector (final) into an orientation relative to a coordinate
176   * system vector (initial).
177   *
178   * @param initial The initial vector.
179   * @param last The final vector.
180   */
181  public Rotation3d(Vector<N3> initial, Vector<N3> last) {
182    double dot = initial.dot(last);
183    double normProduct = initial.norm() * last.norm();
184    double dotNorm = dot / normProduct;
185
186    if (dotNorm > 1.0 - 1E-9) {
187      // If the dot product is 1, the two vectors point in the same direction so
188      // there's no rotation. The default initialization of m_q will work.
189      return;
190    } else if (dotNorm < -1.0 + 1E-9) {
191      // If the dot product is -1, the two vectors point in opposite directions
192      // so a 180 degree rotation is required. Any orthogonal vector can be used
193      // for it. Q in the QR decomposition is an orthonormal basis, so it
194      // contains orthogonal unit vectors.
195      var X =
196          new MatBuilder<>(Nat.N3(), Nat.N1())
197              .fill(initial.get(0, 0), initial.get(1, 0), initial.get(2, 0));
198      final var qr = DecompositionFactory_DDRM.qr(3, 1);
199      qr.decompose(X.getStorage().getMatrix());
200      final var Q = qr.getQ(null, false);
201
202      // w = cos(θ/2) = cos(90°) = 0
203      //
204      // For x, y, and z, we use the second column of Q because the first is
205      // parallel instead of orthogonal. The third column would also work.
206      m_q = new Quaternion(0.0, Q.get(0, 1), Q.get(1, 1), Q.get(2, 1));
207    } else {
208      // initial x last
209      var axis =
210          VecBuilder.fill(
211              initial.get(1, 0) * last.get(2, 0) - last.get(1, 0) * initial.get(2, 0),
212              last.get(0, 0) * initial.get(2, 0) - initial.get(0, 0) * last.get(2, 0),
213              initial.get(0, 0) * last.get(1, 0) - last.get(0, 0) * initial.get(1, 0));
214
215      // https://stackoverflow.com/a/11741520
216      m_q =
217          new Quaternion(normProduct + dot, axis.get(0, 0), axis.get(1, 0), axis.get(2, 0))
218              .normalize();
219    }
220  }
221
222  /**
223   * Adds two rotations together.
224   *
225   * @param other The rotation to add.
226   * @return The sum of the two rotations.
227   */
228  public Rotation3d plus(Rotation3d other) {
229    return rotateBy(other);
230  }
231
232  /**
233   * Subtracts the new rotation from the current rotation and returns the new rotation.
234   *
235   * @param other The rotation to subtract.
236   * @return The difference between the two rotations.
237   */
238  public Rotation3d minus(Rotation3d other) {
239    return rotateBy(other.unaryMinus());
240  }
241
242  /**
243   * Takes the inverse of the current rotation.
244   *
245   * @return The inverse of the current rotation.
246   */
247  public Rotation3d unaryMinus() {
248    return new Rotation3d(m_q.inverse());
249  }
250
251  /**
252   * Multiplies the current rotation by a scalar.
253   *
254   * @param scalar The scalar.
255   * @return The new scaled Rotation3d.
256   */
257  public Rotation3d times(double scalar) {
258    // https://en.wikipedia.org/wiki/Slerp#Quaternion_Slerp
259    if (m_q.getW() >= 0.0) {
260      return new Rotation3d(
261          VecBuilder.fill(m_q.getX(), m_q.getY(), m_q.getZ()),
262          2.0 * scalar * Math.acos(m_q.getW()));
263    } else {
264      return new Rotation3d(
265          VecBuilder.fill(-m_q.getX(), -m_q.getY(), -m_q.getZ()),
266          2.0 * scalar * Math.acos(-m_q.getW()));
267    }
268  }
269
270  /**
271   * Divides the current rotation by a scalar.
272   *
273   * @param scalar The scalar.
274   * @return The new scaled Rotation3d.
275   */
276  public Rotation3d div(double scalar) {
277    return times(1.0 / scalar);
278  }
279
280  /**
281   * Adds the new rotation to the current rotation.
282   *
283   * @param other The rotation to rotate by.
284   * @return The new rotated Rotation3d.
285   */
286  public Rotation3d rotateBy(Rotation3d other) {
287    return new Rotation3d(other.m_q.times(m_q));
288  }
289
290  /**
291   * Returns the quaternion representation of the Rotation3d.
292   *
293   * @return The quaternion representation of the Rotation3d.
294   */
295  @JsonProperty(value = "quaternion")
296  public Quaternion getQuaternion() {
297    return m_q;
298  }
299
300  /**
301   * Returns the counterclockwise rotation angle around the X axis (roll) in radians.
302   *
303   * @return The counterclockwise rotation angle around the X axis (roll) in radians.
304   */
305  public double getX() {
306    final var w = m_q.getW();
307    final var x = m_q.getX();
308    final var y = m_q.getY();
309    final var z = m_q.getZ();
310
311    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_(in_3-2-1_sequence)_conversion
312    return Math.atan2(2.0 * (w * x + y * z), 1.0 - 2.0 * (x * x + y * y));
313  }
314
315  /**
316   * Returns the counterclockwise rotation angle around the Y axis (pitch) in radians.
317   *
318   * @return The counterclockwise rotation angle around the Y axis (pitch) in radians.
319   */
320  public double getY() {
321    final var w = m_q.getW();
322    final var x = m_q.getX();
323    final var y = m_q.getY();
324    final var z = m_q.getZ();
325
326    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_(in_3-2-1_sequence)_conversion
327    double ratio = 2.0 * (w * y - z * x);
328    if (Math.abs(ratio) >= 1.0) {
329      return Math.copySign(Math.PI / 2.0, ratio);
330    } else {
331      return Math.asin(ratio);
332    }
333  }
334
335  /**
336   * Returns the counterclockwise rotation angle around the Z axis (yaw) in radians.
337   *
338   * @return The counterclockwise rotation angle around the Z axis (yaw) in radians.
339   */
340  public double getZ() {
341    final var w = m_q.getW();
342    final var x = m_q.getX();
343    final var y = m_q.getY();
344    final var z = m_q.getZ();
345
346    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_(in_3-2-1_sequence)_conversion
347    return Math.atan2(2.0 * (w * z + x * y), 1.0 - 2.0 * (y * y + z * z));
348  }
349
350  /**
351   * Returns the axis in the axis-angle representation of this rotation.
352   *
353   * @return The axis in the axis-angle representation.
354   */
355  public Vector<N3> getAxis() {
356    double norm =
357        Math.sqrt(m_q.getX() * m_q.getX() + m_q.getY() * m_q.getY() + m_q.getZ() * m_q.getZ());
358    if (norm == 0.0) {
359      return VecBuilder.fill(0.0, 0.0, 0.0);
360    } else {
361      return VecBuilder.fill(m_q.getX() / norm, m_q.getY() / norm, m_q.getZ() / norm);
362    }
363  }
364
365  /**
366   * Returns the angle in radians in the axis-angle representation of this rotation.
367   *
368   * @return The angle in radians in the axis-angle representation of this rotation.
369   */
370  public double getAngle() {
371    double norm =
372        Math.sqrt(m_q.getX() * m_q.getX() + m_q.getY() * m_q.getY() + m_q.getZ() * m_q.getZ());
373    return 2.0 * Math.atan2(norm, m_q.getW());
374  }
375
376  /**
377   * Returns a Rotation2d representing this Rotation3d projected into the X-Y plane.
378   *
379   * @return A Rotation2d representing this Rotation3d projected into the X-Y plane.
380   */
381  public Rotation2d toRotation2d() {
382    return new Rotation2d(getZ());
383  }
384
385  @Override
386  public String toString() {
387    return String.format("Rotation3d(%s)", m_q);
388  }
389
390  /**
391   * Checks equality between this Rotation3d and another object.
392   *
393   * @param obj The other object.
394   * @return Whether the two objects are equal or not.
395   */
396  @Override
397  public boolean equals(Object obj) {
398    if (obj instanceof Rotation3d) {
399      var other = (Rotation3d) obj;
400      return m_q.equals(other.m_q);
401    }
402    return false;
403  }
404
405  @Override
406  public int hashCode() {
407    return Objects.hash(m_q);
408  }
409
410  @Override
411  public Rotation3d interpolate(Rotation3d endValue, double t) {
412    return plus(endValue.minus(this).times(MathUtil.clamp(t, 0, 1)));
413  }
414}