Day 1 Qual Complete Rank 4 (Im geekin)

This commit is contained in:
Abhishrek05
2024-03-22 17:04:15 -06:00
parent 6b0e4b9cad
commit 06ce8deebe
3 changed files with 53 additions and 22 deletions
+36 -22
View File
@@ -157,8 +157,13 @@ public class RobotContainer {
private Command taxi = new JoystickPlayback(m_robotSwerveDrive, "Taxi.txt"); //new InstantCommand(); private Command taxi = new JoystickPlayback(m_robotSwerveDrive, "Taxi.txt"); //new InstantCommand();
private Command startLeftMoveRight = new InstantCommand(); // new JoystickPlayback(m_robotSwerveDrive, "StartLeftMoveRight.txt"); private Command startLeftMoveRight = new InstantCommand(); // new JoystickPlayback(m_robotSwerveDrive, "StartLeftMoveRight.txt");
private Command startRightMoveLeft = new InstantCommand(); // new JoystickPlayback(m_robotSwerveDrive, "StartRightMoveLeft.txt"); private Command startRightMoveLeft = new InstantCommand(); // new JoystickPlayback(m_robotSwerveDrive, "StartRightMoveLeft.txt");
private String lastAutoName = "final_red_center_4note_taxi.auto";
private ConfigurableString autoplaybackName = new ConfigurableString("Auto Playback Name", "defualt.auto"); private ConfigurableString autoplaybackName = new ConfigurableString("Auto Playback Name", lastAutoName);
private neoJoystickPlayback autoPlayback = new neoJoystickPlayback(m_robotSwerveDrive,
lastAutoName, // () -> autoplaybackName.get(),
new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()},
true, true);
//Help Simplify Shooting //Help Simplify Shooting
// private SequentialCommandGroup pullInArmtoShoot = new SequentialCommandGroup( // private SequentialCommandGroup pullInArmtoShoot = new SequentialCommandGroup(
@@ -289,11 +294,12 @@ public class RobotContainer {
public RobotContainer() { public RobotContainer() {
configureButtonBindings(); configureButtonBindings();
configureVirtualButtonBindings(); configureVirtualButtonBindings();
// new Trigger(() -> autoplaybackName.get().equals(lastAutoName)).onTrue(new InstantCommand(() -> changeAuto()));
new DeferredBlock(() -> m_robotSwerveDrive.resetGyro()); new DeferredBlock(() -> m_robotSwerveDrive.resetGyro());
DriverStation.silenceJoystickConnectionWarning(true); DriverStation.silenceJoystickConnectionWarning(true);
CameraServer.startAutomaticCapture().setConfigJson("{ \"width\": -512, \"height\": 512 }"); CameraServer.startAutomaticCapture();
/* Default Commands */ /* Default Commands */
// drives the robot with a two-axis input from the driver controller // drives the robot with a two-axis input from the driver controller
@@ -319,6 +325,12 @@ public class RobotContainer {
} }
// private void changeAuto() {
// autoPlayback.unloadAuto();
// autoPlayback.loadAuto();
// lastAutoName = autoplaybackName.get();
// System.out.println("AUTO: Changed auto to; `" + lastAutoName + "`");
// }
/** /**
* Use this method to define your button->command mappings. Buttons can be * Use this method to define your button->command mappings. Buttons can be
* created by instantiating a {@link GenericHID} or one of its subclasses * created by instantiating a {@link GenericHID} or one of its subclasses
@@ -333,10 +345,12 @@ public class RobotContainer {
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip(), m_robotSwerveDrive)); .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip(), m_robotSwerveDrive));
new JoystickButton(getDeadbandedDriverController(), XboxController.BACK_BUTTON) new JoystickButton(getDeadbandedDriverController(), XboxController.BACK_BUTTON)
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightBlue())); .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightBlue()))
.onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180()));
new JoystickButton(getDeadbandedDriverController(), XboxController.START_BUTTON) new JoystickButton(getDeadbandedDriverController(), XboxController.START_BUTTON)
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightAmp())); .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightAmp()))
.onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180()));
// * /* D-Pad Stuff */ // * /* D-Pad Stuff */
// new Trigger(() -> getDeadbandedDriverController().getRawAxis(XboxController.TOP_BOTTOM_DPAD_AXIS) > 0.9) // new Trigger(() -> getDeadbandedDriverController().getRawAxis(XboxController.TOP_BOTTOM_DPAD_AXIS) > 0.9)
@@ -485,10 +499,13 @@ public class RobotContainer {
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip(), m_robotSwerveDrive)); .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip(), m_robotSwerveDrive));
new JoystickButton(getVirtualDriverController(), XboxController.BACK_BUTTON) new JoystickButton(getVirtualDriverController(), XboxController.BACK_BUTTON)
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightBlue())); .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightBlue()))
.onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180()));
new JoystickButton(getVirtualDriverController(), XboxController.START_BUTTON) new JoystickButton(getVirtualDriverController(), XboxController.START_BUTTON)
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightAmp())); .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightAmp()))
.onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180()));
// * /* D-Pad Stuff */ // * /* D-Pad Stuff */
// new Trigger(() -> getVirtualDriverController().getRawAxis(XboxController.TOP_BOTTOM_DPAD_AXIS) > 0.9) // new Trigger(() -> getVirtualDriverController().getRawAxis(XboxController.TOP_BOTTOM_DPAD_AXIS) > 0.9)
@@ -524,18 +541,18 @@ public class RobotContainer {
// true))); // true)));
// ! /* Auto Recording */ // ! /* Auto Recording */
// new JoystickButton(m_autoRecorderXbox, XboxController.LEFT_BUMPER_BUTTON) new JoystickButton(m_autoRecorderXbox, XboxController.LEFT_BUMPER_BUTTON)
// .whileTrue(new neoJoystickRecorder(m_robotSwerveDrive, .whileTrue(new neoJoystickRecorder(m_robotSwerveDrive,
// new DeadbandedXboxController[]{getDeadbandedDriverController(), getDeadbandedOperatorController()}, new DeadbandedXboxController[]{getDeadbandedDriverController(), getDeadbandedOperatorController()},
// () -> autoplaybackName.get())) () -> autoplaybackName.get()))
// .onFalse(new InstantCommand()); .onFalse(new InstantCommand());
// new JoystickButton(m_autoRecorderXbox, XboxController.RIGHT_BUMPER_BUTTON) new JoystickButton(m_autoRecorderXbox, XboxController.RIGHT_BUMPER_BUTTON)
// .onTrue(new neoJoystickPlayback(m_robotSwerveDrive, .onTrue(new neoJoystickPlayback(m_robotSwerveDrive,
// () -> autoplaybackName.get(), () -> autoplaybackName.get(),
// new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()}, new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()},
// true, false)) true, false))
// .onFalse(new InstantCommand()); .onFalse(new InstantCommand());
// new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) // new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON)
// .whileTrue(new JoystickRecorder(m_robotSwerveDrive, // .whileTrue(new JoystickRecorder(m_robotSwerveDrive,
@@ -636,10 +653,7 @@ public class RobotContainer {
*/ */
public Command getAutonomousCommand() { public Command getAutonomousCommand() {
//no auto //no auto
return new neoJoystickPlayback(m_robotSwerveDrive, return autoPlayback;
() -> autoplaybackName.get(),
new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()},
true, false);
//return playbackChooser.getCommand(); //return playbackChooser.getCommand();
} }
@@ -181,6 +181,12 @@ public class SwerveDrive extends SubsystemBase {
return gyro.getAngle(); return gyro.getAngle();
} }
public void add180() {
gyro.reset(gyro.getAngle()+180);
rotTarget = gyro.getAngle();
}
public void resetGyro() { public void resetGyro() {
gyro.reset(); gyro.reset();
rotTarget = gyro.getAngle(); rotTarget = gyro.getAngle();
@@ -106,6 +106,17 @@ public class RobotGyro implements Gyro {
} }
public void reset(double val) {
resetZeroValues();
if (m_isGyroAPigeon) {
m_pigeon.setYaw(val);
} else {
m_navX.reset();
}
}
public void resetFlip() { public void resetFlip() {
resetZeroValues(); resetZeroValues();