WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
LTVDifferentialDriveController.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <cmath>
8
9#include <Eigen/Core>
10#include <wpi/SymbolExports.h>
11#include <wpi/array.h>
12
13#include "frc/StateSpaceUtil.h"
15#include "frc/geometry/Pose2d.h"
18#include "units/length.h"
19#include "units/time.h"
20#include "units/velocity.h"
21
22namespace frc {
23
24/**
25 * The linear time-varying differential drive controller has a similar form to
26 * the LQR, but the model used to compute the controller gain is the nonlinear
27 * differential drive model linearized around the drivetrain's current state. We
28 * precompute gains for important places in our state-space, then interpolate
29 * between them with a lookup table to save computational resources.
30 *
31 * This controller has a flat hierarchy with pose and wheel velocity references
32 * and voltage outputs. This is different from a unicycle controller's nested
33 * hierarchy where the top-level controller has a pose reference and chassis
34 * velocity command outputs, and the low-level controller has wheel velocity
35 * references and voltage outputs. Flat hierarchies are easier to tune in one
36 * shot.
37 *
38 * See section 8.7 in Controls Engineering in FRC for a derivation of the
39 * control law we used shown in theorem 8.7.4.
40 */
42 public:
43 /**
44 * Constructs a linear time-varying differential drive controller.
45 *
46 * See
47 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
48 * for how to select the tolerances.
49 *
50 * @param plant The differential drive velocity plant.
51 * @param trackwidth The distance between the differential drive's left and
52 * right wheels.
53 * @param Qelems The maximum desired error tolerance for each state.
54 * @param Relems The maximum desired control effort for each input.
55 * @param dt Discretization timestep.
56 */
58 units::meter_t trackwidth,
59 const wpi::array<double, 5>& Qelems,
60 const wpi::array<double, 2>& Relems,
61 units::second_t dt)
62 : m_trackwidth{trackwidth},
63 m_A{plant.A()},
64 m_B{plant.B()},
65 m_Q{frc::MakeCostMatrix(Qelems)},
66 m_R{frc::MakeCostMatrix(Relems)},
67 m_dt{dt} {}
68
69 /**
70 * Move constructor.
71 */
73
74 /**
75 * Move assignment operator.
76 */
78 default;
79
80 /**
81 * Returns true if the pose error is within tolerance of the reference.
82 */
83 bool AtReference() const {
84 return std::abs(m_error(0)) < m_tolerance(0) &&
85 std::abs(m_error(1)) < m_tolerance(1) &&
86 std::abs(m_error(2)) < m_tolerance(2) &&
87 std::abs(m_error(3)) < m_tolerance(3) &&
88 std::abs(m_error(4)) < m_tolerance(4);
89 }
90
91 /**
92 * Sets the pose error which is considered tolerable for use with
93 * AtReference().
94 *
95 * @param poseTolerance Pose error which is tolerable.
96 * @param leftVelocityTolerance Left velocity error which is tolerable.
97 * @param rightVelocityTolerance Right velocity error which is tolerable.
98 */
99 void SetTolerance(const Pose2d& poseTolerance,
100 units::meters_per_second_t leftVelocityTolerance,
101 units::meters_per_second_t rightVelocityTolerance) {
102 m_tolerance = Eigen::Vector<double, 5>{
103 poseTolerance.X().value(), poseTolerance.Y().value(),
104 poseTolerance.Rotation().Radians().value(),
105 leftVelocityTolerance.value(), rightVelocityTolerance.value()};
106 }
107
108 /**
109 * Returns the left and right output voltages of the LTV controller.
110 *
111 * The reference pose, linear velocity, and angular velocity should come from
112 * a drivetrain trajectory.
113 *
114 * @param currentPose The current pose.
115 * @param leftVelocity The current left velocity.
116 * @param rightVelocity The current right velocity.
117 * @param poseRef The desired pose.
118 * @param leftVelocityRef The desired left velocity.
119 * @param rightVelocityRef The desired right velocity.
120 */
122 const Pose2d& currentPose, units::meters_per_second_t leftVelocity,
123 units::meters_per_second_t rightVelocity, const Pose2d& poseRef,
124 units::meters_per_second_t leftVelocityRef,
125 units::meters_per_second_t rightVelocityRef);
126
127 /**
128 * Returns the left and right output voltages of the LTV controller.
129 *
130 * The reference pose, linear velocity, and angular velocity should come from
131 * a drivetrain trajectory.
132 *
133 * @param currentPose The current pose.
134 * @param leftVelocity The left velocity.
135 * @param rightVelocity The right velocity.
136 * @param desiredState The desired pose, linear velocity, and angular velocity
137 * from a trajectory.
138 */
140 const Pose2d& currentPose, units::meters_per_second_t leftVelocity,
141 units::meters_per_second_t rightVelocity,
142 const Trajectory::State& desiredState) {
143 // v = (v_r + v_l) / 2 (1)
144 // w = (v_r - v_l) / (2r) (2)
145 // k = w / v (3)
146 //
147 // v_l = v - wr
148 // v_l = v - (vk)r
149 // v_l = v(1 - kr)
150 //
151 // v_r = v + wr
152 // v_r = v + (vk)r
153 // v_r = v(1 + kr)
154 return Calculate(
155 currentPose, leftVelocity, rightVelocity, desiredState.pose,
156 desiredState.velocity *
157 (1 - (desiredState.curvature / 1_rad * m_trackwidth / 2.0)),
158 desiredState.velocity *
159 (1 + (desiredState.curvature / 1_rad * m_trackwidth / 2.0)));
160 }
161
162 private:
163 units::meter_t m_trackwidth;
164
165 // Continuous velocity dynamics
166 Eigen::Matrix<double, 2, 2> m_A;
167 Eigen::Matrix<double, 2, 2> m_B;
168
169 // LQR cost matrices
170 Eigen::Matrix<double, 5, 5> m_Q;
171 Eigen::Matrix<double, 2, 2> m_R;
172
173 units::second_t m_dt;
174
175 Eigen::Vector<double, 5> m_error;
176 Eigen::Vector<double, 5> m_tolerance;
177};
178
179} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
The linear time-varying differential drive controller has a similar form to the LQR,...
Definition LTVDifferentialDriveController.h:41
bool AtReference() const
Returns true if the pose error is within tolerance of the reference.
Definition LTVDifferentialDriveController.h:83
LTVDifferentialDriveController(const frc::LinearSystem< 2, 2, 2 > &plant, units::meter_t trackwidth, const wpi::array< double, 5 > &Qelems, const wpi::array< double, 2 > &Relems, units::second_t dt)
Constructs a linear time-varying differential drive controller.
Definition LTVDifferentialDriveController.h:57
DifferentialDriveWheelVoltages Calculate(const Pose2d &currentPose, units::meters_per_second_t leftVelocity, units::meters_per_second_t rightVelocity, const Trajectory::State &desiredState)
Returns the left and right output voltages of the LTV controller.
Definition LTVDifferentialDriveController.h:139
LTVDifferentialDriveController & operator=(LTVDifferentialDriveController &&)=default
Move assignment operator.
DifferentialDriveWheelVoltages Calculate(const Pose2d &currentPose, units::meters_per_second_t leftVelocity, units::meters_per_second_t rightVelocity, const Pose2d &poseRef, units::meters_per_second_t leftVelocityRef, units::meters_per_second_t rightVelocityRef)
Returns the left and right output voltages of the LTV controller.
void SetTolerance(const Pose2d &poseTolerance, units::meters_per_second_t leftVelocityTolerance, units::meters_per_second_t rightVelocityTolerance)
Sets the pose error which is considered tolerable for use with AtReference().
Definition LTVDifferentialDriveController.h:99
LTVDifferentialDriveController(LTVDifferentialDriveController &&)=default
Move constructor.
A plant defined using state-space notation.
Definition LinearSystem.h:35
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
constexpr const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition Pose2d.h:128
constexpr units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition Pose2d.h:121
constexpr units::meter_t X() const
Returns the X component of the pose's translation.
Definition Pose2d.h:114
constexpr units::radian_t Radians() const
Returns the radian value of the rotation constrained within [-π, π].
Definition Rotation2d.h:206
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
Definition SystemServer.h:9
constexpr Matrixd< sizeof...(Ts), sizeof...(Ts)> MakeCostMatrix(Ts... tolerances)
Creates a cost matrix from the given vector for use with LQR.
Definition StateSpaceUtil.h:37
Motor voltages for a differential drive.
Definition DifferentialDriveWheelVoltages.h:14
Represents one point on the trajectory.
Definition Trajectory.h:34
Pose2d pose
The pose at that point of the trajectory.
Definition Trajectory.h:45
units::meters_per_second_t velocity
The speed at that point of the trajectory.
Definition Trajectory.h:39
units::curvature_t curvature
The curvature at that point of the trajectory.
Definition Trajectory.h:48