mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Minor improvements/fixes to new command framework (#2186)
This commit is contained in:
@@ -24,8 +24,9 @@ class PIDSubsystem : public SubsystemBase {
|
||||
* Creates a new PIDSubsystem.
|
||||
*
|
||||
* @param controller the PIDController to use
|
||||
* @param initialPosition the initial setpoint of the subsystem
|
||||
*/
|
||||
explicit PIDSubsystem(PIDController controller);
|
||||
explicit PIDSubsystem(PIDController controller, double initialPosition = 0);
|
||||
|
||||
void Periodic() override;
|
||||
|
||||
@@ -62,7 +63,7 @@ class PIDSubsystem : public SubsystemBase {
|
||||
|
||||
protected:
|
||||
PIDController m_controller;
|
||||
bool m_enabled;
|
||||
bool m_enabled{false};
|
||||
|
||||
/**
|
||||
* Returns the measurement of the process variable used by the PIDController.
|
||||
|
||||
@@ -32,9 +32,13 @@ class ProfiledPIDSubsystem : public SubsystemBase {
|
||||
* Creates a new ProfiledPIDSubsystem.
|
||||
*
|
||||
* @param controller the ProfiledPIDController to use
|
||||
* @param initialPosition the initial goal position of the subsystem
|
||||
*/
|
||||
explicit ProfiledPIDSubsystem(frc::ProfiledPIDController<Distance> controller)
|
||||
: m_controller{controller} {}
|
||||
explicit ProfiledPIDSubsystem(frc::ProfiledPIDController<Distance> controller,
|
||||
Distance_t initialPosition = Distance_t{0})
|
||||
: m_controller{controller} {
|
||||
SetGoal(initialPosition);
|
||||
}
|
||||
|
||||
void Periodic() override {
|
||||
if (m_enabled) {
|
||||
|
||||
@@ -42,7 +42,7 @@ class TrapezoidProfileCommand
|
||||
*/
|
||||
TrapezoidProfileCommand(frc::TrapezoidProfile<Distance> profile,
|
||||
std::function<void(State)> output,
|
||||
std::initializer_list<Subsystem*> requirements)
|
||||
std::initializer_list<Subsystem*> requirements = {})
|
||||
: m_profile(profile), m_output(output) {
|
||||
this->AddRequirements(requirements);
|
||||
}
|
||||
|
||||
@@ -37,18 +37,21 @@ class TrapezoidProfileSubsystem : public SubsystemBase {
|
||||
* when the subsystem is constructed.
|
||||
* @param period The period of the main robot loop, in seconds.
|
||||
*/
|
||||
TrapezoidProfileSubsystem(Constraints constraints, Distance_t position,
|
||||
units::second_t period = 20_ms)
|
||||
explicit TrapezoidProfileSubsystem(Constraints constraints,
|
||||
Distance_t initialPosition = Distance_t{0},
|
||||
units::second_t period = 20_ms)
|
||||
: m_constraints(constraints),
|
||||
m_state{position, Velocity_t(0)},
|
||||
m_goal{position, Velocity_t{0}},
|
||||
m_state{initialPosition, Velocity_t(0)},
|
||||
m_goal{initialPosition, Velocity_t{0}},
|
||||
m_period(period) {}
|
||||
|
||||
void Periodic() override {
|
||||
auto profile =
|
||||
frc::TrapezoidProfile<Distance>(m_constraints, m_goal, m_state);
|
||||
m_state = profile.Calculate(m_period);
|
||||
UseState(m_state);
|
||||
if (m_enabled) {
|
||||
UseState(m_state);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -74,10 +77,21 @@ class TrapezoidProfileSubsystem : public SubsystemBase {
|
||||
*/
|
||||
virtual void UseState(State state) = 0;
|
||||
|
||||
/**
|
||||
* Enable the TrapezoidProfileSubsystem's output.
|
||||
*/
|
||||
void Enable() { m_enabled = true; }
|
||||
|
||||
/**
|
||||
* Disable the TrapezoidProfileSubsystem's output.
|
||||
*/
|
||||
void Disable() { m_enabled = false; }
|
||||
|
||||
private:
|
||||
Constraints m_constraints;
|
||||
State m_state;
|
||||
State m_goal;
|
||||
units::second_t m_period;
|
||||
bool m_enabled{false};
|
||||
};
|
||||
} // namespace frc2
|
||||
|
||||
Reference in New Issue
Block a user