blob: 00b37f68c9172c068212cdaa65258b76f750dd8d [file] [log] [blame]
Austin Schuhec7f06d2019-01-04 07:47:15 +11001#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_TRAJECTORY_H_
2#define FRC971_CONTROL_LOOPS_DRIVETRAIN_TRAJECTORY_H_
3
4#include <chrono>
5
James Kuszmaul75a18c52021-03-10 22:02:07 -08006#include "aos/flatbuffers.h"
Austin Schuhec7f06d2019-01-04 07:47:15 +11007#include "Eigen/Dense"
8#include "frc971/control_loops/drivetrain/distance_spline.h"
9#include "frc971/control_loops/drivetrain/drivetrain_config.h"
James Kuszmaul75a18c52021-03-10 22:02:07 -080010#include "frc971/control_loops/drivetrain/trajectory_generated.h"
11#include "frc971/control_loops/drivetrain/spline_goal_generated.h"
Austin Schuhec7f06d2019-01-04 07:47:15 +110012#include "frc971/control_loops/hybrid_state_feedback_loop.h"
13#include "frc971/control_loops/runge_kutta.h"
14#include "frc971/control_loops/state_feedback_loop.h"
15
16namespace frc971 {
17namespace control_loops {
18namespace drivetrain {
19
20template <typename F>
21double IntegrateAccelForDistance(const F &fn, double v, double x, double dx) {
22 // Use a trick from
23 // https://www.johndcook.com/blog/2012/02/21/care-and-treatment-of-singularities/
24 const double a0 = fn(x, v);
25
26 return (RungeKutta(
27 [&fn, &a0](double t, double y) {
28 // Since we know that a0 == a(0) and that they are asymtotically
29 // the same at 0, we know that the limit is 0 at 0. This is
30 // true because when starting from a stop, under sane
31 // accelerations, we can assume that we will start with a
32 // constant acceleration. So, hard-code it.
James Kuszmaul75a18c52021-03-10 22:02:07 -080033 if (std::abs(y) < 1e-6) {
Austin Schuhec7f06d2019-01-04 07:47:15 +110034 return 0.0;
35 }
36 return (fn(t, y) - a0) / y;
37 },
38 v, x, dx) -
39 v) +
James Kuszmaul75a18c52021-03-10 22:02:07 -080040 std::sqrt(2.0 * a0 * dx + v * v);
Austin Schuhec7f06d2019-01-04 07:47:15 +110041}
42
James Kuszmaul75a18c52021-03-10 22:02:07 -080043class BaseTrajectory {
Austin Schuhec7f06d2019-01-04 07:47:15 +110044 public:
James Kuszmaul75a18c52021-03-10 22:02:07 -080045 BaseTrajectory(
46 const flatbuffers::Vector<flatbuffers::Offset<Constraint>> *constraints,
47 const DrivetrainConfig<double> &config);
48
49 virtual ~BaseTrajectory() = default;
Austin Schuhec7f06d2019-01-04 07:47:15 +110050
James Kuszmaulea314d92019-02-18 19:45:06 -080051 // Returns the friction-constrained velocity limit at a given distance along
52 // the path. At the returned velocity, one or both wheels will be on the edge
53 // of slipping.
54 // There are some very disorganized thoughts on the math here and in some of
55 // the other functions in spline_math.tex.
56 double LateralVelocityCurvature(double distance) const;
57
58 // Returns the range of allowable longitudinal accelerations for the center of
59 // the robot at a particular distance (x) along the path and velocity (v).
60 // min_accel and max_accel correspodn to the min/max accelerations that can be
61 // achieved without breaking friction limits on one or both wheels.
62 // If max_accel < min_accel, that implies that v is too high for there to be
63 // any valid acceleration. FrictionLngAccelLimits(x,
64 // LateralVelocityCurvature(x), &min_accel, &max_accel) should result in
65 // min_accel == max_accel.
66 void FrictionLngAccelLimits(double x, double v, double *min_accel,
67 double *max_accel) const;
68
James Kuszmaul75a18c52021-03-10 22:02:07 -080069 // Returns the forwards/backwards acceleration for a distance along the spline
70 // taking into account the lateral acceleration, longitudinal acceleration,
71 // and voltage limits.
72 double BestAcceleration(double x, double v, bool backwards) const;
73 double BackwardAcceleration(double x, double v) const {
74 return BestAcceleration(x, v, true);
75 }
76 double ForwardAcceleration(double x, double v) const {
77 return BestAcceleration(x, v, false);
78 }
79
80 const StateFeedbackLoop<2, 2, 2, double, StateFeedbackHybridPlant<2, 2, 2>,
81 HybridKalman<2, 2, 2>>
82 &velocity_drivetrain() const {
83 return *velocity_drivetrain_;
84 }
85
86 // Returns K1 and K2.
87 // K2 * d^x/dt^2 + K1 (dx/dt)^2 = A * K2 * dx/dt + B * U
88 const Eigen::Matrix<double, 2, 1> K1(double current_ddtheta) const;
89 const Eigen::Matrix<double, 2, 1> K2(double current_dtheta) const;
90
91 // Computes K3, K4, and K5 for the provided distance.
92 // K5 a + K3 v^2 + K4 v = U
93 void K345(const double x, Eigen::Matrix<double, 2, 1> *K3,
94 Eigen::Matrix<double, 2, 1> *K4,
95 Eigen::Matrix<double, 2, 1> *K5) const;
96
97 virtual const DistanceSpline &spline() const = 0;
98
99 // Returns the length of the path in meters.
100 double length() const { return spline().length(); }
101
102 // Returns whether a state represents a state at the end of the spline.
103 bool is_at_end(Eigen::Matrix<double, 2, 1> state) const {
104 return state(0) > length() - 1e-4;
105 }
106
107 // Returns true if the state is invalid or unreasonable in some way.
108 bool state_is_faulted(Eigen::Matrix<double, 2, 1> state) const {
109 // Consider things faulted if the current velocity implies we are going
110 // backwards or if any infinities/NaNs have crept in.
111 return state(1) < 0 || !state.allFinite();
112 }
113
114 virtual float plan_velocity(size_t index) const = 0;
115 virtual size_t distance_plan_size() const = 0;
116
117 // Sets the plan longitudinal acceleration limit
118 void set_longitudinal_acceleration(double longitudinal_acceleration) {
119 longitudinal_acceleration_ = longitudinal_acceleration;
120 }
121 // Sets the plan lateral acceleration limit
122 void set_lateral_acceleration(double lateral_acceleration) {
123 lateral_acceleration_ = lateral_acceleration;
124 }
125 // Sets the voltage limit
126 void set_voltage_limit(double voltage_limit) {
127 voltage_limit_ = voltage_limit;
128 }
129
130 float max_lateral_accel() const { return lateral_acceleration_; }
131
132 float max_longitudinal_accel() const { return longitudinal_acceleration_; }
133
134 float max_voltage() const { return voltage_limit_; }
135
136 // Return the next position, velocity, acceleration based on the current
137 // state. Updates the passed in state for the next iteration.
138 Eigen::Matrix<double, 3, 1> GetNextXVA(
139 std::chrono::nanoseconds dt, Eigen::Matrix<double, 2, 1> *state) const;
140
141 // Returns the distance for an index in the plan.
142 double Distance(int index) const {
143 return static_cast<double>(index) * length() /
144 static_cast<double>(distance_plan_size() - 1);
145 }
146
147 virtual fb::SegmentConstraint plan_constraint(size_t index) const = 0;
148
149 // Returns the feed forwards position, velocity, acceleration for an explicit
150 // distance.
151 Eigen::Matrix<double, 3, 1> FFAcceleration(double distance) const;
152
153 // Returns the feed forwards voltage for an explicit distance.
154 Eigen::Matrix<double, 2, 1> FFVoltage(double distance) const;
155
156 // Computes alpha for a distance.
157 size_t DistanceToSegment(double distance) const {
158 return std::max(
159 static_cast<size_t>(0),
160 std::min(distance_plan_size() - 1,
161 static_cast<size_t>(std::floor(distance / length() *
162 (distance_plan_size() - 1)))));
163 }
164
165 // Returns the goal state as a function of path distance, velocity.
166 const ::Eigen::Matrix<double, 5, 1> GoalState(double distance,
167 double velocity) const;
168
169 protected:
170 double robot_radius_l() const { return robot_radius_l_; }
171 double robot_radius_r() const { return robot_radius_r_; }
172
173 private:
174 static float ConstraintValue(
175 const flatbuffers::Vector<flatbuffers::Offset<Constraint>> *constraints,
176 ConstraintType type);
177
178 std::unique_ptr<
179 StateFeedbackLoop<2, 2, 2, double, StateFeedbackHybridPlant<2, 2, 2>,
180 HybridKalman<2, 2, 2>>>
181 velocity_drivetrain_;
182
183 const DrivetrainConfig<double> config_;
184
185 // Robot radiuses.
186 const double robot_radius_l_;
187 const double robot_radius_r_;
188 float lateral_acceleration_ = 3.0;
189 float longitudinal_acceleration_ = 2.0;
190 float voltage_limit_ = 12.0;
191};
192
193// A wrapper around the Trajectory flatbuffer to allow for controlling to a
194// spline using a pre-generated trajectory.
195class FinishedTrajectory : public BaseTrajectory {
196 public:
197 // Note: The lifetime of the supplied buffer is assumed to be greater than
198 // that of this object.
199 explicit FinishedTrajectory(const DrivetrainConfig<double> &config,
200 const fb::Trajectory *buffer);
201
202 virtual ~FinishedTrajectory() = default;
203
204 // Takes the 5-element state that is [x, y, theta, v_left, v_right] and
205 // converts it to a path-relative state, using distance as a linearization
206 // point (i.e., distance should be roughly equal to the actual distance along
207 // the path).
208 Eigen::Matrix<double, 5, 1> StateToPathRelativeState(
209 double distance, const Eigen::Matrix<double, 5, 1> &state) const;
210
211 // Retrieves the gain matrix K for a given distance along the path.
212 Eigen::Matrix<double, 2, 5> GainForDistance(double distance) const;
213
214 size_t distance_plan_size() const override;
215 float plan_velocity(size_t index) const override;
216 fb::SegmentConstraint plan_constraint(size_t index) const override;
217
218 bool drive_spline_backwards() const {
219 return trajectory().drive_spline_backwards();
220 }
221
222 int spline_handle() const { return trajectory().handle(); }
223 const fb::Trajectory &trajectory() const { return *buffer_; }
224
225 private:
226 const DistanceSpline &spline() const override { return spline_; }
227 const fb::Trajectory *buffer_;
228 const DistanceSpline spline_;
229};
230
231// Class to handle plannign a trajectory and producing a flatbuffer containing
232// all the information required to create a FinishedTrajectory;
233class Trajectory : public BaseTrajectory {
234 public:
235 Trajectory(const SplineGoal &spline_goal,
236 const DrivetrainConfig<double> &config);
237 Trajectory(
238 DistanceSpline &&spline, const DrivetrainConfig<double> &config,
239 const flatbuffers::Vector<flatbuffers::Offset<Constraint>> *constraints,
240 int spline_idx = 0, double vmax = 10.0, int num_distance = 0);
241
242 virtual ~Trajectory() = default;
243
244 std::vector<Eigen::Matrix<double, 3, 1>> PlanXVA(
245 std::chrono::nanoseconds dt);
246
James Kuszmaulea314d92019-02-18 19:45:06 -0800247 enum class VoltageLimit {
248 kConservative,
249 kAggressive,
250 };
251
252 // Calculates the maximum voltage at which we *can* track the path. In some
253 // cases there will be two ranges of feasible velocities for traversing the
254 // path--in such a situation, from zero to velocity A we will be able to track
255 // the path, from velocity A to B we can't, from B to C we can and above C we
256 // can't. If limit_type = kConservative, we return A; if limit_type =
257 // kAggressive, we return C. We currently just use the kConservative limit
258 // because that way we can guarantee that all velocities between zero and A
259 // are allowable and don't have to handle a more complicated planning problem.
260 // constraint_voltages will be populated by the only wheel voltages that are
261 // valid at the returned limit.
262 double VoltageVelocityLimit(
263 double distance, VoltageLimit limit_type,
264 Eigen::Matrix<double, 2, 1> *constraint_voltages = nullptr) const;
Austin Schuhec7f06d2019-01-04 07:47:15 +1100265
Austin Schuh5b9e9c22019-01-07 15:44:06 -0800266 // Limits the velocity in the specified segment to the max velocity.
267 void LimitVelocity(double starting_distance, double ending_distance,
268 double max_velocity);
269
Austin Schuhec7f06d2019-01-04 07:47:15 +1100270 // Runs the lateral acceleration (curvature) pass on the plan.
271 void LateralAccelPass();
James Kuszmaulea314d92019-02-18 19:45:06 -0800272 void VoltageFeasibilityPass(VoltageLimit limit_type);
Austin Schuhec7f06d2019-01-04 07:47:15 +1100273
274 // Runs the forwards pass, setting the starting velocity to 0 m/s
275 void ForwardPass();
276
Austin Schuhec7f06d2019-01-04 07:47:15 +1100277 // Runs the forwards pass, setting the ending velocity to 0 m/s
278 void BackwardPass();
279
280 // Runs all the planning passes.
281 void Plan() {
James Kuszmaulea314d92019-02-18 19:45:06 -0800282 VoltageFeasibilityPass(VoltageLimit::kConservative);
Austin Schuhec7f06d2019-01-04 07:47:15 +1100283 LateralAccelPass();
284 ForwardPass();
285 BackwardPass();
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700286 CalculatePathGains();
Austin Schuhec7f06d2019-01-04 07:47:15 +1100287 }
288
Austin Schuhec7f06d2019-01-04 07:47:15 +1100289 // Returns a list of the distances. Mostly useful for plotting.
James Kuszmaul75a18c52021-03-10 22:02:07 -0800290 const std::vector<double> Distances() const;
Austin Schuhec7f06d2019-01-04 07:47:15 +1100291 // Returns the distance for an index in the plan.
292 double Distance(int index) const {
293 return static_cast<double>(index) * length() /
294 static_cast<double>(plan_.size() - 1);
295 }
296
James Kuszmaul75a18c52021-03-10 22:02:07 -0800297 const std::vector<fb::SegmentConstraint> &plan_segment_type() const {
Austin Schuhe73a9052019-01-07 12:16:17 -0800298 return plan_segment_type_;
299 }
300
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700301 // The controller represented by these functions uses a discrete-time,
302 // finite-horizon LQR with states that are relative to the predicted path
303 // of the robot to produce a gain to be used on the error.
304 // The controller does not currently account for saturation, but is defined
305 // in a way that would make accounting for saturation feasible.
306 // This controller uses a state of:
307 // distance along path
308 // distance lateral to path (positive when robot is to the left of the path).
309 // heading relative to path (positive if robot pointed to left).
310 // v_left (speed of left side of robot)
311 // v_right (speed of right side of robot).
312
313 // Retrieve the continuous-time A/B matrices for the path-relative system
314 // at the given distance along the path. Performs all linearizations about
315 // the nominal velocity that the robot should be following at that point
316 // along the path.
317 void PathRelativeContinuousSystem(double distance,
318 Eigen::Matrix<double, 5, 5> *A,
319 Eigen::Matrix<double, 5, 2> *B);
320 // Retrieve the continuous-time A/B matrices for the path-relative system
321 // given the current path-relative state, as defined above.
322 void PathRelativeContinuousSystem(const Eigen::Matrix<double, 5, 1> &X,
323 Eigen::Matrix<double, 5, 5> *A,
324 Eigen::Matrix<double, 5, 2> *B);
325
326 // Takes the 5-element state that is [x, y, theta, v_left, v_right] and
327 // converts it to a path-relative state, using distance as a linearization
328 // point (i.e., distance should be roughly equal to the actual distance along
329 // the path).
330 Eigen::Matrix<double, 5, 1> StateToPathRelativeState(
331 double distance, const Eigen::Matrix<double, 5, 1> &state);
332
333 // Estimates the current distance along the path, given the current expected
334 // distance and the [x, y, theta, v_left, v_right] state.
335 double EstimateDistanceAlongPath(double nominal_distance,
336 const Eigen::Matrix<double, 5, 1> &state);
337
338 // Calculates all the gains for each point along the planned trajectory.
339 // Only called directly in tests; this is normally a part of the planning
340 // phase, and is a relatively expensive operation.
341 void CalculatePathGains();
342
James Kuszmaul75a18c52021-03-10 22:02:07 -0800343 flatbuffers::Offset<fb::Trajectory> Serialize(
344 flatbuffers::FlatBufferBuilder *fbb) const;
345
346 const std::vector<double> plan() const { return plan_; }
347
348 const DistanceSpline &spline() const override { return spline_; }
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700349
Austin Schuhec7f06d2019-01-04 07:47:15 +1100350 private:
James Kuszmaul75a18c52021-03-10 22:02:07 -0800351
352 float plan_velocity(size_t index) const override {
353 return plan_[index];
354 }
355 size_t distance_plan_size() const override { return plan_.size(); }
356
357 fb::SegmentConstraint plan_constraint(size_t index) const override {
358 return plan_segment_type_[index];
Austin Schuhe73a9052019-01-07 12:16:17 -0800359 }
Austin Schuhec7f06d2019-01-04 07:47:15 +1100360
James Kuszmaul75a18c52021-03-10 22:02:07 -0800361 const int spline_idx_;
Austin Schuhec7f06d2019-01-04 07:47:15 +1100362
363 // The spline we are planning for.
James Kuszmaul75a18c52021-03-10 22:02:07 -0800364 const DistanceSpline spline_;
Austin Schuhec7f06d2019-01-04 07:47:15 +1100365
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700366 const DrivetrainConfig<double> config_;
367
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700368 // Velocities in the plan (distance for each index is defined by Distance())
369 std::vector<double> plan_;
370 // Gain matrices to use for the path-relative state error at each stage in the
371 // plan Individual elements of the plan_gains_ vector are separated by
372 // config_.dt in time.
373 // The first value in the pair is the distance along the path corresponding to
374 // the gain matrix; the second value is the gain itself.
James Kuszmaul75a18c52021-03-10 22:02:07 -0800375 std::vector<std::pair<double, Eigen::Matrix<float, 2, 5>>> plan_gains_;
376 std::vector<fb::SegmentConstraint> plan_segment_type_;
377
378 bool drive_spline_backwards_ = false;
Austin Schuhec7f06d2019-01-04 07:47:15 +1100379};
380
381// Returns the continuous time dynamics given the [x, y, theta, vl, vr] state
382// and the [vl, vr] input voltage.
James Kuszmaul75a18c52021-03-10 22:02:07 -0800383inline Eigen::Matrix<double, 5, 1> ContinuousDynamics(
Austin Schuhec7f06d2019-01-04 07:47:15 +1100384 const StateFeedbackHybridPlant<2, 2, 2> &velocity_drivetrain,
James Kuszmaul75a18c52021-03-10 22:02:07 -0800385 const Eigen::Matrix<double, 2, 2> &Tlr_to_la,
386 const Eigen::Matrix<double, 5, 1> X,
387 const Eigen::Matrix<double, 2, 1> U) {
Austin Schuhec7f06d2019-01-04 07:47:15 +1100388 const auto &velocity = X.block<2, 1>(3, 0);
389 const double theta = X(2);
James Kuszmaul75a18c52021-03-10 22:02:07 -0800390 Eigen::Matrix<double, 2, 1> la = Tlr_to_la * velocity;
391 return (Eigen::Matrix<double, 5, 1>() << std::cos(theta) * la(0),
392 std::sin(theta) * la(0), la(1),
Austin Schuhec7f06d2019-01-04 07:47:15 +1100393 (velocity_drivetrain.coefficients().A_continuous * velocity +
394 velocity_drivetrain.coefficients().B_continuous * U))
395 .finished();
396}
397
398} // namespace drivetrain
399} // namespace control_loops
400} // namespace frc971
401
402#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_TRAJECTORY_H_