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 com.fasterxml.jackson.annotation.JsonAutoDetect;
010import com.fasterxml.jackson.annotation.JsonCreator;
011import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
012import com.fasterxml.jackson.annotation.JsonProperty;
013import edu.wpi.first.math.geometry.proto.Pose2dProto;
014import edu.wpi.first.math.geometry.struct.Pose2dStruct;
015import edu.wpi.first.math.interpolation.Interpolatable;
016import edu.wpi.first.units.Distance;
017import edu.wpi.first.units.Measure;
018import edu.wpi.first.util.protobuf.ProtobufSerializable;
019import edu.wpi.first.util.struct.StructSerializable;
020import java.util.Collections;
021import java.util.Comparator;
022import java.util.List;
023import java.util.Objects;
024
025/** Represents a 2D pose containing translational and rotational elements. */
026@JsonIgnoreProperties(ignoreUnknown = true)
027@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
028public class Pose2d implements Interpolatable<Pose2d>, ProtobufSerializable, StructSerializable {
029  private final Translation2d m_translation;
030  private final Rotation2d m_rotation;
031
032  /** Constructs a pose at the origin facing toward the positive X axis. */
033  public Pose2d() {
034    m_translation = new Translation2d();
035    m_rotation = new Rotation2d();
036  }
037
038  /**
039   * Constructs a pose with the specified translation and rotation.
040   *
041   * @param translation The translational component of the pose.
042   * @param rotation The rotational component of the pose.
043   */
044  @JsonCreator
045  public Pose2d(
046      @JsonProperty(required = true, value = "translation") Translation2d translation,
047      @JsonProperty(required = true, value = "rotation") Rotation2d rotation) {
048    m_translation = translation;
049    m_rotation = rotation;
050  }
051
052  /**
053   * Constructs a pose with x and y translations instead of a separate Translation2d.
054   *
055   * @param x The x component of the translational component of the pose.
056   * @param y The y component of the translational component of the pose.
057   * @param rotation The rotational component of the pose.
058   */
059  public Pose2d(double x, double y, Rotation2d rotation) {
060    m_translation = new Translation2d(x, y);
061    m_rotation = rotation;
062  }
063
064  /**
065   * Constructs a pose with x and y translations instead of a separate Translation2d. The X and Y
066   * translations will be converted to and tracked as meters.
067   *
068   * @param x The x component of the translational component of the pose.
069   * @param y The y component of the translational component of the pose.
070   * @param rotation The rotational component of the pose.
071   */
072  public Pose2d(Measure<Distance> x, Measure<Distance> y, Rotation2d rotation) {
073    this(x.in(Meters), y.in(Meters), rotation);
074  }
075
076  /**
077   * Transforms the pose by the given transformation and returns the new transformed pose.
078   *
079   * <pre>
080   * [x_new]    [cos, -sin, 0][transform.x]
081   * [y_new] += [sin,  cos, 0][transform.y]
082   * [t_new]    [  0,    0, 1][transform.t]
083   * </pre>
084   *
085   * @param other The transform to transform the pose by.
086   * @return The transformed pose.
087   */
088  public Pose2d plus(Transform2d other) {
089    return transformBy(other);
090  }
091
092  /**
093   * Returns the Transform2d that maps the one pose to another.
094   *
095   * @param other The initial pose of the transformation.
096   * @return The transform that maps the other pose to the current pose.
097   */
098  public Transform2d minus(Pose2d other) {
099    final var pose = this.relativeTo(other);
100    return new Transform2d(pose.getTranslation(), pose.getRotation());
101  }
102
103  /**
104   * Returns the translation component of the transformation.
105   *
106   * @return The translational component of the pose.
107   */
108  @JsonProperty
109  public Translation2d getTranslation() {
110    return m_translation;
111  }
112
113  /**
114   * Returns the X component of the pose's translation.
115   *
116   * @return The x component of the pose's translation.
117   */
118  public double getX() {
119    return m_translation.getX();
120  }
121
122  /**
123   * Returns the Y component of the pose's translation.
124   *
125   * @return The y component of the pose's translation.
126   */
127  public double getY() {
128    return m_translation.getY();
129  }
130
131  /**
132   * Returns the rotational component of the transformation.
133   *
134   * @return The rotational component of the pose.
135   */
136  @JsonProperty
137  public Rotation2d getRotation() {
138    return m_rotation;
139  }
140
141  /**
142   * Multiplies the current pose by a scalar.
143   *
144   * @param scalar The scalar.
145   * @return The new scaled Pose2d.
146   */
147  public Pose2d times(double scalar) {
148    return new Pose2d(m_translation.times(scalar), m_rotation.times(scalar));
149  }
150
151  /**
152   * Divides the current pose by a scalar.
153   *
154   * @param scalar The scalar.
155   * @return The new scaled Pose2d.
156   */
157  public Pose2d div(double scalar) {
158    return times(1.0 / scalar);
159  }
160
161  /**
162   * Rotates the pose around the origin and returns the new pose.
163   *
164   * @param other The rotation to transform the pose by.
165   * @return The transformed pose.
166   */
167  public Pose2d rotateBy(Rotation2d other) {
168    return new Pose2d(m_translation.rotateBy(other), m_rotation.rotateBy(other));
169  }
170
171  /**
172   * Transforms the pose by the given transformation and returns the new pose. See + operator for
173   * the matrix multiplication performed.
174   *
175   * @param other The transform to transform the pose by.
176   * @return The transformed pose.
177   */
178  public Pose2d transformBy(Transform2d other) {
179    return new Pose2d(
180        m_translation.plus(other.getTranslation().rotateBy(m_rotation)),
181        other.getRotation().plus(m_rotation));
182  }
183
184  /**
185   * Returns the current pose relative to the given pose.
186   *
187   * <p>This function can often be used for trajectory tracking or pose stabilization algorithms to
188   * get the error between the reference and the current pose.
189   *
190   * @param other The pose that is the origin of the new coordinate frame that the current pose will
191   *     be converted into.
192   * @return The current pose relative to the new origin pose.
193   */
194  public Pose2d relativeTo(Pose2d other) {
195    var transform = new Transform2d(other, this);
196    return new Pose2d(transform.getTranslation(), transform.getRotation());
197  }
198
199  /**
200   * Obtain a new Pose2d from a (constant curvature) velocity.
201   *
202   * <p>See <a href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">Controls
203   * Engineering in the FIRST Robotics Competition</a> section 10.2 "Pose exponential" for a
204   * derivation.
205   *
206   * <p>The twist is a change in pose in the robot's coordinate frame since the previous pose
207   * update. When the user runs exp() on the previous known field-relative pose with the argument
208   * being the twist, the user will receive the new field-relative pose.
209   *
210   * <p>"Exp" represents the pose exponential, which is solving a differential equation moving the
211   * pose forward in time.
212   *
213   * @param twist The change in pose in the robot's coordinate frame since the previous pose update.
214   *     For example, if a non-holonomic robot moves forward 0.01 meters and changes angle by 0.5
215   *     degrees since the previous pose update, the twist would be Twist2d(0.01, 0.0,
216   *     Units.degreesToRadians(0.5)).
217   * @return The new pose of the robot.
218   */
219  public Pose2d exp(Twist2d twist) {
220    double dx = twist.dx;
221    double dy = twist.dy;
222    double dtheta = twist.dtheta;
223
224    double sinTheta = Math.sin(dtheta);
225    double cosTheta = Math.cos(dtheta);
226
227    double s;
228    double c;
229    if (Math.abs(dtheta) < 1E-9) {
230      s = 1.0 - 1.0 / 6.0 * dtheta * dtheta;
231      c = 0.5 * dtheta;
232    } else {
233      s = sinTheta / dtheta;
234      c = (1 - cosTheta) / dtheta;
235    }
236    var transform =
237        new Transform2d(
238            new Translation2d(dx * s - dy * c, dx * c + dy * s),
239            new Rotation2d(cosTheta, sinTheta));
240
241    return this.plus(transform);
242  }
243
244  /**
245   * Returns a Twist2d that maps this pose to the end pose. If c is the output of {@code a.Log(b)},
246   * then {@code a.Exp(c)} would yield b.
247   *
248   * @param end The end pose for the transformation.
249   * @return The twist that maps this to end.
250   */
251  public Twist2d log(Pose2d end) {
252    final var transform = end.relativeTo(this);
253    final var dtheta = transform.getRotation().getRadians();
254    final var halfDtheta = dtheta / 2.0;
255
256    final var cosMinusOne = transform.getRotation().getCos() - 1;
257
258    double halfThetaByTanOfHalfDtheta;
259    if (Math.abs(cosMinusOne) < 1E-9) {
260      halfThetaByTanOfHalfDtheta = 1.0 - 1.0 / 12.0 * dtheta * dtheta;
261    } else {
262      halfThetaByTanOfHalfDtheta = -(halfDtheta * transform.getRotation().getSin()) / cosMinusOne;
263    }
264
265    Translation2d translationPart =
266        transform
267            .getTranslation()
268            .rotateBy(new Rotation2d(halfThetaByTanOfHalfDtheta, -halfDtheta))
269            .times(Math.hypot(halfThetaByTanOfHalfDtheta, halfDtheta));
270
271    return new Twist2d(translationPart.getX(), translationPart.getY(), dtheta);
272  }
273
274  /**
275   * Returns the nearest Pose2d from a list of poses. If two or more poses in the list have the same
276   * distance from this pose, return the one with the closest rotation component.
277   *
278   * @param poses The list of poses to find the nearest.
279   * @return The nearest Pose2d from the list.
280   */
281  public Pose2d nearest(List<Pose2d> poses) {
282    return Collections.min(
283        poses,
284        Comparator.comparing(
285                (Pose2d other) -> this.getTranslation().getDistance(other.getTranslation()))
286            .thenComparing(
287                (Pose2d other) ->
288                    Math.abs(this.getRotation().minus(other.getRotation()).getRadians())));
289  }
290
291  @Override
292  public String toString() {
293    return String.format("Pose2d(%s, %s)", m_translation, m_rotation);
294  }
295
296  /**
297   * Checks equality between this Pose2d and another object.
298   *
299   * @param obj The other object.
300   * @return Whether the two objects are equal or not.
301   */
302  @Override
303  public boolean equals(Object obj) {
304    if (obj instanceof Pose2d) {
305      return ((Pose2d) obj).m_translation.equals(m_translation)
306          && ((Pose2d) obj).m_rotation.equals(m_rotation);
307    }
308    return false;
309  }
310
311  @Override
312  public int hashCode() {
313    return Objects.hash(m_translation, m_rotation);
314  }
315
316  @Override
317  public Pose2d interpolate(Pose2d endValue, double t) {
318    if (t < 0) {
319      return this;
320    } else if (t >= 1) {
321      return endValue;
322    } else {
323      var twist = this.log(endValue);
324      var scaledTwist = new Twist2d(twist.dx * t, twist.dy * t, twist.dtheta * t);
325      return this.exp(scaledTwist);
326    }
327  }
328
329  /** Pose2d protobuf for serialization. */
330  public static final Pose2dProto proto = new Pose2dProto();
331
332  /** Pose2d struct for serialization. */
333  public static final Pose2dStruct struct = new Pose2dStruct();
334}