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.Pose2dProto;
015import org.wpilib.math.geometry.struct.Pose2dStruct;
016import org.wpilib.math.interpolation.Interpolatable;
017import org.wpilib.math.linalg.MatBuilder;
018import org.wpilib.math.linalg.Matrix;
019import org.wpilib.math.numbers.N3;
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 2D pose containing translational and rotational elements. */
026@Json
027public final class Pose2d
028    implements Interpolatable<Pose2d>, ProtobufSerializable, StructSerializable {
029  /**
030   * A preallocated Pose2d representing the origin.
031   *
032   * <p>This exists to avoid allocations for common poses.
033   */
034  public static final Pose2d kZero = new Pose2d();
035
036  @Json.Property("translation")
037  private final Translation2d m_translation;
038
039  @Json.Property("rotation")
040  private final Rotation2d m_rotation;
041
042  /** Constructs a pose at the origin facing toward the positive X axis. */
043  public Pose2d() {
044    m_translation = Translation2d.kZero;
045    m_rotation = Rotation2d.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 Pose2d(Translation2d translation, Rotation2d rotation) {
056    m_translation = translation;
057    m_rotation = rotation;
058  }
059
060  /**
061   * Constructs a pose with x and y translations instead of a separate Translation2d.
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 rotation The rotational component of the pose.
066   */
067  public Pose2d(double x, double y, Rotation2d rotation) {
068    m_translation = new Translation2d(x, y);
069    m_rotation = rotation;
070  }
071
072  /**
073   * Constructs a pose with x and y translations instead of a separate Translation2d. The X and Y
074   * translations will be converted to and tracked as meters.
075   *
076   * @param x The x component of the translational component of the pose.
077   * @param y The y component of the translational component of the pose.
078   * @param rotation The rotational component of the pose.
079   */
080  public Pose2d(Distance x, Distance y, Rotation2d rotation) {
081    this(x.in(Meters), y.in(Meters), rotation);
082  }
083
084  /**
085   * Constructs a pose 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 Pose2d(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  /**
099   * Transforms the pose by the given transformation and returns the new transformed pose.
100   *
101   * <pre>
102   * [x_new]    [cos, -sin, 0][transform.x]
103   * [y_new] += [sin,  cos, 0][transform.y]
104   * [t_new]    [  0,    0, 1][transform.t]
105   * </pre>
106   *
107   * @param other The transform to transform the pose by.
108   * @return The transformed pose.
109   */
110  public Pose2d plus(Transform2d other) {
111    return transformBy(other);
112  }
113
114  /**
115   * Returns the Transform2d that maps the one pose to another.
116   *
117   * @param other The initial pose of the transformation.
118   * @return The transform that maps the other pose to the current pose.
119   */
120  public Transform2d minus(Pose2d other) {
121    final var pose = this.relativeTo(other);
122    return new Transform2d(pose.getTranslation(), pose.getRotation());
123  }
124
125  /**
126   * Returns the translation component of the transformation.
127   *
128   * @return The translational component of the pose.
129   */
130  public Translation2d getTranslation() {
131    return m_translation;
132  }
133
134  /**
135   * Returns the X component of the pose's translation.
136   *
137   * @return The x component of the pose's translation.
138   */
139  public double getX() {
140    return m_translation.getX();
141  }
142
143  /**
144   * Returns the Y component of the pose's translation.
145   *
146   * @return The y component of the pose's translation.
147   */
148  public double getY() {
149    return m_translation.getY();
150  }
151
152  /**
153   * Returns the X component of the pose's translation in a measure.
154   *
155   * @return The x component of the pose's translation in a measure.
156   */
157  public Distance getMeasureX() {
158    return m_translation.getMeasureX();
159  }
160
161  /**
162   * Returns the Y component of the pose's translation in a measure.
163   *
164   * @return The y component of the pose's translation in a measure.
165   */
166  public Distance getMeasureY() {
167    return m_translation.getMeasureY();
168  }
169
170  /**
171   * Returns the rotational component of the transformation.
172   *
173   * @return The rotational component of the pose.
174   */
175  public Rotation2d getRotation() {
176    return m_rotation;
177  }
178
179  /**
180   * Multiplies the current pose by a scalar.
181   *
182   * @param scalar The scalar.
183   * @return The new scaled Pose2d.
184   */
185  public Pose2d times(double scalar) {
186    return new Pose2d(m_translation.times(scalar), m_rotation.times(scalar));
187  }
188
189  /**
190   * Divides the current pose by a scalar.
191   *
192   * @param scalar The scalar.
193   * @return The new scaled Pose2d.
194   */
195  public Pose2d div(double scalar) {
196    return times(1.0 / scalar);
197  }
198
199  /**
200   * Rotates the pose around the origin and returns the new pose.
201   *
202   * @param other The rotation to transform the pose by.
203   * @return The transformed pose.
204   */
205  public Pose2d rotateBy(Rotation2d other) {
206    return new Pose2d(m_translation.rotateBy(other), m_rotation.rotateBy(other));
207  }
208
209  /**
210   * Transforms the pose by the given transformation and returns the new pose. See + operator for
211   * the matrix multiplication performed.
212   *
213   * @param other The transform to transform the pose by.
214   * @return The transformed pose.
215   */
216  public Pose2d transformBy(Transform2d other) {
217    return new Pose2d(
218        m_translation.plus(other.getTranslation().rotateBy(m_rotation)),
219        other.getRotation().rotateBy(m_rotation));
220  }
221
222  /**
223   * Returns the current pose relative to the given pose.
224   *
225   * <p>This function can often be used for trajectory tracking or pose stabilization algorithms to
226   * get the error between the reference and the current pose.
227   *
228   * @param other The pose that is the origin of the new coordinate frame that the current pose will
229   *     be converted into.
230   * @return The current pose relative to the new origin pose.
231   */
232  public Pose2d relativeTo(Pose2d other) {
233    var transform = new Transform2d(other, this);
234    return new Pose2d(transform.getTranslation(), transform.getRotation());
235  }
236
237  /**
238   * Rotates the current pose around a point in 2D space.
239   *
240   * @param point The point in 2D space to rotate around.
241   * @param rot The rotation to rotate the pose by.
242   * @return The new rotated pose.
243   */
244  public Pose2d rotateAround(Translation2d point, Rotation2d rot) {
245    return new Pose2d(m_translation.rotateAround(point, rot), m_rotation.rotateBy(rot));
246  }
247
248  /**
249   * Returns an affine transformation matrix representation of this pose.
250   *
251   * @return An affine transformation matrix representation of this pose.
252   */
253  public Matrix<N3, N3> toMatrix() {
254    var vec = m_translation.toVector();
255    var mat = m_rotation.toMatrix();
256    return MatBuilder.fill(
257        Nat.N3(),
258        Nat.N3(),
259        mat.get(0, 0),
260        mat.get(0, 1),
261        vec.get(0),
262        mat.get(1, 0),
263        mat.get(1, 1),
264        vec.get(1),
265        0.0,
266        0.0,
267        1.0);
268  }
269
270  /**
271   * Returns the nearest Pose2d from a collection of poses. If two or more poses in the collection
272   * have the same distance from this pose, return the one with the closest rotation component.
273   *
274   * @param poses The collection of poses to find the nearest.
275   * @return The nearest Pose2d from the collection.
276   */
277  public Pose2d nearest(Collection<Pose2d> poses) {
278    return Collections.min(
279        poses,
280        Comparator.comparing(
281                (Pose2d other) -> this.getTranslation().getDistance(other.getTranslation()))
282            .thenComparing(
283                (Pose2d other) ->
284                    Math.abs(this.getRotation().minus(other.getRotation()).getRadians())));
285  }
286
287  @Override
288  public String toString() {
289    return String.format("Pose2d(%s, %s)", m_translation, m_rotation);
290  }
291
292  /**
293   * Checks equality between this Pose2d and another object.
294   *
295   * @param obj The other object.
296   * @return Whether the two objects are equal or not.
297   */
298  @Override
299  public boolean equals(Object obj) {
300    return obj instanceof Pose2d pose
301        && m_translation.equals(pose.m_translation)
302        && m_rotation.equals(pose.m_rotation);
303  }
304
305  @Override
306  public int hashCode() {
307    return Objects.hash(m_translation, m_rotation);
308  }
309
310  @Override
311  public Pose2d interpolate(Pose2d endValue, double t) {
312    if (t < 0) {
313      return this;
314    } else if (t >= 1) {
315      return endValue;
316    } else {
317      var twist = endValue.minus(this).log();
318      var scaledTwist = new Twist2d(twist.dx * t, twist.dy * t, twist.dtheta * t);
319      return this.plus(scaledTwist.exp());
320    }
321  }
322
323  /** Pose2d protobuf for serialization. */
324  public static final Pose2dProto proto = new Pose2dProto();
325
326  /** Pose2d struct for serialization. */
327  public static final Pose2dStruct struct = new Pose2dStruct();
328}