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.Matrix;
016import edu.wpi.first.math.Nat;
017import edu.wpi.first.math.geometry.proto.Rotation2dProto;
018import edu.wpi.first.math.geometry.struct.Rotation2dStruct;
019import edu.wpi.first.math.interpolation.Interpolatable;
020import edu.wpi.first.math.numbers.N2;
021import edu.wpi.first.math.util.Units;
022import edu.wpi.first.units.measure.Angle;
023import edu.wpi.first.util.protobuf.ProtobufSerializable;
024import edu.wpi.first.util.struct.StructSerializable;
025import java.util.Objects;
026
027/**
028 * A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
029 */
030@JsonIgnoreProperties(ignoreUnknown = true)
031@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
032public class Rotation2d
033    implements Interpolatable<Rotation2d>, ProtobufSerializable, StructSerializable {
034  /**
035   * A preallocated Rotation2d representing no rotation.
036   *
037   * <p>This exists to avoid allocations for common rotations.
038   */
039  public static final Rotation2d kZero = new Rotation2d();
040
041  /**
042   * A preallocated Rotation2d representing a clockwise rotation by π/2 rad (90°).
043   *
044   * <p>This exists to avoid allocations for common rotations.
045   */
046  public static final Rotation2d kCW_Pi_2 = new Rotation2d(-Math.PI / 2);
047
048  /**
049   * A preallocated Rotation2d representing a clockwise rotation by 90° (π/2 rad).
050   *
051   * <p>This exists to avoid allocations for common rotations.
052   */
053  public static final Rotation2d kCW_90deg = kCW_Pi_2;
054
055  /**
056   * A preallocated Rotation2d representing a counterclockwise rotation by π/2 rad (90°).
057   *
058   * <p>This exists to avoid allocations for common rotations.
059   */
060  public static final Rotation2d kCCW_Pi_2 = new Rotation2d(Math.PI / 2);
061
062  /**
063   * A preallocated Rotation2d representing a counterclockwise rotation by 90° (π/2 rad).
064   *
065   * <p>This exists to avoid allocations for common rotations.
066   */
067  public static final Rotation2d kCCW_90deg = kCCW_Pi_2;
068
069  /**
070   * A preallocated Rotation2d representing a counterclockwise rotation by π rad (180°).
071   *
072   * <p>This exists to avoid allocations for common rotations.
073   */
074  public static final Rotation2d kPi = new Rotation2d(Math.PI);
075
076  /**
077   * A preallocated Rotation2d representing a counterclockwise rotation by 180° (π rad).
078   *
079   * <p>This exists to avoid allocations for common rotations.
080   */
081  public static final Rotation2d k180deg = kPi;
082
083  private final double m_cos;
084  private final double m_sin;
085
086  /** Constructs a Rotation2d with a default angle of 0 degrees. */
087  public Rotation2d() {
088    m_cos = 1.0;
089    m_sin = 0.0;
090  }
091
092  /**
093   * Constructs a Rotation2d with the given radian value.
094   *
095   * @param value The value of the angle in radians.
096   */
097  @JsonCreator
098  public Rotation2d(@JsonProperty(required = true, value = "radians") double value) {
099    m_cos = Math.cos(value);
100    m_sin = Math.sin(value);
101  }
102
103  /**
104   * Constructs a Rotation2d with the given x and y (cosine and sine) components.
105   *
106   * @param x The x component or cosine of the rotation.
107   * @param y The y component or sine of the rotation.
108   */
109  public Rotation2d(double x, double y) {
110    double magnitude = Math.hypot(x, y);
111    if (magnitude > 1e-6) {
112      m_cos = x / magnitude;
113      m_sin = y / magnitude;
114    } else {
115      m_cos = 1.0;
116      m_sin = 0.0;
117      MathSharedStore.reportError(
118          "x and y components of Rotation2d are zero\n", Thread.currentThread().getStackTrace());
119    }
120  }
121
122  /**
123   * Constructs a Rotation2d with the given angle.
124   *
125   * @param angle The angle of the rotation.
126   */
127  public Rotation2d(Angle angle) {
128    this(angle.in(Radians));
129  }
130
131  /**
132   * Constructs a Rotation2d from a rotation matrix.
133   *
134   * @param rotationMatrix The rotation matrix.
135   * @throws IllegalArgumentException if the rotation matrix isn't special orthogonal.
136   */
137  public Rotation2d(Matrix<N2, N2> rotationMatrix) {
138    final var R = rotationMatrix;
139
140    // Require that the rotation matrix is special orthogonal. This is true if
141    // the matrix is orthogonal (RRᵀ = I) and normalized (determinant is 1).
142    if (R.times(R.transpose()).minus(Matrix.eye(Nat.N2())).normF() > 1e-9) {
143      var msg = "Rotation matrix isn't orthogonal\n\nR =\n" + R.getStorage().toString() + '\n';
144      MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
145      throw new IllegalArgumentException(msg);
146    }
147    if (Math.abs(R.det() - 1.0) > 1e-9) {
148      var msg =
149          "Rotation matrix is orthogonal but not special orthogonal\n\nR =\n"
150              + R.getStorage().toString()
151              + '\n';
152      MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
153      throw new IllegalArgumentException(msg);
154    }
155
156    // R = [cosθ  −sinθ]
157    //     [sinθ   cosθ]
158    m_cos = R.get(0, 0);
159    m_sin = R.get(1, 0);
160  }
161
162  /**
163   * Constructs and returns a Rotation2d with the given radian value.
164   *
165   * @param radians The value of the angle in radians.
166   * @return The rotation object with the desired angle value.
167   */
168  public static Rotation2d fromRadians(double radians) {
169    return new Rotation2d(radians);
170  }
171
172  /**
173   * Constructs and returns a Rotation2d with the given degree value.
174   *
175   * @param degrees The value of the angle in degrees.
176   * @return The rotation object with the desired angle value.
177   */
178  public static Rotation2d fromDegrees(double degrees) {
179    return new Rotation2d(Math.toRadians(degrees));
180  }
181
182  /**
183   * Constructs and returns a Rotation2d with the given number of rotations.
184   *
185   * @param rotations The value of the angle in rotations.
186   * @return The rotation object with the desired angle value.
187   */
188  public static Rotation2d fromRotations(double rotations) {
189    return new Rotation2d(Units.rotationsToRadians(rotations));
190  }
191
192  /**
193   * Adds two rotations together, with the result being bounded between -π and π.
194   *
195   * <p>For example, <code>Rotation2d.fromDegrees(30).plus(Rotation2d.fromDegrees(60))</code> equals
196   * <code>Rotation2d(Math.PI/2.0)</code>
197   *
198   * @param other The rotation to add.
199   * @return The sum of the two rotations.
200   */
201  public Rotation2d plus(Rotation2d other) {
202    return rotateBy(other);
203  }
204
205  /**
206   * Subtracts the new rotation from the current rotation and returns the new rotation.
207   *
208   * <p>For example, <code>Rotation2d.fromDegrees(10).minus(Rotation2d.fromDegrees(100))</code>
209   * equals <code>Rotation2d(-Math.PI/2.0)</code>
210   *
211   * @param other The rotation to subtract.
212   * @return The difference between the two rotations.
213   */
214  public Rotation2d minus(Rotation2d other) {
215    return rotateBy(other.unaryMinus());
216  }
217
218  /**
219   * Takes the inverse of the current rotation. This is simply the negative of the current angular
220   * value.
221   *
222   * @return The inverse of the current rotation.
223   */
224  public Rotation2d unaryMinus() {
225    return new Rotation2d(m_cos, -m_sin);
226  }
227
228  /**
229   * Multiplies the current rotation by a scalar.
230   *
231   * @param scalar The scalar.
232   * @return The new scaled Rotation2d.
233   */
234  public Rotation2d times(double scalar) {
235    return new Rotation2d(getRadians() * scalar);
236  }
237
238  /**
239   * Divides the current rotation by a scalar.
240   *
241   * @param scalar The scalar.
242   * @return The new scaled Rotation2d.
243   */
244  public Rotation2d div(double scalar) {
245    return times(1.0 / scalar);
246  }
247
248  /**
249   * Adds the new rotation to the current rotation using a rotation matrix.
250   *
251   * <p>The matrix multiplication is as follows:
252   *
253   * <pre>
254   * [cos_new]   [other.cos, -other.sin][cos]
255   * [sin_new] = [other.sin,  other.cos][sin]
256   * value_new = atan2(sin_new, cos_new)
257   * </pre>
258   *
259   * @param other The rotation to rotate by.
260   * @return The new rotated Rotation2d.
261   */
262  public Rotation2d rotateBy(Rotation2d other) {
263    return new Rotation2d(
264        m_cos * other.m_cos - m_sin * other.m_sin, m_cos * other.m_sin + m_sin * other.m_cos);
265  }
266
267  /**
268   * Returns matrix representation of this rotation.
269   *
270   * @return Matrix representation of this rotation.
271   */
272  public Matrix<N2, N2> toMatrix() {
273    // R = [cosθ  −sinθ]
274    //     [sinθ   cosθ]
275    return MatBuilder.fill(Nat.N2(), Nat.N2(), m_cos, -m_sin, m_sin, m_cos);
276  }
277
278  /**
279   * Returns the measure of the Rotation2d.
280   *
281   * @return The measure of the Rotation2d.
282   */
283  public Angle getMeasure() {
284    return Radians.of(getRadians());
285  }
286
287  /**
288   * Returns the radian value of the Rotation2d constrained within [-π, π].
289   *
290   * @return The radian value of the Rotation2d constrained within [-π, π].
291   */
292  @JsonProperty
293  public double getRadians() {
294    return Math.atan2(m_sin, m_cos);
295  }
296
297  /**
298   * Returns the degree value of the Rotation2d constrained within [-180, 180].
299   *
300   * @return The degree value of the Rotation2d constrained within [-180, 180].
301   */
302  public double getDegrees() {
303    return Math.toDegrees(getRadians());
304  }
305
306  /**
307   * Returns the number of rotations of the Rotation2d.
308   *
309   * @return The number of rotations of the Rotation2d.
310   */
311  public double getRotations() {
312    return Units.radiansToRotations(getRadians());
313  }
314
315  /**
316   * Returns the cosine of the Rotation2d.
317   *
318   * @return The cosine of the Rotation2d.
319   */
320  public double getCos() {
321    return m_cos;
322  }
323
324  /**
325   * Returns the sine of the Rotation2d.
326   *
327   * @return The sine of the Rotation2d.
328   */
329  public double getSin() {
330    return m_sin;
331  }
332
333  /**
334   * Returns the tangent of the Rotation2d.
335   *
336   * @return The tangent of the Rotation2d.
337   */
338  public double getTan() {
339    return m_sin / m_cos;
340  }
341
342  @Override
343  public String toString() {
344    return String.format("Rotation2d(Rads: %.2f, Deg: %.2f)", getRadians(), getDegrees());
345  }
346
347  /**
348   * Checks equality between this Rotation2d and another object.
349   *
350   * @param obj The other object.
351   * @return Whether the two objects are equal or not.
352   */
353  @Override
354  public boolean equals(Object obj) {
355    return obj instanceof Rotation2d other
356        && Math.hypot(m_cos - other.m_cos, m_sin - other.m_sin) < 1E-9;
357  }
358
359  @Override
360  public int hashCode() {
361    return Objects.hash(getRadians());
362  }
363
364  @Override
365  public Rotation2d interpolate(Rotation2d endValue, double t) {
366    return plus(endValue.minus(this).times(Math.clamp(t, 0, 1)));
367  }
368
369  /** Rotation2d protobuf for serialization. */
370  public static final Rotation2dProto proto = new Rotation2dProto();
371
372  /** Rotation2d struct for serialization. */
373  public static final Rotation2dStruct struct = new Rotation2dStruct();
374}