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