001// Copyright (c) Choreo contributors
002
003package choreo.trajectory;
004
005import choreo.util.ChoreoAllianceFlipUtil;
006import edu.wpi.first.math.MathUtil;
007import edu.wpi.first.math.Matrix;
008import edu.wpi.first.math.VecBuilder;
009import edu.wpi.first.math.geometry.Pose2d;
010import edu.wpi.first.math.geometry.Rotation2d;
011import edu.wpi.first.math.kinematics.ChassisSpeeds;
012import edu.wpi.first.math.numbers.N1;
013import edu.wpi.first.math.numbers.N2;
014import edu.wpi.first.math.numbers.N6;
015import edu.wpi.first.math.system.NumericalIntegration;
016import edu.wpi.first.util.struct.Struct;
017import java.nio.ByteBuffer;
018import java.util.function.BiFunction;
019
020/** A single differential drive robot sample in a Trajectory. */
021public class DifferentialSample implements TrajectorySample<DifferentialSample> {
022  /** The timestamp of this sample relative to the beginning of the trajectory. */
023  public final double t;
024
025  /** The X position of the sample relative to the blue alliance wall origin in meters. */
026  public final double x;
027
028  /** The Y position of the sample relative to the blue alliance wall origin in meters. */
029  public final double y;
030
031  /** The heading of the sample in radians, with 0 being in the +X direction. */
032  public final double heading;
033
034  /** The velocity of the left side in m/s. */
035  public final double vl;
036
037  /** The velocity of the right side in m/s. */
038  public final double vr;
039
040  /** The chassis angular velocity in rad/s. */
041  public final double omega;
042
043  /** The acceleration of the left side in m/s². */
044  public final double al;
045
046  /** The acceleration of the right side in m/s². */
047  public final double ar;
048
049  /** The force of the left side in Newtons. */
050  public final double fl;
051
052  /** The force of the right side in Newtons. */
053  public final double fr;
054
055  /**
056   * Constructs a DifferentialSample with the specified parameters.
057   *
058   * @param timestamp The timestamp of this sample.
059   * @param x The X position of the sample in meters.
060   * @param y The Y position of the sample in meters.
061   * @param heading The heading of the sample in radians, with 0 being in the +X direction.
062   * @param vl The velocity of the left side in m/s.
063   * @param vr The velocity of the right side in m/s.
064   * @param omega The chassis angular velocity in rad/s.
065   * @param al The acceleration of the left side in m/s².
066   * @param ar The acceleration of the right side in m/s².
067   * @param fl The force of the left side in Newtons.
068   * @param fr The force of the right side in Newtons.
069   */
070  public DifferentialSample(
071      double timestamp,
072      double x,
073      double y,
074      double heading,
075      double vl,
076      double vr,
077      double omega,
078      double al,
079      double ar,
080      double fl,
081      double fr) {
082    this.t = timestamp;
083    this.x = x;
084    this.y = y;
085    this.heading = heading;
086    this.vl = vl;
087    this.vr = vr;
088    this.omega = omega;
089    this.al = al;
090    this.ar = ar;
091    this.fl = fl;
092    this.fr = fr;
093  }
094
095  @Override
096  public double getTimestamp() {
097    return t;
098  }
099
100  @Override
101  public Pose2d getPose() {
102    return new Pose2d(x, y, Rotation2d.fromRadians(heading));
103  }
104
105  /**
106   * Returns the field-relative chassis speeds of this sample.
107   *
108   * @return the field-relative chassis speeds of this sample.
109   * @see edu.wpi.first.math.kinematics.DifferentialDriveKinematics#toChassisSpeeds
110   */
111  @Override
112  public ChassisSpeeds getChassisSpeeds() {
113    return new ChassisSpeeds((vl + vr) / 2, 0, omega);
114  }
115
116  @Override
117  public DifferentialSample interpolate(DifferentialSample endValue, double timestamp) {
118    double scale = (timestamp - this.t) / (endValue.t - this.t);
119
120    // Integrate the acceleration to get the rest of the state, since linearly
121    // interpolating the state gives an inaccurate result if the accelerations are changing between
122    // states
123    Matrix<N6, N1> initialState = VecBuilder.fill(x, y, heading, vl, vr, omega);
124
125    double width = (vr - vl) / omega;
126    BiFunction<Matrix<N6, N1>, Matrix<N2, N1>, Matrix<N6, N1>> f =
127        (state, input) -> {
128          //  state =  [x, y, θ, vₗ, vᵣ, ω]
129          //  input =  [aₗ, aᵣ]
130          //
131          //  v = (vₗ + vᵣ)/2
132          //  ω = (vᵣ − vₗ)/width
133          //  α = (aᵣ − aₗ)/width
134          //
135          //  ẋ = v cosθ
136          //  ẏ = v sinθ
137          //  θ̇ = ω
138          //  v̇ₗ = aₗ
139          //  v̇ᵣ = aᵣ
140          //  ω̇ = α
141          var θ = state.get(2, 0);
142          var vl = state.get(3, 0);
143          var vr = state.get(4, 0);
144          var ω = state.get(5, 0);
145          var al = input.get(0, 0);
146          var ar = input.get(1, 0);
147          var v = (vl + vr) / 2;
148          var α = (ar - al) / width;
149          return VecBuilder.fill(v * Math.cos(θ), v * Math.sin(θ), ω, al, ar, α);
150        };
151
152    double τ = timestamp - this.t;
153    var sample = NumericalIntegration.rkdp(f, initialState, VecBuilder.fill(al, ar), τ);
154
155    return new DifferentialSample(
156        MathUtil.interpolate(this.t, endValue.t, scale),
157        sample.get(0, 0),
158        sample.get(1, 0),
159        sample.get(2, 0),
160        sample.get(3, 0),
161        sample.get(4, 0),
162        sample.get(5, 0),
163        this.al,
164        this.ar,
165        MathUtil.interpolate(this.fl, endValue.fl, scale),
166        MathUtil.interpolate(this.fr, endValue.fr, scale));
167  }
168
169  public DifferentialSample flipped() {
170    return switch (ChoreoAllianceFlipUtil.getFlipper()) {
171      case MIRRORED ->
172          new DifferentialSample(
173              t,
174              ChoreoAllianceFlipUtil.flipX(x),
175              ChoreoAllianceFlipUtil.flipY(y), // No-op for mirroring
176              ChoreoAllianceFlipUtil.flipHeading(heading),
177              vr,
178              vl,
179              -omega,
180              ar,
181              al,
182              fr,
183              fl);
184      case ROTATE_AROUND ->
185          new DifferentialSample(
186              t,
187              ChoreoAllianceFlipUtil.flipX(x),
188              ChoreoAllianceFlipUtil.flipY(y),
189              ChoreoAllianceFlipUtil.flipHeading(heading),
190              vl,
191              vr,
192              omega,
193              al,
194              ar,
195              fl,
196              fr);
197    };
198  }
199
200  public DifferentialSample offsetBy(double timestampOffset) {
201    return new DifferentialSample(
202        t + timestampOffset, x, y, heading, vl, vr, omega, al, ar, fl, fr);
203  }
204
205  /** The struct for the DifferentialSample class. */
206  public static final Struct<DifferentialSample> struct = new DifferentialSampleStruct();
207
208  private static final class DifferentialSampleStruct implements Struct<DifferentialSample> {
209    @Override
210    public Class<DifferentialSample> getTypeClass() {
211      return DifferentialSample.class;
212    }
213
214    @Override
215    public String getTypeName() {
216      return "DifferentialSample";
217    }
218
219    @Override
220    public int getSize() {
221      return Struct.kSizeDouble * 10;
222    }
223
224    @Override
225    public String getSchema() {
226      return "double timestamp;"
227          + "Pose2d pose;"
228          + "double vl;"
229          + "double vr;"
230          + "double omega;"
231          + "double al;"
232          + "double ar;"
233          + "double fl;"
234          + "double fr;";
235    }
236
237    @Override
238    public Struct<?>[] getNested() {
239      return new Struct<?>[] {Pose2d.struct};
240    }
241
242    @Override
243    public DifferentialSample unpack(ByteBuffer bb) {
244      return new DifferentialSample(
245          bb.getDouble(),
246          bb.getDouble(),
247          bb.getDouble(),
248          bb.getDouble(),
249          bb.getDouble(),
250          bb.getDouble(),
251          bb.getDouble(),
252          bb.getDouble(),
253          bb.getDouble(),
254          bb.getDouble(),
255          bb.getDouble());
256    }
257
258    @Override
259    public void pack(ByteBuffer bb, DifferentialSample value) {
260      bb.putDouble(value.t);
261      bb.putDouble(value.x);
262      bb.putDouble(value.y);
263      bb.putDouble(value.heading);
264      bb.putDouble(value.vl);
265      bb.putDouble(value.vr);
266      bb.putDouble(value.omega);
267      bb.putDouble(value.al);
268      bb.putDouble(value.ar);
269      bb.putDouble(value.fl);
270      bb.putDouble(value.fr);
271    }
272  }
273
274  @Override
275  public boolean equals(Object obj) {
276    if (!(obj instanceof DifferentialSample)) {
277      return false;
278    }
279
280    var other = (DifferentialSample) obj;
281    return this.t == other.t
282        && this.x == other.x
283        && this.y == other.y
284        && this.heading == other.heading
285        && this.vl == other.vl
286        && this.vr == other.vr
287        && this.omega == other.omega
288        && this.al == other.al
289        && this.ar == other.ar
290        && this.fl == other.fl
291        && this.fr == other.fr;
292  }
293}