diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index e34a99c..821a08e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -54,6 +54,16 @@ public class RobotContainer { () -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND), () -> driverXbox.getRawAxis(2)); + Command driveFieldOrientedAnglularVelocityPrecision = + drivebase.driveCommand( + () -> + MathUtil.applyDeadband( + -driverXbox.getLeftY() * 0.5, OperatorConstants.LEFT_Y_DEADBAND), + () -> + MathUtil.applyDeadband( + -driverXbox.getLeftX() * 0.5, OperatorConstants.LEFT_X_DEADBAND), + () -> driverXbox.getRightX() * -1 * 0.5); + /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { NamedCommands.registerCommand("Pivot Up", pivot.pivotUp()); @@ -84,7 +94,7 @@ private void configureBindings() { driverXbox.leftBumper().whileTrue(Commands.none()); driverXbox.leftTrigger().whileTrue(intake.intakeBucket()); driverXbox.rightTrigger().whileTrue(intake.outtakeBucket()); - driverXbox.rightBumper().onTrue(Commands.none()); + driverXbox.rightBumper().whileTrue(driveFieldOrientedAnglularVelocityPrecision); drivebase.setDefaultCommand( !RobotBase.isSimulation() ? driveFieldOrientedAnglularVelocity