31template <
class Distance>
60 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()) {
89 constexpr void SetPID(
double Kp,
double Ki,
double Kd) {
90 m_controller.
SetPID(Kp, Ki, Kd);
98 constexpr void SetP(
double Kp) { m_controller.
SetP(Kp); }
105 constexpr void SetI(
double Ki) { m_controller.
SetI(Ki); }
112 constexpr void SetD(
double Kd) { m_controller.
SetD(Kd); }
132 constexpr double GetP()
const {
return m_controller.
GetP(); }
139 constexpr double GetI()
const {
return m_controller.
GetI(); }
146 constexpr double GetD()
const {
return m_controller.
GetD(); }
224 m_constraints = constraints;
265 maximumInput.
value());
266 m_minimumInput = minimumInput;
267 m_maximumInput = maximumInput;
288 double maximumIntegral) {
301 std::numeric_limits<double>::infinity()}) {
303 velocityTolerance.value());
330 auto errorBound = (m_maximumInput - m_minimumInput) / 2.0;
332 m_goal.position - measurement, -errorBound, errorBound);
334 m_setpoint.position - measurement, -errorBound, errorBound);
342 m_goal.position = goalMinDistance + measurement;
343 m_setpoint.position = setpointMinDistance + measurement;
346 m_setpoint = m_profile.Calculate(
GetPeriod(), m_setpoint, m_goal);
348 m_setpoint.position.value());
392 m_controller.
Reset();
393 m_setpoint = measurement;
404 Reset(
State{measuredPosition, measuredVelocity});
420 "p", [
this] {
return GetP(); }, [
this](
double value) {
SetP(value); });
422 "i", [
this] {
return GetI(); }, [
this](
double value) {
SetI(value); });
424 "d", [
this] {
return GetD(); }, [
this](
double value) {
SetD(value); });
426 "izone", [
this] {
return GetIZone(); },
427 [
this](
double value) {
SetIZone(value); });
429 "maxVelocity", [
this] {
return GetConstraints().maxVelocity.value(); },
430 [
this](
double value) {
437 [
this](
double value) {
442 "goal", [
this] {
return GetGoal().position.value(); },
452 TrapezoidProfile<Distance> m_profile;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Implements a PID control loop.
Definition PIDController.h:29
constexpr bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
Definition PIDController.h:291
constexpr units::second_t GetPeriod() const
Gets the period of this controller.
Definition PIDController.h:178
constexpr double Calculate(double measurement)
Returns the next output of the PID controller.
Definition PIDController.h:355
constexpr double GetErrorDerivativeTolerance() const
Gets the error derivative tolerance of this controller.
Definition PIDController.h:192
constexpr double GetI() const
Gets the integral coefficient.
Definition PIDController.h:157
constexpr void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
Definition PIDController.h:276
constexpr double GetD() const
Gets the differential coefficient.
Definition PIDController.h:164
constexpr void DisableContinuousInput()
Disables continuous input.
Definition PIDController.h:286
constexpr bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
Definition PIDController.h:260
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.h:315
constexpr void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
Definition PIDController.h:124
constexpr void SetIZone(double iZone)
Sets the IZone range.
Definition PIDController.h:137
constexpr double GetErrorTolerance() const
Gets the error tolerance of this controller.
Definition PIDController.h:185
constexpr double GetP() const
Gets the proportional coefficient.
Definition PIDController.h:150
constexpr void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum contributions of the integral term.
Definition PIDController.h:303
constexpr double GetAccumulatedError() const
Gets the accumulated error used in the integral calculation of this controller.
Definition PIDController.h:224
constexpr void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
Definition PIDController.h:99
constexpr void Reset()
Reset the previous error, the integral term, and disable the controller.
Definition PIDController.h:398
constexpr void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
Definition PIDController.h:117
constexpr void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
Definition PIDController.h:110
constexpr double GetErrorDerivative() const
Returns the error derivative.
Definition PIDController.h:330
constexpr double GetError() const
Returns the difference between the setpoint and the measurement.
Definition PIDController.h:325
constexpr double GetIZone() const
Get the IZone range.
Definition PIDController.h:171
Implements a PID control loop whose setpoint is constrained by a trapezoid profile.
Definition ProfiledPIDController.h:34
constexpr double Calculate(Distance_t measurement)
Returns the next output of the PID controller.
Definition ProfiledPIDController.h:327
constexpr double GetPositionTolerance() const
Gets the position tolerance of this controller.
Definition ProfiledPIDController.h:169
constexpr double Calculate(Distance_t measurement, Distance_t goal, typename frc::TrapezoidProfile< Distance >::Constraints constraints)
Returns the next output of the PID controller.
Definition ProfiledPIDController.h:379
constexpr ProfiledPIDController(double Kp, double Ki, double Kd, Constraints constraints, units::second_t period=20_ms)
Allocates a ProfiledPIDController with the given constants for Kp, Ki, and Kd.
Definition ProfiledPIDController.h:58
constexpr units::second_t GetPeriod() const
Gets the period of this controller.
Definition ProfiledPIDController.h:160
constexpr void SetConstraints(Constraints constraints)
Set velocity and acceleration constraints for goal.
Definition ProfiledPIDController.h:223
constexpr double GetD() const
Gets the differential coefficient.
Definition ProfiledPIDController.h:146
constexpr ProfiledPIDController & operator=(const ProfiledPIDController &)=default
constexpr double Calculate(Distance_t measurement, State goal)
Returns the next output of the PID controller.
Definition ProfiledPIDController.h:357
constexpr void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum contributions of the integral term.
Definition ProfiledPIDController.h:287
constexpr bool AtGoal() const
Returns true if the error is within the tolerance of the error.
Definition ProfiledPIDController.h:216
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.h:299
constexpr ~ProfiledPIDController() override=default
constexpr bool AtSetpoint() const
Returns true if the error is within the tolerance of the error.
Definition ProfiledPIDController.h:250
units::unit_t< Distance > Distance_t
Definition ProfiledPIDController.h:36
constexpr Distance_t GetPositionError() const
Returns the difference between the setpoint and the measurement.
Definition ProfiledPIDController.h:311
typename TrapezoidProfile< Distance >::Constraints Constraints
Definition ProfiledPIDController.h:44
units::compound_unit< Distance, units::inverse< units::seconds > > Velocity
Definition ProfiledPIDController.h:37
constexpr Velocity_t GetVelocityError() const
Returns the change in error per second.
Definition ProfiledPIDController.h:318
constexpr ProfiledPIDController(const ProfiledPIDController &)=default
constexpr void DisableContinuousInput()
Disables continuous input.
Definition ProfiledPIDController.h:273
constexpr void SetIZone(double iZone)
Sets the IZone range.
Definition ProfiledPIDController.h:125
constexpr double GetAccumulatedError() const
Gets the accumulated error used in the integral calculation of this controller.
Definition ProfiledPIDController.h:188
constexpr void SetGoal(State goal)
Sets the goal for the ProfiledPIDController.
Definition ProfiledPIDController.h:197
constexpr State GetSetpoint() const
Returns the current setpoint of the ProfiledPIDController.
Definition ProfiledPIDController.h:239
constexpr ProfiledPIDController & operator=(ProfiledPIDController &&)=default
constexpr void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
Definition ProfiledPIDController.h:98
constexpr void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
Definition ProfiledPIDController.h:105
constexpr void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
Definition ProfiledPIDController.h:89
constexpr void Reset(Distance_t measuredPosition, Velocity_t measuredVelocity)
Reset the previous error and the integral term.
Definition ProfiledPIDController.h:402
constexpr void SetGoal(Distance_t goal)
Sets the goal for the ProfiledPIDController.
Definition ProfiledPIDController.h:204
constexpr double Calculate(Distance_t measurement, Distance_t goal)
Returns the next output of the PID controller.
Definition ProfiledPIDController.h:367
constexpr void EnableContinuousInput(Distance_t minimumInput, Distance_t maximumInput)
Enables continuous input.
Definition ProfiledPIDController.h:262
constexpr void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
Definition ProfiledPIDController.h:112
constexpr double GetIZone() const
Get the IZone range.
Definition ProfiledPIDController.h:153
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
Definition ProfiledPIDController.h:417
constexpr State GetGoal() const
Gets the goal for the ProfiledPIDController.
Definition ProfiledPIDController.h:209
constexpr double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
Definition ProfiledPIDController.h:178
constexpr void Reset(const State &measurement)
Reset the previous error and the integral term.
Definition ProfiledPIDController.h:391
typename TrapezoidProfile< Distance >::State State
Definition ProfiledPIDController.h:43
constexpr void Reset(Distance_t measuredPosition)
Reset the previous error and the integral term.
Definition ProfiledPIDController.h:413
units::compound_unit< Velocity, units::inverse< units::seconds > > Acceleration
Definition ProfiledPIDController.h:40
constexpr double GetI() const
Gets the integral coefficient.
Definition ProfiledPIDController.h:139
constexpr double GetP() const
Gets the proportional coefficient.
Definition ProfiledPIDController.h:132
constexpr Constraints GetConstraints()
Get the velocity and acceleration constraints for this controller.
Definition ProfiledPIDController.h:232
constexpr ProfiledPIDController(ProfiledPIDController &&)=default
Profile constraints.
Definition TrapezoidProfile.h:59
Profile state.
Definition TrapezoidProfile.h:96
A trapezoid-shaped velocity profile.
Definition TrapezoidProfile.h:46
constexpr underlying_type value() const noexcept
unit value
Definition base.h:2111
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.h:21
virtual void AddDoubleProperty(std::string_view key, std::function< double()> getter, std::function< void(double)> setter)=0
Add a double property.
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...
A helper class for use with objects that add themselves to SendableRegistry.
Definition SendableHelper.h:21
Interface for Sendable objects.
Definition Sendable.h:16
static void Add(Sendable *sendable, std::string_view name)
Adds an object to the registry.
static void ReportUsage(MathUsageId id, int count)
Definition MathShared.h:75
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition base.h:1438
detail namespace with internal helper functions
Definition input_adapters.h:32
WPILIB_DLLEXPORT int IncrementAndGetProfiledPIDControllerInstances()
constexpr T InputModulus(T input, T minimumInput, T maximumInput)
Returns modulus of input.
Definition MathUtil.h:95
@ kController_ProfiledPIDController