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 static edu.wpi.first.units.Units.Radians;
008
009import com.fasterxml.jackson.annotation.JsonAutoDetect;
010import com.fasterxml.jackson.annotation.JsonCreator;
011import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
012import com.fasterxml.jackson.annotation.JsonProperty;
013import edu.wpi.first.math.MatBuilder;
014import edu.wpi.first.math.MathSharedStore;
015import edu.wpi.first.math.MathUtil;
016import edu.wpi.first.math.Matrix;
017import edu.wpi.first.math.Nat;
018import edu.wpi.first.math.VecBuilder;
019import edu.wpi.first.math.Vector;
020import edu.wpi.first.math.geometry.proto.Rotation3dProto;
021import edu.wpi.first.math.geometry.struct.Rotation3dStruct;
022import edu.wpi.first.math.interpolation.Interpolatable;
023import edu.wpi.first.math.numbers.N3;
024import edu.wpi.first.units.measure.Angle;
025import edu.wpi.first.util.protobuf.ProtobufSerializable;
026import edu.wpi.first.util.struct.StructSerializable;
027import java.util.Objects;
028
029/**
030 * A rotation in a 3D coordinate frame, represented by a quaternion. Note that unlike 2D rotations,
031 * 3D rotations are not always commutative, so changing the order of rotations changes the result.
032 *
033 * <p>As an example of the order of rotations mattering, suppose we have a card that looks like
034 * this:
035 *
036 * <pre>
037 *          ┌───┐        ┌───┐
038 *          │ X │        │ x │
039 *   Front: │ | │  Back: │ · │
040 *          │ | │        │ · │
041 *          └───┘        └───┘
042 * </pre>
043 *
044 * <p>If we rotate 90º clockwise around the axis into the page, then flip around the left/right
045 * axis, we get one result:
046 *
047 * <pre>
048 *   ┌───┐
049 *   │ X │   ┌───────┐   ┌───────┐
050 *   │ | │ → │------X│ → │······x│
051 *   │ | │   └───────┘   └───────┘
052 *   └───┘
053 * </pre>
054 *
055 * <p>If we flip around the left/right axis, then rotate 90º clockwise around the axis into the
056 * page, we get a different result:
057 *
058 * <pre>
059 *   ┌───┐   ┌───┐
060 *   │ X │   │ · │   ┌───────┐
061 *   │ | │ → │ · │ → │x······│
062 *   │ | │   │ x │   └───────┘
063 *   └───┘   └───┘
064 * </pre>
065 *
066 * <p>Because order matters for 3D rotations, we need to distinguish between <em>extrinsic</em>
067 * rotations and <em>intrinsic</em> rotations. Rotating extrinsically means rotating around the
068 * global axes, while rotating intrinsically means rotating from the perspective of the other
069 * rotation. A neat property is that applying a series of rotations extrinsically is the same as
070 * applying the same series in the opposite order intrinsically.
071 */
072@JsonIgnoreProperties(ignoreUnknown = true)
073@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
074public class Rotation3d
075    implements Interpolatable<Rotation3d>, ProtobufSerializable, StructSerializable {
076  /**
077   * A preallocated Rotation3d representing no rotation.
078   *
079   * <p>This exists to avoid allocations for common rotations.
080   */
081  public static final Rotation3d kZero = new Rotation3d();
082
083  private final Quaternion m_q;
084
085  /** Constructs a Rotation3d representing no rotation. */
086  public Rotation3d() {
087    m_q = new Quaternion();
088  }
089
090  /**
091   * Constructs a Rotation3d from a quaternion.
092   *
093   * @param q The quaternion.
094   */
095  @JsonCreator
096  public Rotation3d(@JsonProperty(required = true, value = "quaternion") Quaternion q) {
097    m_q = q.normalize();
098  }
099
100  /**
101   * Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
102   *
103   * <p>Extrinsic rotations occur in that order around the axes in the fixed global frame rather
104   * than the body frame.
105   *
106   * <p>Angles are measured counterclockwise with the rotation axis pointing "out of the page". If
107   * you point your right thumb along the positive axis direction, your fingers curl in the
108   * direction of positive rotation.
109   *
110   * @param roll The counterclockwise rotation angle around the X axis (roll) in radians.
111   * @param pitch The counterclockwise rotation angle around the Y axis (pitch) in radians.
112   * @param yaw The counterclockwise rotation angle around the Z axis (yaw) in radians.
113   */
114  public Rotation3d(double roll, double pitch, double yaw) {
115    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Euler_angles_to_quaternion_conversion
116    double cr = Math.cos(roll * 0.5);
117    double sr = Math.sin(roll * 0.5);
118
119    double cp = Math.cos(pitch * 0.5);
120    double sp = Math.sin(pitch * 0.5);
121
122    double cy = Math.cos(yaw * 0.5);
123    double sy = Math.sin(yaw * 0.5);
124
125    m_q =
126        new Quaternion(
127            cr * cp * cy + sr * sp * sy,
128            sr * cp * cy - cr * sp * sy,
129            cr * sp * cy + sr * cp * sy,
130            cr * cp * sy - sr * sp * cy);
131  }
132
133  /**
134   * Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
135   *
136   * <p>Extrinsic rotations occur in that order around the axes in the fixed global frame rather
137   * than the body frame.
138   *
139   * <p>Angles are measured counterclockwise with the rotation axis pointing "out of the page". If
140   * you point your right thumb along the positive axis direction, your fingers curl in the
141   * direction of positive rotation.
142   *
143   * @param roll The counterclockwise rotation angle around the X axis (roll).
144   * @param pitch The counterclockwise rotation angle around the Y axis (pitch).
145   * @param yaw The counterclockwise rotation angle around the Z axis (yaw).
146   */
147  public Rotation3d(Angle roll, Angle pitch, Angle yaw) {
148    this(roll.in(Radians), pitch.in(Radians), yaw.in(Radians));
149  }
150
151  /**
152   * Constructs a Rotation3d with the given rotation vector representation. This representation is
153   * equivalent to axis-angle, where the normalized axis is multiplied by the rotation around the
154   * axis in radians.
155   *
156   * @param rvec The rotation vector.
157   */
158  public Rotation3d(Vector<N3> rvec) {
159    this(rvec, rvec.norm());
160  }
161
162  /**
163   * Constructs a Rotation3d with the given axis-angle representation. The axis doesn't have to be
164   * normalized.
165   *
166   * @param axis The rotation axis.
167   * @param angleRadians The rotation around the axis in radians.
168   */
169  public Rotation3d(Vector<N3> axis, double angleRadians) {
170    double norm = axis.norm();
171    if (norm == 0.0) {
172      m_q = new Quaternion();
173      return;
174    }
175
176    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Definition
177    var v = axis.times(1.0 / norm).times(Math.sin(angleRadians / 2.0));
178    m_q = new Quaternion(Math.cos(angleRadians / 2.0), v.get(0, 0), v.get(1, 0), v.get(2, 0));
179  }
180
181  /**
182   * Constructs a Rotation3d with the given axis-angle representation. The axis doesn't have to be
183   * normalized.
184   *
185   * @param axis The rotation axis.
186   * @param angle The rotation around the axis.
187   */
188  public Rotation3d(Vector<N3> axis, Angle angle) {
189    this(axis, angle.in(Radians));
190  }
191
192  /**
193   * Constructs a Rotation3d from a rotation matrix.
194   *
195   * @param rotationMatrix The rotation matrix.
196   * @throws IllegalArgumentException if the rotation matrix isn't special orthogonal.
197   */
198  public Rotation3d(Matrix<N3, N3> rotationMatrix) {
199    final var R = rotationMatrix;
200
201    // Require that the rotation matrix is special orthogonal. This is true if
202    // the matrix is orthogonal (RRᵀ = I) and normalized (determinant is 1).
203    if (R.times(R.transpose()).minus(Matrix.eye(Nat.N3())).normF() > 1e-9) {
204      var msg = "Rotation matrix isn't orthogonal\n\nR =\n" + R.getStorage().toString() + '\n';
205      MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
206      throw new IllegalArgumentException(msg);
207    }
208    if (Math.abs(R.det() - 1.0) > 1e-9) {
209      var msg =
210          "Rotation matrix is orthogonal but not special orthogonal\n\nR =\n"
211              + R.getStorage().toString()
212              + '\n';
213      MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
214      throw new IllegalArgumentException(msg);
215    }
216
217    // Turn rotation matrix into a quaternion
218    // https://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/
219    double trace = R.get(0, 0) + R.get(1, 1) + R.get(2, 2);
220    double w;
221    double x;
222    double y;
223    double z;
224
225    if (trace > 0.0) {
226      double s = 0.5 / Math.sqrt(trace + 1.0);
227      w = 0.25 / s;
228      x = (R.get(2, 1) - R.get(1, 2)) * s;
229      y = (R.get(0, 2) - R.get(2, 0)) * s;
230      z = (R.get(1, 0) - R.get(0, 1)) * s;
231    } else {
232      if (R.get(0, 0) > R.get(1, 1) && R.get(0, 0) > R.get(2, 2)) {
233        double s = 2.0 * Math.sqrt(1.0 + R.get(0, 0) - R.get(1, 1) - R.get(2, 2));
234        w = (R.get(2, 1) - R.get(1, 2)) / s;
235        x = 0.25 * s;
236        y = (R.get(0, 1) + R.get(1, 0)) / s;
237        z = (R.get(0, 2) + R.get(2, 0)) / s;
238      } else if (R.get(1, 1) > R.get(2, 2)) {
239        double s = 2.0 * Math.sqrt(1.0 + R.get(1, 1) - R.get(0, 0) - R.get(2, 2));
240        w = (R.get(0, 2) - R.get(2, 0)) / s;
241        x = (R.get(0, 1) + R.get(1, 0)) / s;
242        y = 0.25 * s;
243        z = (R.get(1, 2) + R.get(2, 1)) / s;
244      } else {
245        double s = 2.0 * Math.sqrt(1.0 + R.get(2, 2) - R.get(0, 0) - R.get(1, 1));
246        w = (R.get(1, 0) - R.get(0, 1)) / s;
247        x = (R.get(0, 2) + R.get(2, 0)) / s;
248        y = (R.get(1, 2) + R.get(2, 1)) / s;
249        z = 0.25 * s;
250      }
251    }
252
253    m_q = new Quaternion(w, x, y, z);
254  }
255
256  /**
257   * Constructs a Rotation3d that rotates the initial vector onto the final vector.
258   *
259   * <p>This is useful for turning a 3D vector (final) into an orientation relative to a coordinate
260   * system vector (initial).
261   *
262   * @param initial The initial vector.
263   * @param last The final vector.
264   */
265  public Rotation3d(Vector<N3> initial, Vector<N3> last) {
266    double dot = initial.dot(last);
267    double normProduct = initial.norm() * last.norm();
268    double dotNorm = dot / normProduct;
269
270    if (dotNorm > 1.0 - 1E-9) {
271      // If the dot product is 1, the two vectors point in the same direction so
272      // there's no rotation. The default initialization of m_q will work.
273      m_q = new Quaternion();
274    } else if (dotNorm < -1.0 + 1E-9) {
275      // If the dot product is -1, the two vectors are antiparallel, so a 180°
276      // rotation is required. Any other vector can be used to generate an
277      // orthogonal one.
278
279      double x = Math.abs(initial.get(0, 0));
280      double y = Math.abs(initial.get(1, 0));
281      double z = Math.abs(initial.get(2, 0));
282
283      // Find vector that is most orthogonal to initial vector
284      Vector<N3> other;
285      if (x < y) {
286        if (x < z) {
287          // Use x-axis
288          other = VecBuilder.fill(1, 0, 0);
289        } else {
290          // Use z-axis
291          other = VecBuilder.fill(0, 0, 1);
292        }
293      } else {
294        if (y < z) {
295          // Use y-axis
296          other = VecBuilder.fill(0, 1, 0);
297        } else {
298          // Use z-axis
299          other = VecBuilder.fill(0, 0, 1);
300        }
301      }
302
303      var axis = Vector.cross(initial, other);
304
305      double axisNorm = axis.norm();
306      m_q =
307          new Quaternion(
308              0.0, axis.get(0, 0) / axisNorm, axis.get(1, 0) / axisNorm, axis.get(2, 0) / axisNorm);
309    } else {
310      var axis = Vector.cross(initial, last);
311
312      // https://stackoverflow.com/a/11741520
313      m_q =
314          new Quaternion(normProduct + dot, axis.get(0, 0), axis.get(1, 0), axis.get(2, 0))
315              .normalize();
316    }
317  }
318
319  /**
320   * Constructs a 3D rotation from a 2D rotation in the X-Y plane.
321   *
322   * @param rotation The 2D rotation.
323   * @see Pose3d#Pose3d(Pose2d)
324   * @see Transform3d#Transform3d(Transform2d)
325   */
326  public Rotation3d(Rotation2d rotation) {
327    this(0.0, 0.0, rotation.getRadians());
328  }
329
330  /**
331   * Adds two rotations together. The other rotation is applied extrinsically to this rotation,
332   * which is equivalent to this rotation being applied intrinsically to the other rotation. See the
333   * class comment for definitions of extrinsic and intrinsic rotations.
334   *
335   * <p>Note that {@code a.minus(b).plus(b)} always equals {@code a}, but {@code b.plus(a.minus(b))}
336   * sometimes doesn't. To apply a rotation offset, use either {@code offset =
337   * measurement.unaryMinus().plus(actual); newAngle = angle.plus(offset);} or {@code offset =
338   * actual.minus(measurement); newAngle = offset.plus(angle);}, depending on how the corrected
339   * angle needs to change as the input angle changes.
340   *
341   * @param other The rotation to add (applied extrinsically).
342   * @return The sum of the two rotations.
343   */
344  public Rotation3d plus(Rotation3d other) {
345    return rotateBy(other);
346  }
347
348  /**
349   * Subtracts the other rotation from the current rotation and returns the new rotation. The new
350   * rotation is from the perspective of the other rotation (like {@link Pose3d#minus}), so it needs
351   * to be applied intrinsically. See the class comment for definitions of extrinsic and intrinsic
352   * rotations.
353   *
354   * <p>Note that {@code a.minus(b).plus(b)} always equals {@code a}, but {@code b.plus(a.minus(b))}
355   * sometimes doesn't. To apply a rotation offset, use either {@code offset =
356   * measurement.unaryMinus().plus(actual); newAngle = angle.plus(offset);} or {@code offset =
357   * actual.minus(measurement); newAngle = offset.plus(angle);}, depending on how the corrected
358   * angle needs to change as the input angle changes.
359   *
360   * @param other The rotation to subtract.
361   * @return The difference between the two rotations, from the perspective of the other rotation.
362   */
363  public Rotation3d minus(Rotation3d other) {
364    return rotateBy(other.unaryMinus());
365  }
366
367  /**
368   * Takes the inverse of the current rotation.
369   *
370   * @return The inverse of the current rotation.
371   */
372  public Rotation3d unaryMinus() {
373    return new Rotation3d(m_q.inverse());
374  }
375
376  /**
377   * Multiplies the current rotation by a scalar.
378   *
379   * @param scalar The scalar.
380   * @return The new scaled Rotation3d.
381   */
382  public Rotation3d times(double scalar) {
383    // https://en.wikipedia.org/wiki/Slerp#Quaternion_Slerp
384    if (m_q.getW() >= 0.0) {
385      return new Rotation3d(
386          VecBuilder.fill(m_q.getX(), m_q.getY(), m_q.getZ()),
387          2.0 * scalar * Math.acos(m_q.getW()));
388    } else {
389      return new Rotation3d(
390          VecBuilder.fill(-m_q.getX(), -m_q.getY(), -m_q.getZ()),
391          2.0 * scalar * Math.acos(-m_q.getW()));
392    }
393  }
394
395  /**
396   * Divides the current rotation by a scalar.
397   *
398   * @param scalar The scalar.
399   * @return The new scaled Rotation3d.
400   */
401  public Rotation3d div(double scalar) {
402    return times(1.0 / scalar);
403  }
404
405  /**
406   * Adds the new rotation to the current rotation. The other rotation is applied extrinsically,
407   * which means that it rotates around the global axes. For example, {@code new
408   * Rotation3d(Units.degreesToRadians(90), 0, 0).rotateBy(new Rotation3d(0,
409   * Units.degreesToRadians(45), 0))} rotates by 90 degrees around the +X axis and then by 45
410   * degrees around the global +Y axis. (This is equivalent to {@code new
411   * Rotation3d(Units.degreesToRadians(90), Units.degreesToRadians(45), 0)})
412   *
413   * @param other The extrinsic rotation to rotate by.
414   * @return The new rotated Rotation3d.
415   */
416  public Rotation3d rotateBy(Rotation3d other) {
417    return new Rotation3d(other.m_q.times(m_q));
418  }
419
420  /**
421   * Returns the current rotation relative to the given rotation. Because the result is in the
422   * perspective of the given rotation, it must be applied intrinsically. See the class comment for
423   * definitions of extrinsic and intrinsic rotations.
424   *
425   * @param other The rotation describing the orientation of the new coordinate frame that the
426   *     current rotation will be converted into.
427   * @return The current rotation relative to the new orientation of the coordinate frame.
428   */
429  public Rotation3d relativeTo(Rotation3d other) {
430    // To apply a quaternion intrinsically, we must right-multiply by that quaternion.
431    // Therefore, "this_q relative to other_q" is the q such that other_q q = this_q:
432    //
433    //   other_q q = this_q
434    //   q = other_q⁻¹ this_q
435    return new Rotation3d(other.m_q.inverse().times(m_q));
436  }
437
438  /**
439   * Returns the quaternion representation of the Rotation3d.
440   *
441   * @return The quaternion representation of the Rotation3d.
442   */
443  @JsonProperty(value = "quaternion")
444  public Quaternion getQuaternion() {
445    return m_q;
446  }
447
448  /**
449   * Returns the counterclockwise rotation angle around the X axis (roll) in radians.
450   *
451   * @return The counterclockwise rotation angle around the X axis (roll) in radians.
452   */
453  public double getX() {
454    final var w = m_q.getW();
455    final var x = m_q.getX();
456    final var y = m_q.getY();
457    final var z = m_q.getZ();
458
459    // wpimath/algorithms.md
460    final var cxcy = 1.0 - 2.0 * (x * x + y * y);
461    final var sxcy = 2.0 * (w * x + y * z);
462    final var cy_sq = cxcy * cxcy + sxcy * sxcy;
463    if (cy_sq > 1e-20) {
464      return Math.atan2(sxcy, cxcy);
465    } else {
466      return 0.0;
467    }
468  }
469
470  /**
471   * Returns the counterclockwise rotation angle around the Y axis (pitch) in radians.
472   *
473   * @return The counterclockwise rotation angle around the Y axis (pitch) in radians.
474   */
475  public double getY() {
476    final var w = m_q.getW();
477    final var x = m_q.getX();
478    final var y = m_q.getY();
479    final var z = m_q.getZ();
480
481    // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_(in_3-2-1_sequence)_conversion
482    double ratio = 2.0 * (w * y - z * x);
483    if (Math.abs(ratio) >= 1.0) {
484      return Math.copySign(Math.PI / 2.0, ratio);
485    } else {
486      return Math.asin(ratio);
487    }
488  }
489
490  /**
491   * Returns the counterclockwise rotation angle around the Z axis (yaw) in radians.
492   *
493   * @return The counterclockwise rotation angle around the Z axis (yaw) in radians.
494   */
495  public double getZ() {
496    final var w = m_q.getW();
497    final var x = m_q.getX();
498    final var y = m_q.getY();
499    final var z = m_q.getZ();
500
501    // wpimath/algorithms.md
502    final var cycz = 1.0 - 2.0 * (y * y + z * z);
503    final var cysz = 2.0 * (w * z + x * y);
504    final var cy_sq = cycz * cycz + cysz * cysz;
505    if (cy_sq > 1e-20) {
506      return Math.atan2(cysz, cycz);
507    } else {
508      return Math.atan2(2.0 * w * z, w * w - z * z);
509    }
510  }
511
512  /**
513   * Returns the counterclockwise rotation angle around the X axis (roll) in a measure.
514   *
515   * @return The counterclockwise rotation angle around the x axis (roll) in a measure.
516   */
517  public Angle getMeasureX() {
518    return Radians.of(getX());
519  }
520
521  /**
522   * Returns the counterclockwise rotation angle around the Y axis (pitch) in a measure.
523   *
524   * @return The counterclockwise rotation angle around the y axis (pitch) in a measure.
525   */
526  public Angle getMeasureY() {
527    return Radians.of(getY());
528  }
529
530  /**
531   * Returns the counterclockwise rotation angle around the Z axis (yaw) in a measure.
532   *
533   * @return The counterclockwise rotation angle around the z axis (yaw) in a measure.
534   */
535  public Angle getMeasureZ() {
536    return Radians.of(getZ());
537  }
538
539  /**
540   * Returns the axis in the axis-angle representation of this rotation.
541   *
542   * @return The axis in the axis-angle representation.
543   */
544  public Vector<N3> getAxis() {
545    double norm =
546        Math.sqrt(m_q.getX() * m_q.getX() + m_q.getY() * m_q.getY() + m_q.getZ() * m_q.getZ());
547    if (norm == 0.0) {
548      return VecBuilder.fill(0.0, 0.0, 0.0);
549    } else {
550      return VecBuilder.fill(m_q.getX() / norm, m_q.getY() / norm, m_q.getZ() / norm);
551    }
552  }
553
554  /**
555   * Returns the angle in radians in the axis-angle representation of this rotation.
556   *
557   * @return The angle in radians in the axis-angle representation of this rotation.
558   */
559  public double getAngle() {
560    double norm =
561        Math.sqrt(m_q.getX() * m_q.getX() + m_q.getY() * m_q.getY() + m_q.getZ() * m_q.getZ());
562    return 2.0 * Math.atan2(norm, m_q.getW());
563  }
564
565  /**
566   * Returns rotation matrix representation of this rotation.
567   *
568   * @return Rotation matrix representation of this rotation.
569   */
570  public Matrix<N3, N3> toMatrix() {
571    double w = m_q.getW();
572    double x = m_q.getX();
573    double y = m_q.getY();
574    double z = m_q.getZ();
575
576    // https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation#Quaternion-derived_rotation_matrix
577    return MatBuilder.fill(
578        Nat.N3(),
579        Nat.N3(),
580        1.0 - 2.0 * (y * y + z * z),
581        2.0 * (x * y - w * z),
582        2.0 * (x * z + w * y),
583        2.0 * (x * y + w * z),
584        1.0 - 2.0 * (x * x + z * z),
585        2.0 * (y * z - w * x),
586        2.0 * (x * z - w * y),
587        2.0 * (y * z + w * x),
588        1.0 - 2.0 * (x * x + y * y));
589  }
590
591  /**
592   * Returns rotation vector representation of this rotation.
593   *
594   * @return Rotation vector representation of this rotation.
595   */
596  public Vector<N3> toVector() {
597    return m_q.toRotationVector();
598  }
599
600  /**
601   * Returns the angle in a measure in the axis-angle representation of this rotation.
602   *
603   * @return The angle in a measure in the axis-angle representation of this rotation.
604   */
605  public Angle getMeasureAngle() {
606    return Radians.of(getAngle());
607  }
608
609  /**
610   * Returns a Rotation2d representing this Rotation3d projected into the X-Y plane.
611   *
612   * @return A Rotation2d representing this Rotation3d projected into the X-Y plane.
613   */
614  public Rotation2d toRotation2d() {
615    return new Rotation2d(getZ());
616  }
617
618  @Override
619  public String toString() {
620    return String.format("Rotation3d(%s)", m_q);
621  }
622
623  /**
624   * Checks equality between this Rotation3d and another object.
625   *
626   * @param obj The other object.
627   * @return Whether the two objects are equal or not.
628   */
629  @Override
630  public boolean equals(Object obj) {
631    return obj instanceof Rotation3d other
632        && Math.abs(Math.abs(m_q.dot(other.m_q)) - m_q.norm() * other.m_q.norm()) < 1e-9;
633  }
634
635  @Override
636  public int hashCode() {
637    return Objects.hash(m_q);
638  }
639
640  @Override
641  public Rotation3d interpolate(Rotation3d endValue, double t) {
642    return endValue.minus(this).times(MathUtil.clamp(t, 0, 1)).plus(this);
643  }
644
645  /** Rotation3d protobuf for serialization. */
646  public static final Rotation3dProto proto = new Rotation3dProto();
647
648  /** Rotation3d struct for serialization. */
649  public static final Rotation3dStruct struct = new Rotation3dStruct();
650}