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.MathUtil;
012import edu.wpi.first.math.interpolation.Interpolatable;
013import java.util.Objects;
014
015/** A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine). */
016@JsonIgnoreProperties(ignoreUnknown = true)
017@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
018public class Rotation2d implements Interpolatable<Rotation2d> {
019  private final double m_value;
020  private final double m_cos;
021  private final double m_sin;
022
023  /** Constructs a Rotation2d with a default angle of 0 degrees. */
024  public Rotation2d() {
025    m_value = 0.0;
026    m_cos = 1.0;
027    m_sin = 0.0;
028  }
029
030  /**
031   * Constructs a Rotation2d with the given radian value. The x and y don't have to be normalized.
032   *
033   * @param value The value of the angle in radians.
034   */
035  @JsonCreator
036  public Rotation2d(@JsonProperty(required = true, value = "radians") double value) {
037    m_value = value;
038    m_cos = Math.cos(value);
039    m_sin = Math.sin(value);
040  }
041
042  /**
043   * Constructs a Rotation2d with the given x and y (cosine and sine) components.
044   *
045   * @param x The x component or cosine of the rotation.
046   * @param y The y component or sine of the rotation.
047   */
048  public Rotation2d(double x, double y) {
049    double magnitude = Math.hypot(x, y);
050    if (magnitude > 1e-6) {
051      m_sin = y / magnitude;
052      m_cos = x / magnitude;
053    } else {
054      m_sin = 0.0;
055      m_cos = 1.0;
056    }
057    m_value = Math.atan2(m_sin, m_cos);
058  }
059
060  /**
061   * Constructs and returns a Rotation2d with the given degree value.
062   *
063   * @param degrees The value of the angle in degrees.
064   * @return The rotation object with the desired angle value.
065   */
066  public static Rotation2d fromDegrees(double degrees) {
067    return new Rotation2d(Math.toRadians(degrees));
068  }
069
070  /**
071   * Adds two rotations together, with the result being bounded between -pi and pi.
072   *
073   * <p>For example, Rotation2d.fromDegrees(30) + Rotation2d.fromDegrees(60) = Rotation2d{-pi/2}
074   *
075   * @param other The rotation to add.
076   * @return The sum of the two rotations.
077   */
078  public Rotation2d plus(Rotation2d other) {
079    return rotateBy(other);
080  }
081
082  /**
083   * Subtracts the new rotation from the current rotation and returns the new rotation.
084   *
085   * <p>For example, Rotation2d.fromDegrees(10) - Rotation2d.fromDegrees(100) = Rotation2d{-pi/2}
086   *
087   * @param other The rotation to subtract.
088   * @return The difference between the two rotations.
089   */
090  public Rotation2d minus(Rotation2d other) {
091    return rotateBy(other.unaryMinus());
092  }
093
094  /**
095   * Takes the inverse of the current rotation. This is simply the negative of the current angular
096   * value.
097   *
098   * @return The inverse of the current rotation.
099   */
100  public Rotation2d unaryMinus() {
101    return new Rotation2d(-m_value);
102  }
103
104  /**
105   * Multiplies the current rotation by a scalar.
106   *
107   * @param scalar The scalar.
108   * @return The new scaled Rotation2d.
109   */
110  public Rotation2d times(double scalar) {
111    return new Rotation2d(m_value * scalar);
112  }
113
114  /**
115   * Adds the new rotation to the current rotation using a rotation matrix.
116   *
117   * <p>The matrix multiplication is as follows:
118   *
119   * <pre>
120   * [cos_new]   [other.cos, -other.sin][cos]
121   * [sin_new] = [other.sin,  other.cos][sin]
122   * value_new = atan2(sin_new, cos_new)
123   * </pre>
124   *
125   * @param other The rotation to rotate by.
126   * @return The new rotated Rotation2d.
127   */
128  public Rotation2d rotateBy(Rotation2d other) {
129    return new Rotation2d(
130        m_cos * other.m_cos - m_sin * other.m_sin, m_cos * other.m_sin + m_sin * other.m_cos);
131  }
132
133  /**
134   * Returns the radian value of the rotation.
135   *
136   * @return The radian value of the rotation.
137   */
138  @JsonProperty
139  public double getRadians() {
140    return m_value;
141  }
142
143  /**
144   * Returns the degree value of the rotation.
145   *
146   * @return The degree value of the rotation.
147   */
148  public double getDegrees() {
149    return Math.toDegrees(m_value);
150  }
151
152  /**
153   * Returns the cosine of the rotation.
154   *
155   * @return The cosine of the rotation.
156   */
157  public double getCos() {
158    return m_cos;
159  }
160
161  /**
162   * Returns the sine of the rotation.
163   *
164   * @return The sine of the rotation.
165   */
166  public double getSin() {
167    return m_sin;
168  }
169
170  /**
171   * Returns the tangent of the rotation.
172   *
173   * @return The tangent of the rotation.
174   */
175  public double getTan() {
176    return m_sin / m_cos;
177  }
178
179  @Override
180  public String toString() {
181    return String.format("Rotation2d(Rads: %.2f, Deg: %.2f)", m_value, Math.toDegrees(m_value));
182  }
183
184  /**
185   * Checks equality between this Rotation2d and another object.
186   *
187   * @param obj The other object.
188   * @return Whether the two objects are equal or not.
189   */
190  @Override
191  public boolean equals(Object obj) {
192    if (obj instanceof Rotation2d) {
193      var other = (Rotation2d) obj;
194      return Math.hypot(m_cos - other.m_cos, m_sin - other.m_sin) < 1E-9;
195    }
196    return false;
197  }
198
199  @Override
200  public int hashCode() {
201    return Objects.hash(m_value);
202  }
203
204  @Override
205  @SuppressWarnings("ParameterName")
206  public Rotation2d interpolate(Rotation2d endValue, double t) {
207    return new Rotation2d(MathUtil.interpolate(this.getRadians(), endValue.getRadians(), t));
208  }
209}