32template <
class Distance>
60 Constraints constraints, units::second_t period = 20_ms)
61 : m_controller(Kp, Ki, Kd, period), m_constraints(constraints) {
84 void SetPID(
double Kp,
double Ki,
double Kd) {
85 m_controller.
SetPID(Kp, Ki, Kd);
93 void SetP(
double Kp) { m_controller.
SetP(Kp); }
126 double GetP()
const {
return m_controller.
GetP(); }
133 double GetI()
const {
return m_controller.
GetI(); }
140 double GetD()
const {
return m_controller.
GetD(); }
243 maximumInput.
value());
244 m_minimumInput = minimumInput;
245 m_maximumInput = maximumInput;
275 std::numeric_limits<double>::infinity()}) {
277 velocityTolerance.value());
304 auto errorBound = (m_maximumInput - m_minimumInput) / 2.0;
305 auto goalMinDistance = frc::InputModulus<Distance_t>(
306 m_goal.position - measurement, -errorBound, errorBound);
307 auto setpointMinDistance = frc::InputModulus<Distance_t>(
308 m_setpoint.position - measurement, -errorBound, errorBound);
316 m_goal.position = goalMinDistance + measurement;
317 m_setpoint.position = setpointMinDistance + measurement;
321 m_setpoint = profile.Calculate(
GetPeriod());
323 m_setpoint.position.value());
367 m_controller.
Reset();
368 m_setpoint = measurement;
378 Reset(
State{measuredPosition, measuredVelocity});
400 "izone", [
this] {
return GetIZone(); },
403 "goal", [
this] {
return GetGoal().position.value(); },
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Implements a PID control loop.
Definition: PIDController.h:23
void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
double Calculate(double measurement)
Returns the next output of the PID controller.
double GetIZone() const
Get the IZone range.
void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
double GetP() const
Gets the proportional coefficient.
void SetTolerance(double positionTolerance, double velocityTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
double GetPositionTolerance() const
Gets the position tolerance of this controller.
double GetI() const
Gets the integral coefficient.
void DisableContinuousInput()
Disables continuous input.
double GetD() const
Gets the differential coefficient.
void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
double GetPositionError() const
Returns the difference between the setpoint and the measurement.
void SetIZone(double iZone)
Sets the IZone range.
void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
void Reset()
Reset the previous error, the integral term, and disable the controller.
double GetVelocityError() const
Returns the velocity error.
units::second_t GetPeriod() const
Gets the period of this controller.
void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.
bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
Implements a PID control loop whose setpoint is constrained by a trapezoid profile.
Definition: ProfiledPIDController.h:35
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:59
double GetP() const
Gets the proportional coefficient.
Definition: ProfiledPIDController.h:126
State GetSetpoint() const
Returns the current setpoint of the ProfiledPIDController.
Definition: ProfiledPIDController.h:218
double Calculate(Distance_t measurement, Distance_t goal)
Returns the next output of the PID controller.
Definition: ProfiledPIDController.h:342
ProfiledPIDController & operator=(ProfiledPIDController &&)=default
void Reset(Distance_t measuredPosition)
Reset the previous error and the integral term.
Definition: ProfiledPIDController.h:387
State GetGoal() const
Gets the goal for the ProfiledPIDController.
Definition: ProfiledPIDController.h:191
bool AtSetpoint() const
Returns true if the error is within the tolerance of the error.
Definition: ProfiledPIDController.h:229
double Calculate(Distance_t measurement, State goal)
Returns the next output of the PID controller.
Definition: ProfiledPIDController.h:332
units::unit_t< Distance > Distance_t
Definition: ProfiledPIDController.h:37
typename TrapezoidProfile< Distance >::Constraints Constraints
Definition: ProfiledPIDController.h:45
Distance_t GetPositionError() const
Returns the difference between the setpoint and the measurement.
Definition: ProfiledPIDController.h:285
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:273
void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.
Definition: ProfiledPIDController.h:262
void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
Definition: ProfiledPIDController.h:100
ProfiledPIDController(const ProfiledPIDController &)=default
void SetGoal(Distance_t goal)
Sets the goal for the ProfiledPIDController.
Definition: ProfiledPIDController.h:186
void DisableContinuousInput()
Disables continuous input.
Definition: ProfiledPIDController.h:251
void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
Definition: ProfiledPIDController.h:107
units::second_t GetPeriod() const
Gets the period of this controller.
Definition: ProfiledPIDController.h:154
Velocity_t GetVelocityError() const
Returns the change in error per second.
Definition: ProfiledPIDController.h:292
double GetD() const
Gets the differential coefficient.
Definition: ProfiledPIDController.h:140
void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
Definition: ProfiledPIDController.h:93
double GetPositionTolerance() const
Gets the position tolerance of this controller.
Definition: ProfiledPIDController.h:161
double GetIZone() const
Get the IZone range.
Definition: ProfiledPIDController.h:147
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:354
void EnableContinuousInput(Distance_t minimumInput, Distance_t maximumInput)
Enables continuous input.
Definition: ProfiledPIDController.h:241
ProfiledPIDController(ProfiledPIDController &&)=default
double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
Definition: ProfiledPIDController.h:170
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
Definition: ProfiledPIDController.h:391
ProfiledPIDController & operator=(const ProfiledPIDController &)=default
units::compound_unit< Velocity, units::inverse< units::seconds > > Acceleration
Definition: ProfiledPIDController.h:42
typename TrapezoidProfile< Distance >::State State
Definition: ProfiledPIDController.h:44
void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
Definition: ProfiledPIDController.h:84
void Reset(const State &measurement)
Reset the previous error and the integral term.
Definition: ProfiledPIDController.h:366
units::compound_unit< Distance, units::inverse< units::seconds > > Velocity
Definition: ProfiledPIDController.h:39
double Calculate(Distance_t measurement)
Returns the next output of the PID controller.
Definition: ProfiledPIDController.h:301
void Reset(Distance_t measuredPosition, Velocity_t measuredVelocity)
Reset the previous error and the integral term.
Definition: ProfiledPIDController.h:377
void SetGoal(State goal)
Sets the goal for the ProfiledPIDController.
Definition: ProfiledPIDController.h:179
double GetI() const
Gets the integral coefficient.
Definition: ProfiledPIDController.h:133
Constraints GetConstraints()
Get the velocity and acceleration constraints for this controller.
Definition: ProfiledPIDController.h:211
~ProfiledPIDController() override=default
void SetConstraints(Constraints constraints)
Set velocity and acceleration constraints for goal.
Definition: ProfiledPIDController.h:205
bool AtGoal() const
Returns true if the error is within the tolerance of the error.
Definition: ProfiledPIDController.h:198
void SetIZone(double iZone)
Sets the IZone range.
Definition: ProfiledPIDController.h:119
Definition: TrapezoidProfile.h:52
Definition: TrapezoidProfile.h:67
A trapezoid-shaped velocity profile.
Definition: TrapezoidProfile.h:42
constexpr underlying_type value() const noexcept
unit value
Definition: base.h:2118
Definition: SendableBuilder.h:18
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:19
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:73
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition: base.h:1445
Definition: format-inl.h:32
WPILIB_DLLEXPORT int IncrementAndGetProfiledPIDControllerInstances()
Definition: AprilTagPoseEstimator.h:15
@ kController_ProfiledPIDController