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