Skip to content

Commit

Permalink
Merge branch 'lance/pivot' of https://github.com/team614frc/Team-614-…
Browse files Browse the repository at this point in the history
…Bunny-Bandits into lance/pivot
  • Loading branch information
RealSirLancelot committed Dec 7, 2024
2 parents 752d8ce + 4c1d729 commit 71c7931
Showing 1 changed file with 11 additions and 1 deletion.
12 changes: 11 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down Expand Up @@ -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
Expand Down

0 comments on commit 71c7931

Please sign in to comment.