Skip to content

Commit

Permalink
Add Slow Mode and Fix Controller Inputs
Browse files Browse the repository at this point in the history
  • Loading branch information
S0L0GUY authored and TaylerUva committed Nov 10, 2024
1 parent d572fb0 commit 2a8b7b8
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 6 deletions.
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,7 @@ public class RobotContainer {
private final Hopper subHopper = new Hopper();
private final Shooter subShooter = new Shooter();
private final Stager subStager = new Stager();
private final Drive com_Drive = new Drive(subDrivetrain, m_driverController.axis_LeftY,
m_driverController.axis_RightX);
private final Drive com_Drive = new Drive(subDrivetrain, m_driverController.axis_RightX, m_driverController.axis_LeftY, m_driverController.btn_LeftBumper);
private final IntakeGround com_IntakeGround = new IntakeGround(subIntake, subStager);
private final PrepShooter com_PrepShooter = new PrepShooter(subShooter);
private final HasGP com_StageGP = new HasGP(subStager);
Expand Down
7 changes: 5 additions & 2 deletions src/main/java/frc/robot/commands/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import java.util.function.DoubleSupplier;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.subsystems.Drivetrain;

public class Drive extends Command {
Expand All @@ -15,12 +16,14 @@ public class Drive extends Command {
Drivetrain globalDrivetrain;
DoubleSupplier globalForwardSpeed;
DoubleSupplier globalRotationSpeed;
Trigger globalSlowMode;

public Drive(Drivetrain passedDrivetrain, DoubleSupplier passedForwardSpeed, DoubleSupplier passedRotationSpeed) {
public Drive(Drivetrain passedDrivetrain, DoubleSupplier passedForwardSpeed, DoubleSupplier passedRotationSpeed, Trigger btn_LeftBumper) {
// Use addRequirements() here to declare subsystem dependencies.
globalDrivetrain = passedDrivetrain;
globalForwardSpeed = passedForwardSpeed;
globalRotationSpeed = passedRotationSpeed;
globalSlowMode = btn_LeftBumper;

addRequirements(globalDrivetrain);
}
Expand All @@ -32,7 +35,7 @@ public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
globalDrivetrain.setDrivetrainSpeed(globalForwardSpeed.getAsDouble(), globalRotationSpeed.getAsDouble());
globalDrivetrain.setDrivetrainSpeed(globalForwardSpeed.getAsDouble(), globalRotationSpeed.getAsDouble(), globalSlowMode.getAsBoolean());
}

// Called once the command ends or is interrupted.
Expand Down
9 changes: 7 additions & 2 deletions src/main/java/frc/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,16 @@ public Drivetrain() {
* drivetrain.
* @param rotationSpeed The rotation speed to apply to the drivetrain.
*/
public void setDrivetrainSpeed(double forwardVelocity, double rotationSpeed) {
public void setDrivetrainSpeed(double forwardVelocity, double rotationSpeed, boolean leftBumperDown) {
// Divide speed in half if slow mode is activated
if (leftBumperDown) {
forwardVelocity = forwardVelocity * 0.5;
rotationSpeed = rotationSpeed * 0.5;
}

// Set right velocity
frontRightMotor.set(forwardVelocity - rotationSpeed);
backRightMotor.set(forwardVelocity - rotationSpeed);

// Set left velocity
frontLeftMotor.set(forwardVelocity + rotationSpeed);
backLeftMotor.set(forwardVelocity + rotationSpeed);
Expand Down

0 comments on commit 2a8b7b8

Please sign in to comment.