Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[examples] Move triggers to subsystem fields #6318

Merged
merged 8 commits into from
Jan 28, 2024
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Starlight220 marked this conversation as resolved.
Show resolved Hide resolved

// 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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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"

Expand All @@ -21,6 +22,11 @@ class Storage : frc2::SubsystemBase {
/** Whether the ball storage is full. */
bool IsFull() const;

/** Exposes the IsFull trigger. */
frc2::Trigger HasCargo{[this] {
return IsFull();
}};

private:
frc::PWMSparkMax m_motor{StorageConstants::kMotorPort};
frc::DigitalInput m_ballSensor{StorageConstants::kBallSensorPort};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,11 +46,12 @@ public class RapidReactCommandBot {
*/
public void configureBindings() {
// Automatically run the storage motor whenever the ball storage is not full,
// and turn it off whenever it fills.
new Trigger(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.
new Trigger(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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,19 @@

package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;

import static edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.StorageConstants;

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.StorageConstants;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.button.Trigger;

public class Storage extends SubsystemBase {
private final PWMSparkMax m_motor = new PWMSparkMax(StorageConstants.kMotorPort);
private final DigitalInput m_ballSensor = new DigitalInput(StorageConstants.kBallSensorPort);
// Expose trigger from subsystem to improve readability and ease
// inter-subsystem communications
public final Trigger hasCargo = new Trigger(this::isFull);

/** Create a new Storage subsystem. */
public Storage() {
Expand Down
Loading