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.Meters;
008
009import io.avaje.jsonb.Json;
010import java.util.Collection;
011import java.util.Collections;
012import java.util.Comparator;
013import java.util.Objects;
014import org.wpilib.math.geometry.proto.Pose3dProto;
015import org.wpilib.math.geometry.struct.Pose3dStruct;
016import org.wpilib.math.interpolation.Interpolatable;
017import org.wpilib.math.linalg.MatBuilder;
018import org.wpilib.math.linalg.Matrix;
019import org.wpilib.math.numbers.N4;
020import org.wpilib.math.util.Nat;
021import org.wpilib.units.measure.Distance;
022import org.wpilib.util.protobuf.ProtobufSerializable;
023import org.wpilib.util.struct.StructSerializable;
024
025/** Represents a 3D pose containing translational and rotational elements. */
026@Json
027public final class Pose3d
028    implements Interpolatable<Pose3d>, ProtobufSerializable, StructSerializable {
029  /**
030   * A preallocated Pose3d representing the origin.
031   *
032   * <p>This exists to avoid allocations for common poses.
033   */
034  public static final Pose3d kZero = new Pose3d();
035
036  @Json.Property("translation")
037  private final Translation3d m_translation;
038
039  @Json.Property("rotation")
040  private final Rotation3d m_rotation;
041
042  /** Constructs a pose at the origin facing toward the positive X axis. */
043  public Pose3d() {
044    m_translation = Translation3d.kZero;
045    m_rotation = Rotation3d.kZero;
046  }
047
048  /**
049   * Constructs a pose with the specified translation and rotation.
050   *
051   * @param translation The translational component of the pose.
052   * @param rotation The rotational component of the pose.
053   */
054  @Json.Creator
055  public Pose3d(Translation3d translation, Rotation3d rotation) {
056    m_translation = translation;
057    m_rotation = rotation;
058  }
059
060  /**
061   * Constructs a pose with x, y, and z translations instead of a separate Translation3d.
062   *
063   * @param x The x component of the translational component of the pose.
064   * @param y The y component of the translational component of the pose.
065   * @param z The z component of the translational component of the pose.
066   * @param rotation The rotational component of the pose.
067   */
068  public Pose3d(double x, double y, double z, Rotation3d rotation) {
069    m_translation = new Translation3d(x, y, z);
070    m_rotation = rotation;
071  }
072
073  /**
074   * Constructs a pose with x, y, and z translations instead of a separate Translation3d. The X, Y,
075   * and Z translations will be converted to and tracked as meters.
076   *
077   * @param x The x component of the translational component of the pose.
078   * @param y The y component of the translational component of the pose.
079   * @param z The z component of the translational component of the pose.
080   * @param rotation The rotational component of the pose.
081   */
082  public Pose3d(Distance x, Distance y, Distance z, Rotation3d rotation) {
083    this(x.in(Meters), y.in(Meters), z.in(Meters), rotation);
084  }
085
086  /**
087   * Constructs a pose with the specified affine transformation matrix.
088   *
089   * @param matrix The affine transformation matrix.
090   * @throws IllegalArgumentException if the affine transformation matrix is invalid.
091   */
092  public Pose3d(Matrix<N4, N4> matrix) {
093    m_translation = new Translation3d(matrix.get(0, 3), matrix.get(1, 3), matrix.get(2, 3));
094    m_rotation = new Rotation3d(matrix.block(3, 3, 0, 0));
095    if (matrix.get(3, 0) != 0.0
096        || matrix.get(3, 1) != 0.0
097        || matrix.get(3, 2) != 0.0
098        || matrix.get(3, 3) != 1.0) {
099      throw new IllegalArgumentException("Affine transformation matrix is invalid");
100    }
101  }
102
103  /**
104   * Constructs a 3D pose from a 2D pose in the X-Y plane.
105   *
106   * @param pose The 2D pose.
107   * @see Rotation3d#Rotation3d(Rotation2d)
108   * @see Translation3d#Translation3d(Translation2d)
109   */
110  public Pose3d(Pose2d pose) {
111    m_translation = new Translation3d(pose.getX(), pose.getY(), 0.0);
112    m_rotation = new Rotation3d(0.0, 0.0, pose.getRotation().getRadians());
113  }
114
115  /**
116   * Transforms the pose by the given transformation and returns the new transformed pose. The
117   * transform is applied relative to the pose's frame. Note that this differs from {@link
118   * Pose3d#rotateBy(Rotation3d)}, which is applied relative to the global frame and around the
119   * origin.
120   *
121   * @param other The transform to transform the pose by.
122   * @return The transformed pose.
123   */
124  public Pose3d plus(Transform3d other) {
125    return transformBy(other);
126  }
127
128  /**
129   * Returns the Transform3d that maps the one pose to another.
130   *
131   * @param other The initial pose of the transformation.
132   * @return The transform that maps the other pose to the current pose.
133   */
134  public Transform3d minus(Pose3d other) {
135    final var pose = this.relativeTo(other);
136    return new Transform3d(pose.getTranslation(), pose.getRotation());
137  }
138
139  /**
140   * Returns the translation component of the transformation.
141   *
142   * @return The translational component of the pose.
143   */
144  public Translation3d getTranslation() {
145    return m_translation;
146  }
147
148  /**
149   * Returns the X component of the pose's translation.
150   *
151   * @return The x component of the pose's translation.
152   */
153  public double getX() {
154    return m_translation.getX();
155  }
156
157  /**
158   * Returns the Y component of the pose's translation.
159   *
160   * @return The y component of the pose's translation.
161   */
162  public double getY() {
163    return m_translation.getY();
164  }
165
166  /**
167   * Returns the Z component of the pose's translation.
168   *
169   * @return The z component of the pose's translation.
170   */
171  public double getZ() {
172    return m_translation.getZ();
173  }
174
175  /**
176   * Returns the X component of the pose's translation in a measure.
177   *
178   * @return The x component of the pose's translation in a measure.
179   */
180  public Distance getMeasureX() {
181    return m_translation.getMeasureX();
182  }
183
184  /**
185   * Returns the Y component of the pose's translation in a measure.
186   *
187   * @return The y component of the pose's translation in a measure.
188   */
189  public Distance getMeasureY() {
190    return m_translation.getMeasureY();
191  }
192
193  /**
194   * Returns the Z component of the pose's translation in a measure.
195   *
196   * @return The z component of the pose's translation in a measure.
197   */
198  public Distance getMeasureZ() {
199    return m_translation.getMeasureZ();
200  }
201
202  /**
203   * Returns the rotational component of the transformation.
204   *
205   * @return The rotational component of the pose.
206   */
207  public Rotation3d getRotation() {
208    return m_rotation;
209  }
210
211  /**
212   * Multiplies the current pose by a scalar.
213   *
214   * @param scalar The scalar.
215   * @return The new scaled Pose3d.
216   */
217  public Pose3d times(double scalar) {
218    return new Pose3d(m_translation.times(scalar), m_rotation.times(scalar));
219  }
220
221  /**
222   * Divides the current pose by a scalar.
223   *
224   * @param scalar The scalar.
225   * @return The new scaled Pose3d.
226   */
227  public Pose3d div(double scalar) {
228    return times(1.0 / scalar);
229  }
230
231  /**
232   * Rotates the pose around the origin and returns the new pose.
233   *
234   * @param other The rotation to transform the pose by, which is applied extrinsically (from the
235   *     global frame).
236   * @return The rotated pose.
237   */
238  public Pose3d rotateBy(Rotation3d other) {
239    return new Pose3d(m_translation.rotateBy(other), m_rotation.rotateBy(other));
240  }
241
242  /**
243   * Transforms the pose by the given transformation and returns the new transformed pose. The
244   * transform is applied relative to the pose's frame. Note that this differs from {@link
245   * Pose3d#rotateBy(Rotation3d)}, which is applied relative to the global frame and around the
246   * origin.
247   *
248   * @param other The transform to transform the pose by.
249   * @return The transformed pose.
250   */
251  public Pose3d transformBy(Transform3d other) {
252    // Rotating the transform's rotation by the pose's rotation extrinsically is equivalent to
253    // rotating the pose's rotation by the transform's rotation intrinsically. (We define transforms
254    // as being applied intrinsically.)
255    return new Pose3d(
256        m_translation.plus(other.getTranslation().rotateBy(m_rotation)),
257        other.getRotation().rotateBy(m_rotation));
258  }
259
260  /**
261   * Returns the current pose relative to the given pose.
262   *
263   * <p>This function can often be used for trajectory tracking or pose stabilization algorithms to
264   * get the error between the reference and the current pose.
265   *
266   * @param other The pose that is the origin of the new coordinate frame that the current pose will
267   *     be converted into.
268   * @return The current pose relative to the new origin pose.
269   */
270  public Pose3d relativeTo(Pose3d other) {
271    var transform = new Transform3d(other, this);
272    return new Pose3d(transform.getTranslation(), transform.getRotation());
273  }
274
275  /**
276   * Rotates the current pose around a point in 3D space.
277   *
278   * @param point The point in 3D space to rotate around.
279   * @param rot The rotation to rotate the pose by.
280   * @return The new rotated pose.
281   */
282  public Pose3d rotateAround(Translation3d point, Rotation3d rot) {
283    return new Pose3d(m_translation.rotateAround(point, rot), m_rotation.rotateBy(rot));
284  }
285
286  /**
287   * Returns an affine transformation matrix representation of this pose.
288   *
289   * @return An affine transformation matrix representation of this pose.
290   */
291  public Matrix<N4, N4> toMatrix() {
292    var vec = m_translation.toVector();
293    var mat = m_rotation.toMatrix();
294    return MatBuilder.fill(
295        Nat.N4(),
296        Nat.N4(),
297        mat.get(0, 0),
298        mat.get(0, 1),
299        mat.get(0, 2),
300        vec.get(0),
301        mat.get(1, 0),
302        mat.get(1, 1),
303        mat.get(1, 2),
304        vec.get(1),
305        mat.get(2, 0),
306        mat.get(2, 1),
307        mat.get(2, 2),
308        vec.get(2),
309        0.0,
310        0.0,
311        0.0,
312        1.0);
313  }
314
315  /**
316   * Returns a Pose2d representing this Pose3d projected into the X-Y plane.
317   *
318   * @return A Pose2d representing this Pose3d projected into the X-Y plane.
319   */
320  public Pose2d toPose2d() {
321    return new Pose2d(m_translation.toTranslation2d(), m_rotation.toRotation2d());
322  }
323
324  /**
325   * Returns the nearest Pose3d from a collection of poses. If two or more poses in the collection
326   * have the same distance from this pose, return the one with the closest rotation component.
327   *
328   * @param poses The collection of poses to find the nearest.
329   * @return The nearest Pose3d from the collection.
330   */
331  public Pose3d nearest(Collection<Pose3d> poses) {
332    return Collections.min(
333        poses,
334        Comparator.comparing(
335                (Pose3d other) -> this.getTranslation().getDistance(other.getTranslation()))
336            .thenComparing(
337                (Pose3d other) -> this.getRotation().relativeTo(other.getRotation()).getAngle()));
338  }
339
340  @Override
341  public String toString() {
342    return String.format("Pose3d(%s, %s)", m_translation, m_rotation);
343  }
344
345  /**
346   * Checks equality between this Pose3d and another object.
347   *
348   * @param obj The other object.
349   * @return Whether the two objects are equal or not.
350   */
351  @Override
352  public boolean equals(Object obj) {
353    return obj instanceof Pose3d pose
354        && m_translation.equals(pose.m_translation)
355        && m_rotation.equals(pose.m_rotation);
356  }
357
358  @Override
359  public int hashCode() {
360    return Objects.hash(m_translation, m_rotation);
361  }
362
363  @Override
364  public Pose3d interpolate(Pose3d endValue, double t) {
365    if (t < 0) {
366      return this;
367    } else if (t >= 1) {
368      return endValue;
369    } else {
370      var twist = endValue.minus(this).log();
371      var scaledTwist =
372          new Twist3d(
373              twist.dx * t, twist.dy * t, twist.dz * t, twist.rx * t, twist.ry * t, twist.rz * t);
374      return this.plus(scaledTwist.exp());
375    }
376  }
377
378  /** Pose3d protobuf for serialization. */
379  public static final Pose3dProto proto = new Pose3dProto();
380
381  /** Pose3d struct for serialization. */
382  public static final Pose3dStruct struct = new Pose3dStruct();
383}