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"
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>>;
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) {
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};
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};
64 "period must be a positive number, got {}!", dt.value());
83 [[deprecated(
"Use the current/next velocity overload instead.")]]
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;
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);
124 wpi::units::unit_t<Angle> currentAngle,
125 wpi::units::unit_t<Velocity> currentVelocity)
const {
127 kG * wpi::units::math::cos(currentAngle) + kV * currentVelocity;
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;
166 wpi::units::volt_t maxVoltage, wpi::units::unit_t<Angle> angle,
167 wpi::units::unit_t<Acceleration> acceleration) {
169 return (maxVoltage - kS - kG * wpi::units::math::cos(angle) -
191 wpi::units::volt_t maxVoltage, wpi::units::unit_t<Angle> angle,
192 wpi::units::unit_t<Acceleration> acceleration) {
194 return (-maxVoltage + kS - kG * wpi::units::math::cos(angle) -
216 wpi::units::volt_t maxVoltage, wpi::units::unit_t<Angle> angle,
217 wpi::units::unit_t<Velocity> velocity) {
219 kG * wpi::units::math::cos(angle) - kV * velocity) /
240 wpi::units::volt_t maxVoltage, wpi::units::unit_t<Angle> angle,
241 wpi::units::unit_t<Velocity> velocity) {
250 constexpr void SetKs(wpi::units::volt_t kS) { this->kS = kS; }
257 constexpr void SetKg(wpi::units::volt_t kG) { this->kG = kG; }
264 constexpr void SetKv(wpi::units::unit_t<kv_unit> kV) { this->kV = kV; }
271 constexpr void SetKa(wpi::units::unit_t<ka_unit> kA) { this->kA = kA; }
278 constexpr wpi::units::volt_t
GetKs()
const {
return kS; }
285 constexpr wpi::units::volt_t
GetKg()
const {
return kG; }
292 constexpr wpi::units::unit_t<kv_unit>
GetKv()
const {
return kV; }
299 constexpr wpi::units::unit_t<ka_unit>
GetKa()
const {
return kA; }
303 wpi::units::volt_t kS;
306 wpi::units::volt_t kG;
309 wpi::units::unit_t<kv_unit> kV;
312 wpi::units::unit_t<ka_unit> kA;
315 wpi::units::second_t m_dt;
#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