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.Transform3dProto;
013import edu.wpi.first.math.geometry.struct.Transform3dStruct;
014import edu.wpi.first.math.numbers.N4;
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 Pose3d in the pose's frame. */
021public class Transform3d implements ProtobufSerializable, StructSerializable {
022  /**
023   * A preallocated Transform3d representing no transformation.
024   *
025   * <p>This exists to avoid allocations for common transformations.
026   */
027  public static final Transform3d kZero = new Transform3d();
028
029  private final Translation3d m_translation;
030  private final Rotation3d 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 Transform3d(Pose3d initial, Pose3d 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 Transform3d(Translation3d translation, Rotation3d rotation) {
057    m_translation = translation;
058    m_rotation = rotation;
059  }
060
061  /**
062   * Constructs a transform with x, y, and z translations instead of a separate Translation3d.
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 z The z component of the translational component of the transform.
067   * @param rotation The rotational component of the transform.
068   */
069  public Transform3d(double x, double y, double z, Rotation3d rotation) {
070    m_translation = new Translation3d(x, y, z);
071    m_rotation = rotation;
072  }
073
074  /**
075   * Constructs a transform with x, y, and z translations instead of a separate Translation3d. The
076   * X, Y, and Z translations will be converted to and tracked as meters.
077   *
078   * @param x The x component of the translational component of the transform.
079   * @param y The y component of the translational component of the transform.
080   * @param z The z component of the translational component of the transform.
081   * @param rotation The rotational component of the transform.
082   */
083  public Transform3d(Distance x, Distance y, Distance z, Rotation3d rotation) {
084    this(x.in(Meters), y.in(Meters), z.in(Meters), rotation);
085  }
086
087  /**
088   * Constructs a transform with the specified affine transformation matrix.
089   *
090   * @param matrix The affine transformation matrix.
091   * @throws IllegalArgumentException if the affine transformation matrix is invalid.
092   */
093  public Transform3d(Matrix<N4, N4> matrix) {
094    m_translation = new Translation3d(matrix.get(0, 3), matrix.get(1, 3), matrix.get(2, 3));
095    m_rotation = new Rotation3d(matrix.block(3, 3, 0, 0));
096    if (matrix.get(3, 0) != 0.0
097        || matrix.get(3, 1) != 0.0
098        || matrix.get(3, 2) != 0.0
099        || matrix.get(3, 3) != 1.0) {
100      throw new IllegalArgumentException("Affine transformation matrix is invalid");
101    }
102  }
103
104  /** Constructs the identity transform -- maps an initial pose to itself. */
105  public Transform3d() {
106    m_translation = Translation3d.kZero;
107    m_rotation = Rotation3d.kZero;
108  }
109
110  /**
111   * Constructs a 3D transform from a 2D transform in the X-Y plane.
112   *
113   * @param transform The 2D transform.
114   * @see Rotation3d#Rotation3d(Rotation2d)
115   * @see Translation3d#Translation3d(Translation2d)
116   */
117  public Transform3d(Transform2d transform) {
118    m_translation = new Translation3d(transform.getTranslation());
119    m_rotation = new Rotation3d(transform.getRotation());
120  }
121
122  /**
123   * Multiplies the transform by the scalar.
124   *
125   * @param scalar The scalar.
126   * @return The scaled Transform3d.
127   */
128  public Transform3d times(double scalar) {
129    return new Transform3d(m_translation.times(scalar), m_rotation.times(scalar));
130  }
131
132  /**
133   * Divides the transform by the scalar.
134   *
135   * @param scalar The scalar.
136   * @return The scaled Transform3d.
137   */
138  public Transform3d div(double scalar) {
139    return times(1.0 / scalar);
140  }
141
142  /**
143   * Composes two transformations. The second transform is applied relative to the orientation of
144   * the first.
145   *
146   * @param other The transform to compose with this one.
147   * @return The composition of the two transformations.
148   */
149  public Transform3d plus(Transform3d other) {
150    return new Transform3d(Pose3d.kZero, Pose3d.kZero.transformBy(this).transformBy(other));
151  }
152
153  /**
154   * Returns the translation component of the transformation.
155   *
156   * @return The translational component of the transform.
157   */
158  public Translation3d getTranslation() {
159    return m_translation;
160  }
161
162  /**
163   * Returns the X component of the transformation's translation.
164   *
165   * @return The x component of the transformation's translation.
166   */
167  public double getX() {
168    return m_translation.getX();
169  }
170
171  /**
172   * Returns the Y component of the transformation's translation.
173   *
174   * @return The y component of the transformation's translation.
175   */
176  public double getY() {
177    return m_translation.getY();
178  }
179
180  /**
181   * Returns the Z component of the transformation's translation.
182   *
183   * @return The z component of the transformation's translation.
184   */
185  public double getZ() {
186    return m_translation.getZ();
187  }
188
189  /**
190   * Returns the X component of the transformation's translation in a measure.
191   *
192   * @return The x component of the transformation's translation in a measure.
193   */
194  public Distance getMeasureX() {
195    return m_translation.getMeasureX();
196  }
197
198  /**
199   * Returns the Y component of the transformation's translation in a measure.
200   *
201   * @return The y component of the transformation's translation in a measure.
202   */
203  public Distance getMeasureY() {
204    return m_translation.getMeasureY();
205  }
206
207  /**
208   * Returns the Z component of the transformation's translation in a measure.
209   *
210   * @return The z component of the transformation's translation in a measure.
211   */
212  public Distance getMeasureZ() {
213    return m_translation.getMeasureZ();
214  }
215
216  /**
217   * Returns an affine transformation matrix representation of this transformation.
218   *
219   * @return An affine transformation matrix representation of this transformation.
220   */
221  public Matrix<N4, N4> toMatrix() {
222    var vec = m_translation.toVector();
223    var mat = m_rotation.toMatrix();
224    return MatBuilder.fill(
225        Nat.N4(),
226        Nat.N4(),
227        mat.get(0, 0),
228        mat.get(0, 1),
229        mat.get(0, 2),
230        vec.get(0),
231        mat.get(1, 0),
232        mat.get(1, 1),
233        mat.get(1, 2),
234        vec.get(1),
235        mat.get(2, 0),
236        mat.get(2, 1),
237        mat.get(2, 2),
238        vec.get(2),
239        0.0,
240        0.0,
241        0.0,
242        1.0);
243  }
244
245  /**
246   * Returns the rotational component of the transformation.
247   *
248   * @return Reference to the rotational component of the transform.
249   */
250  public Rotation3d getRotation() {
251    return m_rotation;
252  }
253
254  /**
255   * Invert the transformation. This is useful for undoing a transformation.
256   *
257   * @return The inverted transformation.
258   */
259  public Transform3d inverse() {
260    // We are rotating the difference between the translations
261    // using a clockwise rotation matrix. This transforms the global
262    // delta into a local delta (relative to the initial pose).
263    return new Transform3d(
264        getTranslation().unaryMinus().rotateBy(getRotation().unaryMinus()),
265        getRotation().unaryMinus());
266  }
267
268  @Override
269  public String toString() {
270    return String.format("Transform3d(%s, %s)", m_translation, m_rotation);
271  }
272
273  /**
274   * Checks equality between this Transform3d and another object.
275   *
276   * @param obj The other object.
277   * @return Whether the two objects are equal or not.
278   */
279  @Override
280  public boolean equals(Object obj) {
281    return obj instanceof Transform3d other
282        && other.m_translation.equals(m_translation)
283        && other.m_rotation.equals(m_rotation);
284  }
285
286  @Override
287  public int hashCode() {
288    return Objects.hash(m_translation, m_rotation);
289  }
290
291  /** Transform3d protobuf for serialization. */
292  public static final Transform3dProto proto = new Transform3dProto();
293
294  /** Transform3d struct for serialization. */
295  public static final Transform3dStruct struct = new Transform3dStruct();
296}