|
17 | 17 | import edu.wpi.first.math.geometry.Pose2d; |
18 | 18 | import edu.wpi.first.math.geometry.Rotation2d; |
19 | 19 | import edu.wpi.first.wpilibj.GenericHID; |
| 20 | +import edu.wpi.first.wpilibj.RobotController; |
20 | 21 | import edu.wpi.first.wpilibj.XboxController; |
21 | 22 | import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; |
22 | 23 | import edu.wpi.first.wpilibj2.command.Command; |
@@ -478,6 +479,18 @@ private void configureButtonBindings() { |
478 | 479 | } |
479 | 480 |
|
480 | 481 | private void demoControls() { |
| 482 | + // led.setDefaultCommand(new BatteryDisplay(led)); |
| 483 | + // alternatively |
| 484 | + // new Trigger(() -> RobotController.getBatteryVoltage() < 11) |
| 485 | + // .onTrue( |
| 486 | + // new InstantCommand(() -> led.setState(LED_STATE.PURPLE)) |
| 487 | + // .andThen(new WaitCommand(0.2)) |
| 488 | + // .andThen(new InstantCommand(() -> led.setState(LED_STATE.YELLOW)))); |
| 489 | + // alternatively alternatively |
| 490 | + new Trigger(() -> RobotController.getBatteryVoltage() < 11) |
| 491 | + .onTrue(new InstantCommand(() -> led.setState(LED_STATE.PURPLE))) |
| 492 | + .onFalse(new InstantCommand(() -> led.setState(LED_STATE.YELLOW))); |
| 493 | + |
481 | 494 | drive.setDefaultCommand( |
482 | 495 | DriveCommands.joystickDrive( |
483 | 496 | drive, |
@@ -592,28 +605,28 @@ private void demoControls() { |
592 | 605 | // new InstantCommand(() -> trapStateMachine.setTargetState(TRAP_STATES.PIVOT)), |
593 | 606 | // new SetElevatorTarget(0, 1.5, elevator), |
594 | 607 | new InstantCommand(() -> pivot.setShootState(SHOOT_STATE.PIVOT_PRESET)), |
595 | | - new SetPivotTarget(45, pivot), |
596 | | - new InstantCommand(() -> shooter.setFlywheelRPMs(1500, 1900)))); |
| 608 | + new SetPivotTarget(60, pivot), |
| 609 | + new InstantCommand(() -> shooter.setFlywheelRPMs(1200, 1600)))); |
597 | 610 | driveController |
598 | 611 | .b() |
599 | 612 | .onFalse( |
600 | 613 | new InstantCommand(() -> led.setState(LED_STATE.BLUE)) |
601 | 614 | .andThen(new InstantCommand(() -> shooter.stopFlywheels())) |
602 | 615 | .andThen(new SetPivotTarget(Constants.PivotConstants.STOW_SETPOINT_DEG, pivot))); |
603 | | - |
604 | | - driveController |
605 | | - .a() |
606 | | - .onTrue( |
607 | | - new SequentialCommandGroup( |
608 | | - new InstantCommand(() -> pivot.setShootState(SHOOT_STATE.PIVOT_PRESET)), |
609 | | - new SetPivotTarget(45, pivot), |
610 | | - new InstantCommand(() -> shooter.setFlywheelRPMs(5600, 6000)))); |
611 | | - driveController |
612 | | - .a() |
613 | | - .onFalse( |
614 | | - new InstantCommand(() -> led.setState(LED_STATE.BLUE)) |
615 | | - .andThen(new InstantCommand(() -> shooter.stopFlywheels())) |
616 | | - .andThen(new SetPivotTarget(Constants.PivotConstants.STOW_SETPOINT_DEG, pivot))); |
| 616 | + |
| 617 | + // driveController |
| 618 | + // .a() |
| 619 | + // .onTrue( |
| 620 | + // new SequentialCommandGroup( |
| 621 | + // new InstantCommand(() -> pivot.setShootState(SHOOT_STATE.PIVOT_PRESET)), |
| 622 | + // new SetPivotTarget(60, pivot), |
| 623 | + // new InstantCommand(() -> shooter.setFlywheelRPMs(5600, 6000)))); |
| 624 | + // driveController |
| 625 | + // .a() |
| 626 | + // .onFalse( |
| 627 | + // new InstantCommand(() -> led.setState(LED_STATE.BLUE)) |
| 628 | + // .andThen(new InstantCommand(() -> shooter.stopFlywheels())) |
| 629 | + // .andThen(new SetPivotTarget(Constants.PivotConstants.STOW_SETPOINT_DEG, pivot))); |
617 | 630 |
|
618 | 631 | driveController.back().onTrue(new SetPivotTarget(95, pivot)); |
619 | 632 | } |
|
0 commit comments