[examples] Move triggers to subsystem fields (#6318)

This commit is contained in:
DeltaDizzy
2024-01-28 01:47:06 -06:00
committed by GitHub
parent 177132fa2a
commit 53ebb6679e
5 changed files with 18 additions and 22 deletions

View File

@@ -12,16 +12,13 @@
void RapidReactCommandBot::ConfigureBindings() {
// Automatically run the storage motor whenever the ball storage is not full,
// and turn it off whenever it fills.
frc2::Trigger([this] {
return m_storage.IsFull();
}).WhileFalse(m_storage.RunCommand());
// and turn it off whenever it fills. Uses subsystem-hosted trigger to
// improve readability and make inter-subsystem communication easier.
m_storage.HasCargo.WhileFalse(m_storage.RunCommand());
// Automatically disable and retract the intake whenever the ball storage is
// full.
frc2::Trigger([this] {
return m_storage.IsFull();
}).OnTrue(m_intake.RetractCommand());
m_storage.HasCargo.OnTrue(m_intake.RetractCommand());
// Control the drive with split-stick arcade controls
m_drive.SetDefaultCommand(m_drive.ArcadeDriveCommand(

View File

@@ -12,7 +12,3 @@ Storage::Storage() {
frc2::CommandPtr Storage::RunCommand() {
return Run([this] { m_motor.Set(1.0); }).WithName("Run");
}
bool Storage::IsFull() const {
return m_ballSensor.Get();
}

View File

@@ -8,6 +8,7 @@
#include <frc/motorcontrol/PWMSparkMax.h>
#include <frc2/command/CommandPtr.h>
#include <frc2/command/SubsystemBase.h>
#include <frc2/command/button/Trigger.h>
#include "Constants.h"
@@ -19,7 +20,7 @@ class Storage : frc2::SubsystemBase {
frc2::CommandPtr RunCommand();
/** Whether the ball storage is full. */
bool IsFull() const;
frc2::Trigger HasCargo{[this] { return m_ballSensor.Get(); }};
private:
frc::PWMSparkMax m_motor{StorageConstants::kMotorPort};