WPILibC++ 2024.3.2
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 // Rearranging the main equation from the calculate() method yields the
80 // formulas for the methods below:
81
82 /**
83 * Calculates the maximum achievable velocity given a maximum voltage supply,
84 * a position, and an acceleration. Useful for ensuring that velocity and
85 * acceleration constraints for a trapezoidal profile are simultaneously
86 * achievable - enter the acceleration constraint, and this will give you
87 * a simultaneously-achievable velocity constraint.
88 *
89 * @param maxVoltage The maximum voltage that can be supplied to the arm.
90 * @param angle The angle of the arm. This angle should be measured
91 * from the horizontal (i.e. if the provided angle is 0,
92 * the arm should be parallel to the floor). If your
93 * encoder does not follow this convention, an offset
94 * should be added.
95 * @param acceleration The acceleration of the arm.
96 * @return The maximum possible velocity at the given acceleration and angle.
97 */
99 units::volt_t maxVoltage, units::unit_t<Angle> angle,
100 units::unit_t<Acceleration> acceleration) {
101 // Assume max velocity is positive
102 return (maxVoltage - kS - kG * units::math::cos(angle) -
103 kA * acceleration) /
104 kV;
105 }
106
107 /**
108 * Calculates the minimum achievable velocity given a maximum voltage supply,
109 * a position, and an acceleration. Useful for ensuring that velocity and
110 * acceleration constraints for a trapezoidal profile are simultaneously
111 * achievable - enter the acceleration constraint, and this will give you
112 * a simultaneously-achievable velocity constraint.
113 *
114 * @param maxVoltage The maximum voltage that can be supplied to the arm.
115 * @param angle The angle of the arm. This angle should be measured
116 * from the horizontal (i.e. if the provided angle is 0,
117 * the arm should be parallel to the floor). If your
118 * encoder does not follow this convention, an offset
119 * should be added.
120 * @param acceleration The acceleration of the arm.
121 * @return The minimum possible velocity at the given acceleration and angle.
122 */
124 units::volt_t maxVoltage, units::unit_t<Angle> angle,
125 units::unit_t<Acceleration> acceleration) {
126 // Assume min velocity is negative, ks flips sign
127 return (-maxVoltage + kS - kG * units::math::cos(angle) -
128 kA * acceleration) /
129 kV;
130 }
131
132 /**
133 * Calculates the maximum achievable acceleration given a maximum voltage
134 * supply, a position, and a velocity. Useful for ensuring that velocity and
135 * acceleration constraints for a trapezoidal profile are simultaneously
136 * achievable - enter the velocity constraint, and this will give you
137 * a simultaneously-achievable acceleration constraint.
138 *
139 * @param maxVoltage The maximum voltage that can be supplied to the arm.
140 * @param angle The angle of the arm. This angle should be measured
141 * from the horizontal (i.e. if the provided angle is 0,
142 * the arm should be parallel to the floor). If your
143 * encoder does not follow this convention, an offset
144 * should be added.
145 * @param velocity The velocity of the arm.
146 * @return The maximum possible acceleration at the given velocity and angle.
147 */
149 units::volt_t maxVoltage, units::unit_t<Angle> angle,
150 units::unit_t<Velocity> velocity) {
151 return (maxVoltage - kS * wpi::sgn(velocity) -
152 kG * units::math::cos(angle) - kV * velocity) /
153 kA;
154 }
155
156 /**
157 * Calculates the minimum achievable acceleration given a maximum voltage
158 * supply, a position, and a velocity. Useful for ensuring that velocity and
159 * acceleration constraints for a trapezoidal profile are simultaneously
160 * achievable - enter the velocity constraint, and this will give you
161 * a simultaneously-achievable acceleration constraint.
162 *
163 * @param maxVoltage The maximum voltage that can be supplied to the arm.
164 * @param angle The angle of the arm. This angle should be measured
165 * from the horizontal (i.e. if the provided angle is 0,
166 * the arm should be parallel to the floor). If your
167 * encoder does not follow this convention, an offset
168 * should be added.
169 * @param velocity The velocity of the arm.
170 * @return The minimum possible acceleration at the given velocity and angle.
171 */
173 units::volt_t maxVoltage, units::unit_t<Angle> angle,
174 units::unit_t<Velocity> velocity) {
175 return MaxAchievableAcceleration(-maxVoltage, angle, velocity);
176 }
177
178 /// The static gain, in volts.
179 const units::volt_t kS;
180
181 /// The gravity gain, in volts.
182 const units::volt_t kG;
183
184 /// The velocity gain, in volt seconds per radian.
186
187 /// The acceleration gain, in volt seconds² per radian.
189};
190} // namespace frc
191
#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:98
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:188
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:148
const units::volt_t kS
The static gain, in volts.
Definition: ArmFeedforward.h:179
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:182
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:172
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:123
const units::unit_t< kv_unit > kV
The velocity gain, in volt seconds per radian.
Definition: ArmFeedforward.h:185
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:2107
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:1134
dimensionless::scalar_t cos(const AngleUnit angle) noexcept
Compute cosine.
Definition: math.h:61
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition: base.h:1434
Definition: AprilTagPoseEstimator.h:15
constexpr int sgn(T val)
Definition: MathExtras.h:624