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