diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java index 0f28d852ec..549de24d9f 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java @@ -20,8 +20,6 @@ public abstract class ProfiledPIDSubsystem extends SubsystemBase { protected final ProfiledPIDController m_controller; protected boolean m_enabled; - private TrapezoidProfile.State m_goal; - /** * Creates a new ProfiledPIDSubsystem. * @@ -45,7 +43,7 @@ public abstract class ProfiledPIDSubsystem extends SubsystemBase { @Override public void periodic() { if (m_enabled) { - useOutput(m_controller.calculate(getMeasurement(), m_goal), m_controller.getSetpoint()); + useOutput(m_controller.calculate(getMeasurement()), m_controller.getSetpoint()); } } @@ -59,7 +57,7 @@ public abstract class ProfiledPIDSubsystem extends SubsystemBase { * @param goal The goal state for the subsystem's motion profile. */ public void setGoal(TrapezoidProfile.State goal) { - m_goal = goal; + m_controller.setGoal(goal); } /** diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h index 032ee4b958..cfdfc6b631 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h @@ -41,7 +41,7 @@ class ProfiledPIDSubsystem : public SubsystemBase { void Periodic() override { if (m_enabled) { - UseOutput(m_controller.Calculate(GetMeasurement(), m_goal), + UseOutput(m_controller.Calculate(GetMeasurement()), m_controller.GetSetpoint()); } } @@ -51,14 +51,14 @@ class ProfiledPIDSubsystem : public SubsystemBase { * * @param goal The goal state for the subsystem's motion profile. */ - void SetGoal(State goal) { m_goal = goal; } + void SetGoal(State goal) { m_controller.SetGoal(goal); } /** * Sets the goal state for the subsystem. Goal velocity assumed to be zero. * * @param goal The goal position for the subsystem's motion profile. */ - void SetGoal(Distance_t goal) { m_goal = State{goal, Velocity_t(0)}; } + void SetGoal(Distance_t goal) { SetGoal(State{goal, Velocity_t(0)}); } /** * Enables the PID control. Resets the controller. @@ -110,8 +110,5 @@ class ProfiledPIDSubsystem : public SubsystemBase { * feedforward */ virtual void UseOutput(double output, State setpoint) = 0; - - private: - State m_goal; }; } // namespace frc2