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