Intake (Command-Based)
Template Project
Start with the Command Robot template project. In VS Code, create a new WPILib project and select "Command Robot" from the template list. This template provides
Robot.java, RobotContainer.java, and an example subsystem structure.Overview
We will rebuild the intake using the command-based framework. This separates hardware control (Subsystem), actions (Commands), and button bindings (RobotContainer) for better organization and safety.
Step 1: Create the Subsystem Class
Start by creating a new class called
Intake that extends SubsystemBase. This class will encapsulate all hardware-related code for the intake motor.Step 1a: Subsystem Structure
Create the basic class structure with imports:
package frc.robot.subsystems;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.ctre.phoenix6.controls.DutyCycleOut;
public class Intake extends SubsystemBase {
// We'll add fields and methods here
}Step 1b: Declare Motor Field
Add a field for the intake motor. The motor is on CAN ID 5. For Talon FX, we also create a control request object that we'll reuse.
Add the motor field to the class:
public class Intake extends SubsystemBase {
// Intake motor on CAN ID 5
private final TalonFX m_motor = new TalonFX(5);
private final DutyCycleOut m_out = new DutyCycleOut(0);
}Step 1c: Configure Motor in Constructor
In the constructor, configure the motor with appropriate settings. We use Coast mode (allows free spinning when stopped) and enable current limiting to protect the motor.
Add constructor with motor configuration:
public Intake() {
// Configure motor for intake use
TalonFXConfiguration config = new TalonFXConfiguration();
// Coast mode allows free spinning when stopped
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
// Enable current limiting to protect motor
config.CurrentLimits.StatorCurrentLimitEnable = true;
config.CurrentLimits.StatorCurrentLimit = 30.0;
m_motor.getConfigurator().apply(config);
}Step 1d: Add Public Methods
Add public methods that commands can use to control the intake. These methods hide the hardware details from the rest of the code.
Add methods to run and stop the intake:
/**
* Run the intake at the specified speed
* @param speed Motor speed (-1.0 to 1.0, positive = collect)
*/
public void run(double speed) {
m_motor.setControl(m_out.withOutput(speed));
}
/**
* Stop the intake motor
*/
public void stop() {
m_motor.setControl(m_out.withOutput(0.0));
}Step 2: Set Up RobotContainer
Create or update the
RobotContainer class. This class creates subsystems and binds buttons to commands. It's the central place where we wire everything together.Step 2a: RobotContainer Structure
package frc.robot;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.subsystems.Intake;
public class RobotContainer {
// The template provides ExampleSubsystem - replace with your subsystems
// We'll add fields here next
}Step 2b: Create Subsystem and Controller
Declare the intake subsystem and controller as fields. These are created once and reused throughout the robot's operation.
public class RobotContainer {
// Create subsystem instance
private final Intake m_intake = new Intake();
// Create controller on USB port 1
private final CommandXboxController m_controller = new CommandXboxController(1);
}Step 2c: Configure Button Bindings
In the constructor, set up a default command that stops the intake when no other command is running. Then bind buttons: Button A runs the intake forward while held, and Button B runs it reverse while held.
public RobotContainer() {
// Default command: Stop intake when no other command is running
m_intake.setDefaultCommand(new RunCommand(() -> m_intake.stop(), m_intake));
// Button bindings
// Button A: Run intake forward (collect) while held
m_controller.a().whileTrue(new RunCommand(() -> m_intake.run(0.6), m_intake));
// Button B: Run intake reverse (eject) while held
m_controller.b().whileTrue(new RunCommand(() -> m_intake.run(-0.4), m_intake));
}Understanding Default Commands
The default command runs whenever the subsystem is not being used by another command. This ensures the motor stops automatically when no button is pressed, providing a safety mechanism.
Full Code - Intake Subsystem
Complete Intake subsystem implementation:
package frc.robot.subsystems;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.ctre.phoenix6.controls.DutyCycleOut;
public class Intake extends SubsystemBase {
// Intake motor on CAN ID 5
private final TalonFX m_motor = new TalonFX(5);
private final DutyCycleOut m_out = new DutyCycleOut(0);
public Intake() {
// Configure motor for intake use
TalonFXConfiguration config = new TalonFXConfiguration();
// Coast mode allows free spinning when stopped
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
// Enable current limiting to protect motor
config.CurrentLimits.StatorCurrentLimitEnable = true;
config.CurrentLimits.StatorCurrentLimit = 30.0;
m_motor.getConfigurator().apply(config);
}
/**
* Run the intake at the specified speed
* @param speed Motor speed (-1.0 to 1.0, positive = collect)
*/
public void run(double speed) {
m_motor.setControl(m_out.withOutput(speed));
}
/**
* Stop the intake motor
*/
public void stop() {
m_motor.setControl(m_out.withOutput(0.0));
}
}Full Code - RobotContainer
package frc.robot;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.subsystems.Intake;
public class RobotContainer {
// Create subsystem instance
private final Intake m_intake = new Intake();
// The template uses Constants.OperatorConstants.kDriverControllerPort
// For this example, we'll use port 1 directly
private final CommandXboxController m_controller = new CommandXboxController(1);
public RobotContainer() {
// Configure button bindings (template provides configureBindings() method)
configureBindings();
// Default command: Stop intake when no other command is running
m_intake.setDefaultCommand(new RunCommand(() -> m_intake.stop(), m_intake));
}
private void configureBindings() {
// Button A: Run intake forward (collect) while held
m_controller.a().whileTrue(new RunCommand(() -> m_intake.run(0.6), m_intake));
// Button B: Run intake reverse (eject) while held
m_controller.b().whileTrue(new RunCommand(() -> m_intake.run(-0.4), m_intake));
}
}Benefits
Why this is better:
- Encapsulation: Hardware details are hidden in the Subsystem.
- Readability: RobotContainer clearly shows controls.
- Safety: Default commands ensure motors stop.
- Flexibility: Easy to reuse the intake in Auto.