Skip to content

Use fluent command builders #15

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

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all 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
Empty file modified gradlew
100644 → 100755
Empty file.
18 changes: 7 additions & 11 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
import frc.robot.Constants.OIConstants;
import frc.robot.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SwerveControllerCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import java.util.List;
Expand Down Expand Up @@ -49,13 +48,12 @@ public RobotContainer() {
m_robotDrive.setDefaultCommand(
// The left stick controls translation of the robot.
// Turning is controlled by the X axis of the right stick.
new RunCommand(
() -> m_robotDrive.drive(
-MathUtil.applyDeadband(m_driverController.getLeftY(), OIConstants.kDriveDeadband),
-MathUtil.applyDeadband(m_driverController.getLeftX(), OIConstants.kDriveDeadband),
-MathUtil.applyDeadband(m_driverController.getRightX(), OIConstants.kDriveDeadband),
true, true),
m_robotDrive));
m_robotDrive.driveCommand(
() -> -MathUtil.applyDeadband(m_driverController.getLeftY(), OIConstants.kDriveDeadband),
() -> -MathUtil.applyDeadband(m_driverController.getLeftX(), OIConstants.kDriveDeadband),
() -> -MathUtil.applyDeadband(m_driverController.getRightX(), OIConstants.kDriveDeadband),
true,
true));
}

/**
Expand All @@ -69,9 +67,7 @@ public RobotContainer() {
*/
private void configureButtonBindings() {
new JoystickButton(m_driverController, Button.kR1.value)
.whileTrue(new RunCommand(
() -> m_robotDrive.setX(),
m_robotDrive));
.whileTrue(m_robotDrive.setXCommand());
}

/**
Expand Down
47 changes: 47 additions & 0 deletions src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,11 @@
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.util.WPIUtilJNI;
import edu.wpi.first.wpilibj.ADIS16470_IMU;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants.DriveConstants;
import frc.utils.SwerveUtils;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import java.util.function.DoubleSupplier;

public class DriveSubsystem extends SubsystemBase {
// Create MAXSwerveModules
Expand Down Expand Up @@ -186,6 +188,43 @@ else if (angleDif > 0.85*Math.PI) {
m_rearRight.setDesiredState(swerveModuleStates[3]);
}

/**
* Creates a command that will drive the robot with dynamic inputs for x, y,
* and angular speeds.
*
* <p>Speed suppliers should be specified as lambdas or method references. If
* joystick inputs need to have a deadband or input squaring function applied,
* do so within the lambda function.</p>
*
* @param xSpeed provides speeds in the X direction (forward).
* @param ySpeed provides speeds in the Y direction (sideways).
* @param rot provides angular speeds.
* @param fieldRelative Whether the provided x and y speeds are relative to the
* field.
* @param rateLimit Whether to enable rate limiting for smoother control.
* @return the driving command
*
* @see <a href="https://docs.wpilib.org/en/stable/docs/software/basic-programming/functions-as-data.html">
* https://docs.wpilib.org/en/stable/docs/software/basic-programming/functions-as-data.html
* </a>
*/
public Command driveCommand(
DoubleSupplier xSpeed,
DoubleSupplier ySpeed,
DoubleSupplier rot,
boolean fieldRelative,
boolean rateLimit) {
return run(() -> {
drive(
xSpeed.getAsDouble(),
ySpeed.getAsDouble(),
rot.getAsDouble(),
fieldRelative,
rateLimit
);
});
}

/**
* Sets the wheels into an X formation to prevent movement.
*/
Expand All @@ -196,6 +235,14 @@ public void setX() {
m_rearRight.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(45)));
}

/**
* Creates a command that continually sets the wheels into an X formation to
* prevent movement.
*/
public Command setXCommand() {
return run(this::setX);
}

/**
* Sets the swerve ModuleStates.
*
Expand Down