WPILibC++ 2025.0.0-alpha-1-14-g3b6f38d
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 <wpi/MathExtras.h>
8#include <wpi/SymbolExports.h>
9
10#include "units/angle.h"
12#include "units/math.h"
13#include "units/voltage.h"
14#include "wpimath/MathShared.h"
15
16namespace frc {
17/**
18 * A helper class that computes feedforward outputs for a simple arm (modeled as
19 * a motor acting against the force of gravity on a beam suspended at an angle).
20 */
22 public:
23 using Angle = units::radians;
24 using Velocity = units::radians_per_second;
25 using Acceleration = units::compound_unit<units::radians_per_second,
27 using kv_unit =
28 units::compound_unit<units::volts,
30 using ka_unit =
32
33 /**
34 * Creates a new ArmFeedforward with the specified gains.
35 *
36 * @param kS The static gain, in volts.
37 * @param kG The gravity gain, in volts.
38 * @param kV The velocity gain, in volt seconds per radian.
39 * @param kA The acceleration gain, in volt seconds² per radian.
40 */
41 constexpr ArmFeedforward(
42 units::volt_t kS, units::volt_t kG, units::unit_t<kv_unit> kV,
44 : kS(kS), kG(kG), kV(kV), kA(kA) {
45 if (kV.value() < 0) {
47 "kV must be a non-negative number, got {}!", kV.value());
50 }
51 if (kA.value() < 0) {
53 "kA must be a non-negative number, got {}!", kA.value());
56 }
57 }
58
59 /**
60 * Calculates the feedforward from the gains and setpoints.
61 *
62 * @param angle The angle setpoint, in radians. This angle should be
63 * measured from the horizontal (i.e. if the provided
64 * angle is 0, the arm should be parallel to the floor).
65 * If your encoder does not follow this convention, an
66 * offset should be added.
67 * @param velocity The velocity setpoint, in radians per second.
68 * @param acceleration The acceleration setpoint, in radians per second².
69 * @return The computed feedforward, in volts.
70 */
71 units::volt_t Calculate(units::unit_t<Angle> angle,
73 units::unit_t<Acceleration> acceleration =
75 return kS * wpi::sgn(velocity) + kG * units::math::cos(angle) +
76 kV * velocity + kA * acceleration;
77 }
78
79 /**
80 * Calculates the feedforward from the gains and setpoints.
81 *
82 * @param currentAngle The current angle in radians. This angle should be
83 * measured from the horizontal (i.e. if the provided angle is 0, the arm
84 * should be parallel to the floor). If your encoder does not follow this
85 * convention, an offset should be added.
86 * @param currentVelocity The current velocity setpoint in radians per second.
87 * @param nextVelocity The next velocity setpoint in radians per second.
88 * @param dt Time between velocity setpoints in seconds.
89 * @return The computed feedforward in volts.
90 */
91 units::volt_t Calculate(units::unit_t<Angle> currentAngle,
92 units::unit_t<Velocity> currentVelocity,
93 units::unit_t<Velocity> nextVelocity,
94 units::second_t dt) const;
95
96 // Rearranging the main equation from the calculate() method yields the
97 // formulas for the methods below:
98
99 /**
100 * Calculates the maximum achievable velocity given a maximum voltage supply,
101 * a position, and an acceleration. Useful for ensuring that velocity and
102 * acceleration constraints for a trapezoidal profile are simultaneously
103 * achievable - enter the acceleration constraint, and this will give you
104 * a simultaneously-achievable velocity constraint.
105 *
106 * @param maxVoltage The maximum voltage that can be supplied to the arm.
107 * @param angle The angle of the arm. This angle should be measured
108 * from the horizontal (i.e. if the provided angle is 0,
109 * the arm should be parallel to the floor). If your
110 * encoder does not follow this convention, an offset
111 * should be added.
112 * @param acceleration The acceleration of the arm.
113 * @return The maximum possible velocity at the given acceleration and angle.
114 */
116 units::volt_t maxVoltage, units::unit_t<Angle> angle,
117 units::unit_t<Acceleration> acceleration) {
118 // Assume max velocity is positive
119 return (maxVoltage - kS - kG * units::math::cos(angle) -
120 kA * acceleration) /
121 kV;
122 }
123
124 /**
125 * Calculates the minimum achievable velocity given a maximum voltage supply,
126 * a position, and an acceleration. Useful for ensuring that velocity and
127 * acceleration constraints for a trapezoidal profile are simultaneously
128 * achievable - enter the acceleration constraint, and this will give you
129 * a simultaneously-achievable velocity constraint.
130 *
131 * @param maxVoltage The maximum voltage that can be supplied to the arm.
132 * @param angle The angle of the arm. This angle should be measured
133 * from the horizontal (i.e. if the provided angle is 0,
134 * the arm should be parallel to the floor). If your
135 * encoder does not follow this convention, an offset
136 * should be added.
137 * @param acceleration The acceleration of the arm.
138 * @return The minimum possible velocity at the given acceleration and angle.
139 */
141 units::volt_t maxVoltage, units::unit_t<Angle> angle,
142 units::unit_t<Acceleration> acceleration) {
143 // Assume min velocity is negative, ks flips sign
144 return (-maxVoltage + kS - kG * units::math::cos(angle) -
145 kA * acceleration) /
146 kV;
147 }
148
149 /**
150 * Calculates the maximum achievable acceleration given a maximum voltage
151 * supply, a position, and a velocity. Useful for ensuring that velocity and
152 * acceleration constraints for a trapezoidal profile are simultaneously
153 * achievable - enter the velocity constraint, and this will give you
154 * a simultaneously-achievable acceleration 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 velocity The velocity of the arm.
163 * @return The maximum possible acceleration at the given velocity and angle.
164 */
166 units::volt_t maxVoltage, units::unit_t<Angle> angle,
167 units::unit_t<Velocity> velocity) {
168 return (maxVoltage - kS * wpi::sgn(velocity) -
169 kG * units::math::cos(angle) - kV * velocity) /
170 kA;
171 }
172
173 /**
174 * Calculates the minimum achievable acceleration given a maximum voltage
175 * supply, a position, and a velocity. Useful for ensuring that velocity and
176 * acceleration constraints for a trapezoidal profile are simultaneously
177 * achievable - enter the velocity constraint, and this will give you
178 * a simultaneously-achievable acceleration constraint.
179 *
180 * @param maxVoltage The maximum voltage that can be supplied to the arm.
181 * @param angle The angle of the arm. This angle should be measured
182 * from the horizontal (i.e. if the provided angle is 0,
183 * the arm should be parallel to the floor). If your
184 * encoder does not follow this convention, an offset
185 * should be added.
186 * @param velocity The velocity of the arm.
187 * @return The minimum possible acceleration at the given velocity and angle.
188 */
190 units::volt_t maxVoltage, units::unit_t<Angle> angle,
191 units::unit_t<Velocity> velocity) {
192 return MaxAchievableAcceleration(-maxVoltage, angle, velocity);
193 }
194
195 /// The static gain, in volts.
196 const units::volt_t kS;
197
198 /// The gravity gain, in volts.
199 const units::volt_t kG;
200
201 /// The velocity gain, in volt seconds per radian.
203
204 /// The acceleration gain, in volt seconds² per radian.
206};
207} // namespace frc
208
#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:21
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:115
units::radians_per_second Velocity
Definition: ArmFeedforward.h:24
units::volt_t Calculate(units::unit_t< Angle > angle, units::unit_t< Velocity > velocity, units::unit_t< Acceleration > acceleration=units::unit_t< Acceleration >(0)) const
Calculates the feedforward from the gains and setpoints.
Definition: ArmFeedforward.h:71
const units::unit_t< ka_unit > kA
The acceleration gain, in volt seconds² per radian.
Definition: ArmFeedforward.h:205
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:165
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.
const units::volt_t kS
The static gain, in volts.
Definition: ArmFeedforward.h:196
units::compound_unit< units::volts, units::inverse< Acceleration > > ka_unit
Definition: ArmFeedforward.h:31
units::compound_unit< units::radians_per_second, units::inverse< units::second > > Acceleration
Definition: ArmFeedforward.h:26
units::radians Angle
Definition: ArmFeedforward.h:23
const units::volt_t kG
The gravity gain, in volts.
Definition: ArmFeedforward.h:199
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:189
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:140
const units::unit_t< kv_unit > kV
The velocity gain, in volt seconds per radian.
Definition: ArmFeedforward.h:202
units::compound_unit< units::volts, units::inverse< units::radians_per_second > > kv_unit
Definition: ArmFeedforward.h:29
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))
Creates a new ArmFeedforward with the specified gains.
Definition: ArmFeedforward.h:41
constexpr underlying_type value() const noexcept
unit value
Definition: base.h:2110
static void ReportError(const S &format, Args &&... args)
Definition: MathShared.h:60
static void ReportWarning(const S &format, Args &&... args)
Definition: MathShared.h:69
typename units::detail::inverse_impl< U >::type inverse
represents the inverse unit type of class U.
Definition: base.h:1137
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:1437
Definition: AprilTagDetector_cv.h:11
constexpr int sgn(T val)
Definition: MathExtras.h:624