Skip to content

Commit

Permalink
commented elvis
Browse files Browse the repository at this point in the history
  • Loading branch information
PGgit08 committed Mar 12, 2024
1 parent bbfc6e8 commit 6ad5ab0
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 19 deletions.
5 changes: 2 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -167,9 +167,8 @@ private void configureBindings() {
_driveController.R1().onTrue(Commands.runOnce(() -> _swerveSubsystem.fieldOriented = !_swerveSubsystem.fieldOriented, _swerveSubsystem));
_driveController.L1().onTrue(Commands.runOnce(() -> _swerveSubsystem.resetPose(new Pose2d()), _swerveSubsystem));
_driveController.cross().whileTrue(new BrakeSwerve(_swerveSubsystem, _ledSubsystem));
_driveController.L2().onTrue(Commands.runOnce(() -> _swerveSubsystem.toggleSpeed(), _swerveSubsystem));


_driveController.L2().onTrue(Commands.runOnce(_swerveSubsystem::toggleSpeed, _swerveSubsystem));

_driveController.R2().whileTrue(
new AutoAim(
_shooterSubsystem,
Expand Down
38 changes: 22 additions & 16 deletions src/main/java/frc/robot/subsystems/SwerveDriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -206,6 +206,28 @@ private void setupOrchestra() {
_orchestra.play();
}

/**
* Toggle the driving speed between slow/fast.
*/
public void toggleSpeed(){
if (_drivingState == DrivingSpeeds.FAST) {
_drivingState = DrivingSpeeds.SLOW;
} else {
_drivingState = DrivingSpeeds.FAST;
}
}

/**
* Get drive coeff based on toggled speed.
*/
public double getDriveCoeff() {
if (_drivingState == DrivingSpeeds.FAST) {
return Constants.Speeds.SWERVE_DRIVE_FAST_COEFF;
} else {
return Constants.Speeds.SWERVE_DRIVE_SLOW_COEFF;
}
}

/**
* Set the chassis speed of the swerve drive.
*
Expand Down Expand Up @@ -337,20 +359,4 @@ public void pivotMotor(Translation2d pivotPoint) {
public void resetPivot() {
_pivotPoint = new Translation2d(0, 0);
}

public void toggleSpeed(){
if (_drivingState == DrivingSpeeds.FAST) {
_drivingState = DrivingSpeeds.SLOW;
} else {
_drivingState = DrivingSpeeds.FAST;
}
}

public double getDriveCoeff() {
if (_drivingState == DrivingSpeeds.FAST) {
return Constants.Speeds.SWERVE_DRIVE_FAST_COEFF;
} else {
return Constants.Speeds.SWERVE_DRIVE_SLOW_COEFF;
}
}
}

0 comments on commit 6ad5ab0

Please sign in to comment.