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