13#include "wpi/units/time.hpp"
29template <
class Distance>
36 wpi::units::compound_unit<Distance,
37 wpi::units::inverse<wpi::units::seconds>>;
41 wpi::units::inverse<wpi::units::seconds>>;
60 wpi::units::second_t period = 20_ms)
61 : m_controller{Kp, Ki, Kd, period},
62 m_constraints{constraints},
63 m_profile{m_constraints} {
64 if (!std::is_constant_evaluated()) {
67 std::to_string(instances));
90 constexpr void SetPID(
double Kp,
double Ki,
double Kd) {
91 m_controller.SetPID(Kp, Ki, Kd);
99 constexpr void SetP(
double Kp) { m_controller.SetP(Kp); }
106 constexpr void SetI(
double Ki) { m_controller.SetI(Ki); }
113 constexpr void SetD(
double Kd) { m_controller.SetD(Kd); }
126 constexpr void SetIZone(
double iZone) { m_controller.SetIZone(iZone); }
133 constexpr double GetP()
const {
return m_controller.GetP(); }
140 constexpr double GetI()
const {
return m_controller.GetI(); }
147 constexpr double GetD()
const {
return m_controller.GetD(); }
154 constexpr double GetIZone()
const {
return m_controller.GetIZone(); }
162 return m_controller.GetPeriod();
171 return m_controller.GetErrorTolerance();
180 return m_controller.GetErrorDerivativeTolerance();
190 return m_controller.GetAccumulatedError();
225 m_constraints = constraints;
251 constexpr bool AtSetpoint()
const {
return m_controller.AtSetpoint(); }
265 m_controller.EnableContinuousInput(minimumInput.value(),
266 maximumInput.value());
267 m_minimumInput = minimumInput;
268 m_maximumInput = maximumInput;
275 m_controller.DisableContinuousInput();
289 double maximumIntegral) {
290 m_controller.SetIntegratorRange(minimumIntegral, maximumIntegral);
302 std::numeric_limits<double>::infinity()}) {
304 velocityTolerance.value());
320 return Velocity_t{m_controller.GetErrorDerivative()};
329 if (m_controller.IsContinuousInputEnabled()) {
331 auto errorBound = (m_maximumInput - m_minimumInput) / 2.0;
333 m_goal.position - measurement, -errorBound, errorBound);
335 m_setpoint.position - measurement, -errorBound, errorBound);
343 m_goal.position = goalMinDistance + measurement;
344 m_setpoint.position = setpointMinDistance + measurement;
347 m_setpoint = m_profile.Calculate(
GetPeriod(), m_setpoint, m_goal);
348 return m_controller.Calculate(measurement.value(),
349 m_setpoint.position.value());
393 m_controller.Reset();
394 m_setpoint = measurement;
405 Reset(
State{measuredPosition, measuredVelocity});
421 "p", [
this] {
return GetP(); }, [
this](
double value) {
SetP(value); });
423 "i", [
this] {
return GetI(); }, [
this](
double value) {
SetI(value); });
425 "d", [
this] {
return GetD(); }, [
this](
double value) {
SetD(value); });
427 "izone", [
this] {
return GetIZone(); },
428 [
this](
double value) {
SetIZone(value); });
430 "maxVelocity", [
this] {
return GetConstraints().maxVelocity.value(); },
431 [
this](
double value) {
438 [
this](
double value) {
443 "goal", [
this] {
return GetGoal().position.value(); },
453 TrapezoidProfile<Distance> m_profile;
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.hpp:61
Implements a PID control loop.
Definition PIDController.hpp:28
constexpr void SetTolerance(double errorTolerance, double errorDerivativeTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
Definition PIDController.hpp:314
constexpr void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
Definition ProfiledPIDController.hpp:99
constexpr void Reset(Distance_t measuredPosition, Velocity_t measuredVelocity)
Reset the previous error and the integral term.
Definition ProfiledPIDController.hpp:403
constexpr ProfiledPIDController & operator=(ProfiledPIDController &&)=default
constexpr void SetTolerance(Distance_t positionTolerance, Velocity_t velocityTolerance=Velocity_t{ std::numeric_limits< double >::infinity()})
Sets the error which is considered tolerable for use with AtSetpoint().
Definition ProfiledPIDController.hpp:300
constexpr void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
Definition ProfiledPIDController.hpp:90
void InitSendable(wpi::util::SendableBuilder &builder) override
Initializes this Sendable object.
Definition ProfiledPIDController.hpp:418
constexpr double GetPositionTolerance() const
Gets the position tolerance of this controller.
Definition ProfiledPIDController.hpp:170
typename TrapezoidProfile< Distance >::State State
Definition ProfiledPIDController.hpp:43
wpi::units::compound_unit< Velocity, wpi::units::inverse< wpi::units::seconds > > Acceleration
Definition ProfiledPIDController.hpp:39
constexpr Distance_t GetPositionError() const
Returns the difference between the setpoint and the measurement.
Definition ProfiledPIDController.hpp:312
constexpr void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
Definition ProfiledPIDController.hpp:106
constexpr Velocity_t GetVelocityError() const
Returns the change in error per second.
Definition ProfiledPIDController.hpp:319
constexpr void DisableContinuousInput()
Disables continuous input.
Definition ProfiledPIDController.hpp:274
constexpr double Calculate(Distance_t measurement)
Returns the next output of the PID controller.
Definition ProfiledPIDController.hpp:328
constexpr ProfiledPIDController(const ProfiledPIDController &)=default
constexpr double GetP() const
Gets the proportional coefficient.
Definition ProfiledPIDController.hpp:133
constexpr double GetAccumulatedError() const
Gets the accumulated error used in the integral calculation of this controller.
Definition ProfiledPIDController.hpp:189
constexpr State GetSetpoint() const
Returns the current setpoint of the ProfiledPIDController.
Definition ProfiledPIDController.hpp:240
constexpr wpi::units::second_t GetPeriod() const
Gets the period of this controller.
Definition ProfiledPIDController.hpp:161
constexpr void Reset(Distance_t measuredPosition)
Reset the previous error and the integral term.
Definition ProfiledPIDController.hpp:414
constexpr void Reset(const State &measurement)
Reset the previous error and the integral term.
Definition ProfiledPIDController.hpp:392
wpi::units::compound_unit< Distance, wpi::units::inverse< wpi::units::seconds > > Velocity
Definition ProfiledPIDController.hpp:35
constexpr double Calculate(Distance_t measurement, Distance_t goal, typename wpi::math::TrapezoidProfile< Distance >::Constraints constraints)
Returns the next output of the PID controller.
Definition ProfiledPIDController.hpp:380
constexpr bool AtGoal() const
Returns true if the error is within the tolerance of the error.
Definition ProfiledPIDController.hpp:217
constexpr double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
Definition ProfiledPIDController.hpp:179
constexpr void SetGoal(Distance_t goal)
Sets the goal for the ProfiledPIDController.
Definition ProfiledPIDController.hpp:205
constexpr double Calculate(Distance_t measurement, State goal)
Returns the next output of the PID controller.
Definition ProfiledPIDController.hpp:358
constexpr ProfiledPIDController(double Kp, double Ki, double Kd, Constraints constraints, wpi::units::second_t period=20_ms)
Allocates a ProfiledPIDController with the given constants for Kp, Ki, and Kd.
Definition ProfiledPIDController.hpp:58
constexpr void EnableContinuousInput(Distance_t minimumInput, Distance_t maximumInput)
Enables continuous input.
Definition ProfiledPIDController.hpp:263
constexpr void SetGoal(State goal)
Sets the goal for the ProfiledPIDController.
Definition ProfiledPIDController.hpp:198
constexpr double Calculate(Distance_t measurement, Distance_t goal)
Returns the next output of the PID controller.
Definition ProfiledPIDController.hpp:368
wpi::units::unit_t< Distance > Distance_t
Definition ProfiledPIDController.hpp:34
constexpr void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum contributions of the integral term.
Definition ProfiledPIDController.hpp:288
wpi::units::unit_t< Velocity > Velocity_t
Definition ProfiledPIDController.hpp:38
constexpr ~ProfiledPIDController() override=default
constexpr void SetIZone(double iZone)
Sets the IZone range.
Definition ProfiledPIDController.hpp:126
typename TrapezoidProfile< Distance >::Constraints Constraints
Definition ProfiledPIDController.hpp:44
constexpr bool AtSetpoint() const
Returns true if the error is within the tolerance of the error.
Definition ProfiledPIDController.hpp:251
constexpr double GetIZone() const
Get the IZone range.
Definition ProfiledPIDController.hpp:154
constexpr ProfiledPIDController(ProfiledPIDController &&)=default
constexpr double GetI() const
Gets the integral coefficient.
Definition ProfiledPIDController.hpp:140
constexpr void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
Definition ProfiledPIDController.hpp:113
constexpr Constraints GetConstraints()
Get the velocity and acceleration constraints for this controller.
Definition ProfiledPIDController.hpp:233
wpi::units::unit_t< Acceleration > Acceleration_t
Definition ProfiledPIDController.hpp:42
constexpr double GetD() const
Gets the differential coefficient.
Definition ProfiledPIDController.hpp:147
constexpr ProfiledPIDController & operator=(const ProfiledPIDController &)=default
constexpr void SetConstraints(Constraints constraints)
Set velocity and acceleration constraints for goal.
Definition ProfiledPIDController.hpp:224
constexpr State GetGoal() const
Gets the goal for the ProfiledPIDController.
Definition ProfiledPIDController.hpp:210
Profile constraints.
Definition TrapezoidProfile.hpp:61
Profile state.
Definition TrapezoidProfile.hpp:100
A trapezoid-shaped velocity profile.
Definition TrapezoidProfile.hpp:46
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.hpp:21
virtual void SetSmartDashboardType(std::string_view type)=0
Set the string representation of the named data type that will be used by the smart dashboard for thi...
virtual void AddDoubleProperty(std::string_view key, std::function< double()> getter, std::function< void(double)> setter)=0
Add a double property.
A helper class for use with objects that add themselves to SendableRegistry.
Definition SendableHelper.hpp:21
Interface for Sendable objects.
Definition Sendable.hpp:16
static void Add(Sendable *sendable, std::string_view name)
Adds an object to the registry.
Converts a string literal into a format string that will be parsed at compile time and converted into...
Definition printf.h:50
WPILIB_DLLEXPORT int IncrementAndGetProfiledPIDControllerInstances()
Definition LinearSystem.hpp:20
constexpr T InputModulus(T input, T minimumInput, T maximumInput)
Returns modulus of input.
Definition MathUtil.hpp:205