Merge branch 'master' into GalacticSearch

This commit is contained in:
Ryan
2021-04-15 16:50:23 -06:00
committed by GitHub
37 changed files with 2146 additions and 115 deletions
+127 -26
View File
@@ -49,14 +49,24 @@ import frc4388.robot.commands.climber.RunClimberWithTriggers;
import frc4388.robot.commands.climber.RunLevelerWithJoystick;
import frc4388.robot.commands.drive.DriveStraightAtVelocityPID;
import frc4388.robot.commands.drive.DriveWithJoystick;
import frc4388.robot.commands.drive.PlaySongDrive;
import frc4388.robot.commands.drive.SkipSong;
import frc4388.robot.commands.drive.TurnDegrees;
import frc4388.robot.commands.intake.RunIntakeWithTriggers;
import frc4388.robot.commands.shooter.CalibrateShooter;
import frc4388.robot.commands.shooter.TrackTarget;
import frc4388.robot.commands.shooter.TrimShooter;
import frc4388.robot.commands.shooter.RunHoodWithJoystick;
import frc4388.robot.commands.shooter.ShootPrepGroup;
import frc4388.robot.commands.shooter.ShooterGoalPosition;
import frc4388.robot.commands.shooter.ShooterManual;
import frc4388.robot.commands.shooter.ShooterTrenchPosition;
import frc4388.robot.commands.shooter.ShooterVelocityControlPID;
import frc4388.robot.commands.shooter.TrackTarget;
import frc4388.robot.commands.shooter.TrimShooter;
import frc4388.robot.commands.storage.ManageStorage;
import frc4388.robot.commands.storage.ManageStorage.StorageMode;
import frc4388.robot.commands.storage.StoragePrep;
import frc4388.robot.subsystems.Camera;
import frc4388.robot.subsystems.Climber;
import frc4388.robot.subsystems.Drive;
@@ -69,7 +79,10 @@ import frc4388.robot.subsystems.Shooter;
import frc4388.robot.subsystems.ShooterAim;
import frc4388.robot.subsystems.ShooterHood;
import frc4388.robot.subsystems.Storage;
import frc4388.robot.subsystems.Storage.StorageMode;
import frc4388.utility.controller.ButtonFox;
import frc4388.utility.controller.IHandController;
import frc4388.utility.controller.JoystickManualButton;
import frc4388.utility.controller.XboxController;
/**
@@ -98,11 +111,12 @@ public class RobotContainer {
private final LimeLight m_robotLime = new LimeLight();
/* Controllers */
private final XboxController m_driverXbox = new XboxController(OIConstants.XBOX_DRIVER_ID);
private final XboxController m_operatorXbox = new XboxController(OIConstants.XBOX_OPERATOR_ID);
private final Joystick m_joystick = new Joystick(0);
public boolean isGS = false;
private static XboxController m_driverXbox = new XboxController(OIConstants.XBOX_DRIVER_ID);
private static XboxController m_operatorXbox = new XboxController(OIConstants.XBOX_OPERATOR_ID);
private static XboxController m_buttonFox = new XboxController(OIConstants. BUTTON_FOX_ID);
private static XboxController m_manualXbox = new XboxController(3);
/* Autos */
double m_totalTimeAuto;
@@ -137,17 +151,19 @@ public class RobotContainer {
GalacticSearch m_galacticSearch;
public static boolean m_isShooterManual = false;
/**
* The container for the robot. Contains subsystems, OI devices, and commands.
*/
public RobotContainer() {
/* Passing Drive and Pneumatics Subsystems */
m_robotPneumatics.passRequiredSubsystem(m_robotDrive);
m_robotDrive.passRequiredSubsystem(m_robotPneumatics);
m_robotDrive.passRequiredSubsystem(m_robotPneumatics, m_robotShooter);
m_robotShooter.passRequiredSubsystem(m_robotShooterHood, m_robotShooterAim);
m_robotShooterHood.passRequiredSubsystem(m_robotShooter);
m_robotShooterAim.passRequiredSubsystem(m_robotShooter);
m_robotShooterAim.passRequiredSubsystem(m_robotShooter, m_robotDrive);
m_robotLeveler.passRequiredSubsystem(m_robotClimber);
@@ -166,6 +182,8 @@ public class RobotContainer {
m_robotIntake.setDefaultCommand(new RunIntakeWithTriggers(m_robotIntake, getOperatorController()));
// runs the turret with joystick
m_robotShooterAim.setDefaultCommand(new RunCommand(() -> m_robotShooterAim.runShooterWithInput(-m_operatorXbox.getLeftXAxis()), m_robotShooterAim));
// runs the hood with joystick
m_robotShooterHood.setDefaultCommand(new RunHoodWithJoystick(m_robotShooterHood, getOperatorController()));
// moves the drum not
m_robotShooter.setDefaultCommand(new RunCommand(() -> m_robotShooter.runDrumShooterVelocityPID(0), m_robotShooter));
// drives climber with input from triggers on the opperator controller
@@ -176,7 +194,7 @@ public class RobotContainer {
m_robotLED.setDefaultCommand(new RunCommand(() -> m_robotLED.updateLED(), m_robotLED));
// runs the storage not
//m_robotStorage.setDefaultCommand(new RunCommand(() -> m_robotStorage.runStorage(0), m_robotStorage));
m_robotStorage.setDefaultCommand(new ManageStorage(m_robotStorage, StorageMode.IDLE));
m_robotStorage.setDefaultCommand(new ManageStorage(m_robotStorage));
//m_robotLime.setDefaultCommand(new RunCommand(() -> m_robotLime.limeOff(), m_robotLime));
}
@@ -189,8 +207,6 @@ public class RobotContainer {
private void configureButtonBindings() {
/* Test Buttons */
// A driver test button
new JoystickButton(getDriverJoystick(), XboxController.A_BUTTON)
.whenPressed(new DriveStraightAtVelocityPID(m_robotDrive, 1000));
// B driver test button
new JoystickButton(getDriverJoystick(), XboxController.B_BUTTON)
@@ -218,6 +234,9 @@ public class RobotContainer {
new JoystickButton(getDriverJoystick(), XboxController.BACK_BUTTON)
.whileHeld(new DisengageRachet(m_robotClimber));
/* Operator Buttons */
// shoots until released
new JoystickButton(getOperatorJoystick(), XboxController.RIGHT_BUMPER_BUTTON)
@@ -268,36 +287,100 @@ public class RobotContainer {
new JoystickButton(getOperatorJoystick(), XboxController.START_BUTTON)
.whileHeld(new CalibrateShooter(m_robotShooter, m_robotShooterAim, m_robotShooterHood));
//Prepares storage for intaking
//new XboxTriggerButton(m_operatorXbox, XboxTriggerButton.LEFT_TRIGGER)
//.whileHeld(new RunCommand(() -> m_robotStorage.runStorage(0.8)))
//.whenReleased(new RunCommand(() -> m_robotStorage.runStorage(0.0)));
//.whileHeld(new StorageIntake(m_robotIntake, m_robotStorage));
//Runs storage to outtake
//new XboxTriggerButton(m_operatorXbox, XboxTriggerButton.RIGHT_TRIGGER)
//.whileHeld(new RunCommand(() -> m_robotStorage.runStorage(-0.8)))
//.whenReleased(new RunCommand(() -> m_robotStorage.runStorage(0.0)));
//Run drum
new JoystickButton(getOperatorJoystick(), XboxController.B_BUTTON)
new JoystickManualButton(getOperatorJoystick(), XboxController.B_BUTTON, false)
.whileHeld(new ShootPrepGroup(m_robotShooter, m_robotShooterAim, m_robotShooterHood, m_robotStorage), false)
//.whenReleased(new ManageStorage(m_robotStorage, StorageMode.RESET))
.whenReleased(new InstantCommand(() -> m_robotLime.limeOff()));
new JoystickButton(m_joystick, 1)
.whenPressed(new IdentifyPath(m_robotLime));
//Run drum manual
new JoystickManualButton(getOperatorJoystick(), XboxController.B_BUTTON, true)
.whileHeld(new RunCommand(() -> m_robotShooter.runDrumShooterVelocityPID(10000)))
.whenReleased(new RunCommand(() -> m_robotShooter.runDrumShooterVelocityPID(0)));
/* Button Fox */
// Storage Manual
new JoystickButton(getButtonFox(), ButtonFox.LEFT_SWITCH)
.whenPressed(new InstantCommand(() -> m_robotStorage.changeStorageMode(StorageMode.MANUAL)))
.whenReleased(new InstantCommand(() -> m_robotStorage.changeStorageMode(StorageMode.RESET)));
// Meg
new JoystickButton(getButtonFox(), ButtonFox.MIDDLE_SWITCH)
.whileHeld(new PlaySongDrive(m_robotDrive, m_robotShooter))
.whenReleased(new InterruptSubystem(m_robotDrive));
// Shooter Manual
new JoystickButton(getButtonFox(), ButtonFox.RIGHT_SWITCH)
.whileHeld(new ShooterManual(true))
.whenReleased(new ShooterManual(false));
// Goal Shooter Position
new JoystickButton(getButtonFox(), ButtonFox.RIGHT_BUTTON)
.whileHeld(new PlaySongDrive(m_robotDrive, m_robotShooter))
.whenReleased(new InterruptSubystem(m_robotDrive));
// Trench Shooter Position
new JoystickButton(getButtonFox(), ButtonFox.LEFT_BUTTON)
.whileHeld(new ShooterTrenchPosition(m_robotShooter, m_robotShooterHood, m_robotShooterAim))
.whenReleased(new InterruptSubystem(m_robotShooter))
.whenReleased(new InterruptSubystem(m_robotShooterHood))
.whenReleased(new InterruptSubystem(m_robotShooterAim));
//.whenPressed(new SkipSong(m_robotDrive, 1));
}
public void buildAutos() {
//resetOdometry(new Pose2d(0, 0, new Rotation2d(180)));
String[] sixBallAutoMiddlePaths = new String[]{
"SixBallMidComplete"
};
m_sixBallAutoMiddle = new SixBallAutoMiddle(m_robotDrive, buildPaths(sixBallAutoMiddlePaths));
String[] eightBallAutoMiddlePaths = new String[]{
"EightBallMidComplete"
};
m_eightBallAutoMiddle = new EightBallAutoMiddle(m_robotDrive, buildPaths(eightBallAutoMiddlePaths));
String[] driveOffLineForwardPaths = new String[]{
"DriveOffLineForward"
};
m_driveOffLineForward = new DriveOffLineForward(m_robotDrive, buildPaths(driveOffLineForwardPaths));
String[] driveOffLineBackwardPaths = new String[]{
"DriveOffLineBackward"
};
m_driveOffLineBackward = new DriveOffLineBackward(m_robotDrive, buildPaths(driveOffLineBackwardPaths));
String[] fiveBallAutoMiddlePaths = new String[]{
"FiveBallMidComplete"
};
m_fiveBallAutoMiddle = new FiveBallAutoMiddle(m_robotDrive, buildPaths(fiveBallAutoMiddlePaths));
String[] tenBallAutoMiddlePaths = new String[]{
"SixBallMidComplete",
"TenBallMidComplete"
};
m_tenBallAutoMiddle = new TenBallAutoMiddle(m_robotShooterHood, m_robotStorage, m_robotIntake, m_robotShooter,
m_robotShooterAim, m_robotDrive,buildPaths(tenBallAutoMiddlePaths));
String[] galacticSearchPaths = new String[]{
"GSC_ARED",
"GSC_ABLUE",
"GSC_BRED",
"GSC_BBLUE"
"GSC_ARED",
"GSC_ABLUE",
"GSC_BRED",
"GSC_BBLUE"
};
idenPath();
m_galacticSearch = new GalacticSearch(m_robotLime, m_robotIntake, buildPaths(galacticSearchPaths));
}
public void idenPath()
@@ -321,7 +404,7 @@ public class RobotContainer {
//return m_sixBallAutoMiddle1.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
//return m_eightBallAutoMiddle.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
//return m_driveOffLineForward.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
//return m_driveOffLineBackward.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
//return m_driveOffLinfeBackward.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
//return m_fiveBallAutoMiddle.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
//return m_tenBallAutoMiddle.andThen(()-> m_robotDrive.tankDriveVelocity(0, 0));
//return m_slalom.andThen(()-> m_robotDrive.tankDriveVelocity(0, 0));
@@ -330,6 +413,7 @@ public class RobotContainer {
//return m_sequentialTest.andThen(() -> m_robotDrive.tankDriveVelocity(0,0));
return m_galacticSearch.andThen(() -> m_robotDrive.tankDriveVelocity(0,0));
} catch (Exception e) {
System.err.println("ERROR");
}
@@ -451,6 +535,12 @@ public class RobotContainer {
return m_operatorXbox;
}
public IHandController getButtonFoxObject()
{
return m_buttonFox;
}
/**
* Gets the {@link edu.wpi.first.wpilibj.GenericHID#GenericHID(int) Generic HID} for the Operator Xbox Controller.
* Generic HIDs/Joysticks can be used to set up JoystickButtons.
@@ -470,4 +560,15 @@ public class RobotContainer {
{
return m_driverXbox.getJoyStick();
}
/**
* Gets the {@link edu.wpi.first.wpilibj.GenericHID#GenericHID(int) Generic HID} for the Button Fox.
* Generic HIDs/Joysticks can be used to set up JoystickButtons.
* @return The IHandController interface for the Button Fox.
*/
public Joystick getButtonFox()
{
return m_buttonFox.getJoyStick();
}
}