WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
ArmFeedforward.hpp
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
8#include "wpi/units/angle.hpp"
9#include "wpi/units/angular_velocity.hpp"
10#include "wpi/units/math.hpp"
11#include "wpi/units/voltage.hpp"
14
15namespace wpi::math {
16/**
17 * A helper class that computes feedforward outputs for a simple arm (modeled as
18 * a motor acting against the force of gravity on a beam suspended at an angle).
19 */
21 public:
22 using Angle = wpi::units::radians;
23 using Velocity = wpi::units::radians_per_second;
25 wpi::units::compound_unit<wpi::units::radians_per_second,
26 wpi::units::inverse<wpi::units::second>>;
27 using kv_unit = wpi::units::compound_unit<
28 wpi::units::volts, wpi::units::inverse<wpi::units::radians_per_second>>;
29 using ka_unit = wpi::units::compound_unit<wpi::units::volts,
30 wpi::units::inverse<Acceleration>>;
31
32 /**
33 * Creates a new ArmFeedforward with the specified gains.
34 *
35 * @param kS The static gain, in volts.
36 * @param kG The gravity gain, in volts.
37 * @param kV The velocity gain, in volt seconds per radian.
38 * @param kA The acceleration gain, in volt seconds² per radian.
39 * @param dt The period in seconds.
40 * @throws IllegalArgumentException for kv &lt; zero.
41 * @throws IllegalArgumentException for ka &lt; zero.
42 * @throws IllegalArgumentException for period &le; zero.
43 */
44 constexpr ArmFeedforward(
45 wpi::units::volt_t kS, wpi::units::volt_t kG,
46 wpi::units::unit_t<kv_unit> kV,
47 wpi::units::unit_t<ka_unit> kA = wpi::units::unit_t<ka_unit>(0),
48 wpi::units::second_t dt = 20_ms)
49 : kS(kS), kG(kG), kV(kV), kA(kA), m_dt(dt) {
50 if (kV.value() < 0) {
51 wpi::math::MathSharedStore::ReportError(
52 "kV must be a non-negative number, got {}!", kV.value());
53 this->kV = wpi::units::unit_t<kv_unit>{0};
55 }
56 if (kA.value() < 0) {
57 wpi::math::MathSharedStore::ReportError(
58 "kA must be a non-negative number, got {}!", kA.value());
59 this->kA = wpi::units::unit_t<ka_unit>{0};
61 }
62 if (dt <= 0_ms) {
64 "period must be a positive number, got {}!", dt.value());
65 this->m_dt = 20_ms;
66 wpi::math::MathSharedStore::ReportWarning("period defaulted to 20 ms.");
67 }
68 }
69
70 /**
71 * Calculates the feedforward from the gains and setpoints assuming continuous
72 * control.
73 *
74 * @param angle The angle setpoint, in radians. This angle should be
75 * measured from the horizontal (i.e. if the provided
76 * angle is 0, the arm should be parallel to the floor).
77 * If your encoder does not follow this convention, an
78 * offset should be added.
79 * @param velocity The velocity setpoint.
80 * @param acceleration The acceleration setpoint.
81 * @return The computed feedforward, in volts.
82 */
83 [[deprecated("Use the current/next velocity overload instead.")]]
84 constexpr wpi::units::volt_t Calculate(
85 wpi::units::unit_t<Angle> angle, wpi::units::unit_t<Velocity> velocity,
86 wpi::units::unit_t<Acceleration> acceleration) const {
87 return kS * wpi::util::sgn(velocity) + kG * wpi::units::math::cos(angle) +
88 kV * velocity + kA * acceleration;
89 }
90
91 /**
92 * Calculates the feedforward from the gains and setpoints assuming continuous
93 * control.
94 *
95 * @param currentAngle The current angle in radians. This angle should be
96 * measured from the horizontal (i.e. if the provided angle is 0, the arm
97 * should be parallel to the floor). If your encoder does not follow this
98 * convention, an offset should be added.
99 * @param currentVelocity The current velocity setpoint.
100 * @param nextVelocity The next velocity setpoint.
101 * @param dt Time between velocity setpoints in seconds.
102 * @return The computed feedforward in volts.
103 */
104 [[deprecated("Use the current/next velocity overload instead.")]]
105 wpi::units::volt_t Calculate(wpi::units::unit_t<Angle> currentAngle,
106 wpi::units::unit_t<Velocity> currentVelocity,
107 wpi::units::unit_t<Velocity> nextVelocity,
108 wpi::units::second_t dt) const {
109 return Calculate(currentAngle, currentVelocity, nextVelocity);
110 }
111
112 /**
113 * Calculates the feedforward from the gains and setpoint assuming discrete
114 * control. Use this method when the velocity does not change.
115 *
116 * @param currentAngle The current angle. This angle should be measured from
117 * the horizontal (i.e. if the provided angle is 0, the arm should be parallel
118 * to the floor). If your encoder does not follow this convention, an offset
119 * should be added.
120 * @param currentVelocity The current velocity.
121 * @return The computed feedforward in volts.
122 */
123 constexpr wpi::units::volt_t Calculate(
124 wpi::units::unit_t<Angle> currentAngle,
125 wpi::units::unit_t<Velocity> currentVelocity) const {
126 return kS * wpi::util::sgn(currentVelocity) +
127 kG * wpi::units::math::cos(currentAngle) + kV * currentVelocity;
128 }
129
130 /**
131 * Calculates the feedforward from the gains and setpoints assuming discrete
132 * control.
133 *
134 * @param currentAngle The current angle. This angle should be measured from
135 * the horizontal (i.e. if the provided angle is 0, the arm should be parallel
136 * to the floor). If your encoder does not follow this convention, an offset
137 * should be added.
138 * @param currentVelocity The current velocity.
139 * @param nextVelocity The next velocity.
140 * @return The computed feedforward in volts.
141 */
142 wpi::units::volt_t Calculate(wpi::units::unit_t<Angle> currentAngle,
143 wpi::units::unit_t<Velocity> currentVelocity,
144 wpi::units::unit_t<Velocity> nextVelocity) const;
145
146 // Rearranging the main equation from the calculate() method yields the
147 // formulas for the methods below:
148
149 /**
150 * Calculates the maximum achievable velocity given a maximum voltage supply,
151 * a position, and an acceleration. Useful for ensuring that velocity and
152 * acceleration constraints for a trapezoidal profile are simultaneously
153 * achievable - enter the acceleration constraint, and this will give you
154 * a simultaneously-achievable velocity constraint.
155 *
156 * @param maxVoltage The maximum voltage that can be supplied to the arm.
157 * @param angle The angle of the arm. This angle should be measured
158 * from the horizontal (i.e. if the provided angle is 0,
159 * the arm should be parallel to the floor). If your
160 * encoder does not follow this convention, an offset
161 * should be added.
162 * @param acceleration The acceleration of the arm.
163 * @return The maximum possible velocity at the given acceleration and angle.
164 */
165 constexpr wpi::units::unit_t<Velocity> MaxAchievableVelocity(
166 wpi::units::volt_t maxVoltage, wpi::units::unit_t<Angle> angle,
167 wpi::units::unit_t<Acceleration> acceleration) {
168 // Assume max velocity is positive
169 return (maxVoltage - kS - kG * wpi::units::math::cos(angle) -
170 kA * acceleration) /
171 kV;
172 }
173
174 /**
175 * Calculates the minimum achievable velocity given a maximum voltage supply,
176 * a position, and an acceleration. Useful for ensuring that velocity and
177 * acceleration constraints for a trapezoidal profile are simultaneously
178 * achievable - enter the acceleration constraint, and this will give you
179 * a simultaneously-achievable velocity constraint.
180 *
181 * @param maxVoltage The maximum voltage that can be supplied to the arm.
182 * @param angle The angle of the arm. This angle should be measured
183 * from the horizontal (i.e. if the provided angle is 0,
184 * the arm should be parallel to the floor). If your
185 * encoder does not follow this convention, an offset
186 * should be added.
187 * @param acceleration The acceleration of the arm.
188 * @return The minimum possible velocity at the given acceleration and angle.
189 */
190 constexpr wpi::units::unit_t<Velocity> MinAchievableVelocity(
191 wpi::units::volt_t maxVoltage, wpi::units::unit_t<Angle> angle,
192 wpi::units::unit_t<Acceleration> acceleration) {
193 // Assume min velocity is negative, ks flips sign
194 return (-maxVoltage + kS - kG * wpi::units::math::cos(angle) -
195 kA * acceleration) /
196 kV;
197 }
198
199 /**
200 * Calculates the maximum achievable acceleration given a maximum voltage
201 * supply, a position, and a velocity. Useful for ensuring that velocity and
202 * acceleration constraints for a trapezoidal profile are simultaneously
203 * achievable - enter the velocity constraint, and this will give you
204 * a simultaneously-achievable acceleration constraint.
205 *
206 * @param maxVoltage The maximum voltage that can be supplied to the arm.
207 * @param angle The angle of the arm. This angle should be measured
208 * from the horizontal (i.e. if the provided angle is 0,
209 * the arm should be parallel to the floor). If your
210 * encoder does not follow this convention, an offset
211 * should be added.
212 * @param velocity The velocity of the arm.
213 * @return The maximum possible acceleration at the given velocity and angle.
214 */
215 constexpr wpi::units::unit_t<Acceleration> MaxAchievableAcceleration(
216 wpi::units::volt_t maxVoltage, wpi::units::unit_t<Angle> angle,
217 wpi::units::unit_t<Velocity> velocity) {
218 return (maxVoltage - kS * wpi::util::sgn(velocity) -
219 kG * wpi::units::math::cos(angle) - kV * velocity) /
220 kA;
221 }
222
223 /**
224 * Calculates the minimum achievable acceleration given a maximum voltage
225 * supply, a position, and a velocity. Useful for ensuring that velocity and
226 * acceleration constraints for a trapezoidal profile are simultaneously
227 * achievable - enter the velocity constraint, and this will give you
228 * a simultaneously-achievable acceleration constraint.
229 *
230 * @param maxVoltage The maximum voltage that can be supplied to the arm.
231 * @param angle The angle of the arm. This angle should be measured
232 * from the horizontal (i.e. if the provided angle is 0,
233 * the arm should be parallel to the floor). If your
234 * encoder does not follow this convention, an offset
235 * should be added.
236 * @param velocity The velocity of the arm.
237 * @return The minimum possible acceleration at the given velocity and angle.
238 */
239 constexpr wpi::units::unit_t<Acceleration> MinAchievableAcceleration(
240 wpi::units::volt_t maxVoltage, wpi::units::unit_t<Angle> angle,
241 wpi::units::unit_t<Velocity> velocity) {
242 return MaxAchievableAcceleration(-maxVoltage, angle, velocity);
243 }
244
245 /**
246 * Sets the static gain.
247 *
248 * @param kS The static gain.
249 */
250 constexpr void SetKs(wpi::units::volt_t kS) { this->kS = kS; }
251
252 /**
253 * Sets the gravity gain.
254 *
255 * @param kG The gravity gain.
256 */
257 constexpr void SetKg(wpi::units::volt_t kG) { this->kG = kG; }
258
259 /**
260 * Sets the velocity gain.
261 *
262 * @param kV The velocity gain.
263 */
264 constexpr void SetKv(wpi::units::unit_t<kv_unit> kV) { this->kV = kV; }
265
266 /**
267 * Sets the acceleration gain.
268 *
269 * @param kA The acceleration gain.
270 */
271 constexpr void SetKa(wpi::units::unit_t<ka_unit> kA) { this->kA = kA; }
272
273 /**
274 * Returns the static gain.
275 *
276 * @return The static gain.
277 */
278 constexpr wpi::units::volt_t GetKs() const { return kS; }
279
280 /**
281 * Returns the gravity gain.
282 *
283 * @return The gravity gain.
284 */
285 constexpr wpi::units::volt_t GetKg() const { return kG; }
286
287 /**
288 * Returns the velocity gain.
289 *
290 * @return The velocity gain.
291 */
292 constexpr wpi::units::unit_t<kv_unit> GetKv() const { return kV; }
293
294 /**
295 * Returns the acceleration gain.
296 *
297 * @return The acceleration gain.
298 */
299 constexpr wpi::units::unit_t<ka_unit> GetKa() const { return kA; }
300
301 private:
302 /// The static gain, in volts.
303 wpi::units::volt_t kS;
304
305 /// The gravity gain, in volts.
306 wpi::units::volt_t kG;
307
308 /// The velocity gain, in V/(rad/s)volt seconds per radian.
309 wpi::units::unit_t<kv_unit> kV;
310
311 /// The acceleration gain, in V/(rad/s²).
312 wpi::units::unit_t<ka_unit> kA;
313
314 /** The period. */
315 wpi::units::second_t m_dt;
316};
317} // namespace wpi::math
318
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
constexpr wpi::units::volt_t GetKg() const
Returns the gravity gain.
Definition ArmFeedforward.hpp:285
constexpr void SetKs(wpi::units::volt_t kS)
Sets the static gain.
Definition ArmFeedforward.hpp:250
constexpr wpi::units::unit_t< Velocity > MaxAchievableVelocity(wpi::units::volt_t maxVoltage, wpi::units::unit_t< Angle > angle, wpi::units::unit_t< Acceleration > acceleration)
Calculates the maximum achievable velocity given a maximum voltage supply, a position,...
Definition ArmFeedforward.hpp:165
wpi::units::radians_per_second Velocity
Definition ArmFeedforward.hpp:23
constexpr wpi::units::unit_t< ka_unit > GetKa() const
Returns the acceleration gain.
Definition ArmFeedforward.hpp:299
constexpr wpi::units::unit_t< Acceleration > MinAchievableAcceleration(wpi::units::volt_t maxVoltage, wpi::units::unit_t< Angle > angle, wpi::units::unit_t< Velocity > velocity)
Calculates the minimum achievable acceleration given a maximum voltage supply, a position,...
Definition ArmFeedforward.hpp:239
constexpr wpi::units::unit_t< Acceleration > MaxAchievableAcceleration(wpi::units::volt_t maxVoltage, wpi::units::unit_t< Angle > angle, wpi::units::unit_t< Velocity > velocity)
Calculates the maximum achievable acceleration given a maximum voltage supply, a position,...
Definition ArmFeedforward.hpp:215
constexpr wpi::units::volt_t Calculate(wpi::units::unit_t< Angle > currentAngle, wpi::units::unit_t< Velocity > currentVelocity) const
Calculates the feedforward from the gains and setpoint assuming discrete control.
Definition ArmFeedforward.hpp:123
constexpr wpi::units::volt_t GetKs() const
Returns the static gain.
Definition ArmFeedforward.hpp:278
wpi::units::radians Angle
Definition ArmFeedforward.hpp:22
constexpr void SetKa(wpi::units::unit_t< ka_unit > kA)
Sets the acceleration gain.
Definition ArmFeedforward.hpp:271
constexpr wpi::units::unit_t< Velocity > MinAchievableVelocity(wpi::units::volt_t maxVoltage, wpi::units::unit_t< Angle > angle, wpi::units::unit_t< Acceleration > acceleration)
Calculates the minimum achievable velocity given a maximum voltage supply, a position,...
Definition ArmFeedforward.hpp:190
constexpr wpi::units::unit_t< kv_unit > GetKv() const
Returns the velocity gain.
Definition ArmFeedforward.hpp:292
wpi::units::compound_unit< wpi::units::volts, wpi::units::inverse< wpi::units::radians_per_second > > kv_unit
Definition ArmFeedforward.hpp:27
constexpr ArmFeedforward(wpi::units::volt_t kS, wpi::units::volt_t kG, wpi::units::unit_t< kv_unit > kV, wpi::units::unit_t< ka_unit > kA=wpi::units::unit_t< ka_unit >(0), wpi::units::second_t dt=20_ms)
Creates a new ArmFeedforward with the specified gains.
Definition ArmFeedforward.hpp:44
constexpr wpi::units::volt_t Calculate(wpi::units::unit_t< Angle > angle, wpi::units::unit_t< Velocity > velocity, wpi::units::unit_t< Acceleration > acceleration) const
Calculates the feedforward from the gains and setpoints assuming continuous control.
Definition ArmFeedforward.hpp:84
wpi::units::volt_t Calculate(wpi::units::unit_t< Angle > currentAngle, wpi::units::unit_t< Velocity > currentVelocity, wpi::units::unit_t< Velocity > nextVelocity) const
Calculates the feedforward from the gains and setpoints assuming discrete control.
wpi::units::compound_unit< wpi::units::volts, wpi::units::inverse< Acceleration > > ka_unit
Definition ArmFeedforward.hpp:29
constexpr void SetKg(wpi::units::volt_t kG)
Sets the gravity gain.
Definition ArmFeedforward.hpp:257
wpi::units::volt_t Calculate(wpi::units::unit_t< Angle > currentAngle, wpi::units::unit_t< Velocity > currentVelocity, wpi::units::unit_t< Velocity > nextVelocity, wpi::units::second_t dt) const
Calculates the feedforward from the gains and setpoints assuming continuous control.
Definition ArmFeedforward.hpp:105
constexpr void SetKv(wpi::units::unit_t< kv_unit > kV)
Sets the velocity gain.
Definition ArmFeedforward.hpp:264
wpi::units::compound_unit< wpi::units::radians_per_second, wpi::units::inverse< wpi::units::second > > Acceleration
Definition ArmFeedforward.hpp:24
static void ReportError(const S &format, Args &&... args)
Definition MathShared.hpp:48
static void ReportWarning(const S &format, Args &&... args)
Definition MathShared.hpp:57
Definition LinearSystem.hpp:20
constexpr int sgn(T val)
Definition MathExtras.hpp:766