mirror of
https://github.com/Team4388/RiseOfRidgebotics2020.git
synced 2026-06-09 00:38:00 -06:00
Merge branch 'button-fox' into highlanders-day
This commit is contained in:
@@ -48,17 +48,22 @@ import frc4388.robot.commands.climber.RunClimberWithTriggers;
|
||||
import frc4388.robot.commands.climber.RunLevelerWithJoystick;
|
||||
import frc4388.robot.commands.drive.DriveStraightToPositionMM;
|
||||
import frc4388.robot.commands.drive.DriveWithJoystick;
|
||||
import frc4388.robot.commands.drive.PlaySongDrive;
|
||||
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.StoragePrep;
|
||||
import frc4388.robot.commands.storage.ManageStorage.StorageMode;
|
||||
import frc4388.robot.subsystems.Camera;
|
||||
import frc4388.robot.subsystems.Climber;
|
||||
import frc4388.robot.subsystems.Drive;
|
||||
@@ -71,7 +76,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;
|
||||
|
||||
/**
|
||||
@@ -100,8 +108,10 @@ 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 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;
|
||||
@@ -118,6 +128,7 @@ public class RobotContainer {
|
||||
|
||||
TenBallAutoMiddle m_tenBallAutoMiddle;
|
||||
|
||||
public static boolean m_isShooterManual = false;
|
||||
|
||||
/**
|
||||
* The container for the robot. Contains subsystems, OI devices, and commands.
|
||||
@@ -148,6 +159,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(1500), m_robotShooter));
|
||||
// drives climber with input from triggers on the opperator controller
|
||||
@@ -158,7 +171,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));
|
||||
}
|
||||
|
||||
@@ -200,6 +213,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)
|
||||
@@ -250,22 +266,50 @@ 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()));
|
||||
|
||||
//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)
|
||||
.whenPressed(new PlaySongDrive(m_robotDrive))
|
||||
.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.LEFT_BUTTON)
|
||||
.whileHeld(new ShooterGoalPosition(m_robotShooter, m_robotShooterHood, m_robotShooterAim))
|
||||
.whenReleased(new InterruptSubystem(m_robotShooter))
|
||||
.whenReleased(new InterruptSubystem(m_robotShooterHood))
|
||||
.whenReleased(new InterruptSubystem(m_robotShooterAim));
|
||||
|
||||
// Trench Shooter Position
|
||||
new JoystickButton(getButtonFox(), ButtonFox.RIGHT_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));
|
||||
}
|
||||
|
||||
public void buildAutos() {
|
||||
@@ -466,6 +510,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.
|
||||
@@ -485,4 +535,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();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user