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.Meters;
008
009import edu.wpi.first.math.MatBuilder;
010import edu.wpi.first.math.Matrix;
011import edu.wpi.first.math.Nat;
012import edu.wpi.first.math.geometry.proto.Transform2dProto;
013import edu.wpi.first.math.geometry.struct.Transform2dStruct;
014import edu.wpi.first.math.numbers.N3;
015import edu.wpi.first.units.measure.Distance;
016import edu.wpi.first.util.protobuf.ProtobufSerializable;
017import edu.wpi.first.util.struct.StructSerializable;
018import java.util.Objects;
019
020/** Represents a transformation for a Pose2d in the pose's frame. */
021public class Transform2d implements ProtobufSerializable, StructSerializable {
022  /**
023   * A preallocated Transform2d representing no transformation.
024   *
025   * <p>This exists to avoid allocations for common transformations.
026   */
027  public static final Transform2d kZero = new Transform2d();
028
029  private final Translation2d m_translation;
030  private final Rotation2d m_rotation;
031
032  /**
033   * Constructs the transform that maps the initial pose to the final pose.
034   *
035   * @param initial The initial pose for the transformation.
036   * @param last The final pose for the transformation.
037   */
038  public Transform2d(Pose2d initial, Pose2d last) {
039    // We are rotating the difference between the translations
040    // using a clockwise rotation matrix. This transforms the global
041    // delta into a local delta (relative to the initial pose).
042    m_translation =
043        last.getTranslation()
044            .minus(initial.getTranslation())
045            .rotateBy(initial.getRotation().unaryMinus());
046
047    m_rotation = last.getRotation().minus(initial.getRotation());
048  }
049
050  /**
051   * Constructs a transform with the given translation and rotation components.
052   *
053   * @param translation Translational component of the transform.
054   * @param rotation Rotational component of the transform.
055   */
056  public Transform2d(Translation2d translation, Rotation2d rotation) {
057    m_translation = translation;
058    m_rotation = rotation;
059  }
060
061  /**
062   * Constructs a transform with x and y translations instead of a separate Translation2d.
063   *
064   * @param x The x component of the translational component of the transform.
065   * @param y The y component of the translational component of the transform.
066   * @param rotation The rotational component of the transform.
067   */
068  public Transform2d(double x, double y, Rotation2d rotation) {
069    m_translation = new Translation2d(x, y);
070    m_rotation = rotation;
071  }
072
073  /**
074   * Constructs a transform with x and y translations instead of a separate Translation2d. The X and
075   * Y translations will be converted to and tracked as meters.
076   *
077   * @param x The x component of the translational component of the transform.
078   * @param y The y component of the translational component of the transform.
079   * @param rotation The rotational component of the transform.
080   */
081  public Transform2d(Distance x, Distance y, Rotation2d rotation) {
082    this(x.in(Meters), y.in(Meters), rotation);
083  }
084
085  /**
086   * Constructs a transform with the specified affine transformation matrix.
087   *
088   * @param matrix The affine transformation matrix.
089   * @throws IllegalArgumentException if the affine transformation matrix is invalid.
090   */
091  public Transform2d(Matrix<N3, N3> matrix) {
092    m_translation = new Translation2d(matrix.get(0, 2), matrix.get(1, 2));
093    m_rotation = new Rotation2d(matrix.block(2, 2, 0, 0));
094    if (matrix.get(2, 0) != 0.0 || matrix.get(2, 1) != 0.0 || matrix.get(2, 2) != 1.0) {
095      throw new IllegalArgumentException("Affine transformation matrix is invalid");
096    }
097  }
098
099  /** Constructs the identity transform -- maps an initial pose to itself. */
100  public Transform2d() {
101    m_translation = Translation2d.kZero;
102    m_rotation = Rotation2d.kZero;
103  }
104
105  /**
106   * Multiplies the transform by the scalar.
107   *
108   * @param scalar The scalar.
109   * @return The scaled Transform2d.
110   */
111  public Transform2d times(double scalar) {
112    return new Transform2d(m_translation.times(scalar), m_rotation.times(scalar));
113  }
114
115  /**
116   * Divides the transform by the scalar.
117   *
118   * @param scalar The scalar.
119   * @return The scaled Transform2d.
120   */
121  public Transform2d div(double scalar) {
122    return times(1.0 / scalar);
123  }
124
125  /**
126   * Composes two transformations. The second transform is applied relative to the orientation of
127   * the first.
128   *
129   * @param other The transform to compose with this one.
130   * @return The composition of the two transformations.
131   */
132  public Transform2d plus(Transform2d other) {
133    return new Transform2d(Pose2d.kZero, Pose2d.kZero.transformBy(this).transformBy(other));
134  }
135
136  /**
137   * Returns the translation component of the transformation.
138   *
139   * @return The translational component of the transform.
140   */
141  public Translation2d getTranslation() {
142    return m_translation;
143  }
144
145  /**
146   * Returns the X component of the transformation's translation.
147   *
148   * @return The x component of the transformation's translation.
149   */
150  public double getX() {
151    return m_translation.getX();
152  }
153
154  /**
155   * Returns the Y component of the transformation's translation.
156   *
157   * @return The y component of the transformation's translation.
158   */
159  public double getY() {
160    return m_translation.getY();
161  }
162
163  /**
164   * Returns the X component of the transformation's translation in a measure.
165   *
166   * @return The x component of the transformation's translation in a measure.
167   */
168  public Distance getMeasureX() {
169    return m_translation.getMeasureX();
170  }
171
172  /**
173   * Returns the Y component of the transformation's translation in a measure.
174   *
175   * @return The y component of the transformation's translation in a measure.
176   */
177  public Distance getMeasureY() {
178    return m_translation.getMeasureY();
179  }
180
181  /**
182   * Returns an affine transformation matrix representation of this transformation.
183   *
184   * @return An affine transformation matrix representation of this transformation.
185   */
186  public Matrix<N3, N3> toMatrix() {
187    var vec = m_translation.toVector();
188    var mat = m_rotation.toMatrix();
189    return MatBuilder.fill(
190        Nat.N3(),
191        Nat.N3(),
192        mat.get(0, 0),
193        mat.get(0, 1),
194        vec.get(0),
195        mat.get(1, 0),
196        mat.get(1, 1),
197        vec.get(1),
198        0.0,
199        0.0,
200        1.0);
201  }
202
203  /**
204   * Returns the rotational component of the transformation.
205   *
206   * @return Reference to the rotational component of the transform.
207   */
208  public Rotation2d getRotation() {
209    return m_rotation;
210  }
211
212  /**
213   * Invert the transformation. This is useful for undoing a transformation.
214   *
215   * @return The inverted transformation.
216   */
217  public Transform2d inverse() {
218    // We are rotating the difference between the translations
219    // using a clockwise rotation matrix. This transforms the global
220    // delta into a local delta (relative to the initial pose).
221    return new Transform2d(
222        getTranslation().unaryMinus().rotateBy(getRotation().unaryMinus()),
223        getRotation().unaryMinus());
224  }
225
226  @Override
227  public String toString() {
228    return String.format("Transform2d(%s, %s)", m_translation, m_rotation);
229  }
230
231  /**
232   * Checks equality between this Transform2d and another object.
233   *
234   * @param obj The other object.
235   * @return Whether the two objects are equal or not.
236   */
237  @Override
238  public boolean equals(Object obj) {
239    return obj instanceof Transform2d other
240        && other.m_translation.equals(m_translation)
241        && other.m_rotation.equals(m_rotation);
242  }
243
244  @Override
245  public int hashCode() {
246    return Objects.hash(m_translation, m_rotation);
247  }
248
249  /** Transform2d protobuf for serialization. */
250  public static final Transform2dProto proto = new Transform2dProto();
251
252  /** Transform2d struct for serialization. */
253  public static final Transform2dStruct struct = new Transform2dStruct();
254}