mirror of
https://github.com/Team4388/RiseOfRidgebotics2020.git
synced 2026-06-08 16:28:01 -06:00
Fixed Enums for Manual
This commit is contained in:
@@ -44,7 +44,6 @@ 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;
|
||||
@@ -57,6 +56,7 @@ 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.XboxController;
|
||||
@@ -129,7 +129,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 InstantCommand(() -> m_robotStorage.changeStorageMode(StorageMode.IDLE)));
|
||||
//m_robotLime.setDefaultCommand(new RunCommand(() -> m_robotLime.limeOff(), m_robotLime));
|
||||
}
|
||||
|
||||
@@ -247,8 +247,8 @@ public class RobotContainer {
|
||||
/* Button Fox */
|
||||
// Storage Manual
|
||||
new JoystickButton(getButtonFox(), ButtonFox.LEFT_SWITCH)
|
||||
.whileHeld(new ManageStorage(m_robotStorage, StorageMode.MANUAL))
|
||||
.whenReleased(new ManageStorage(m_robotStorage, StorageMode.RESET));
|
||||
.whenPressed(new InstantCommand(() -> m_robotStorage.changeStorageMode(StorageMode.MANUAL)))
|
||||
.whenReleased(new InstantCommand(() -> m_robotStorage.changeStorageMode(StorageMode.RESET)));
|
||||
|
||||
// Meg
|
||||
new JoystickButton(getButtonFox(), ButtonFox.MIDDLE_SWITCH)
|
||||
|
||||
@@ -0,0 +1,40 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package frc4388.robot.commands.shooter;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
|
||||
public class ShooterGoalPosition extends CommandBase {
|
||||
/**
|
||||
* Creates a new ShooterGoalPosition.
|
||||
*/
|
||||
public ShooterGoalPosition() {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,40 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package frc4388.robot.commands.shooter;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
|
||||
public class ShooterTrenchPosition extends CommandBase {
|
||||
/**
|
||||
* Creates a new ShooterTrenchPosition.
|
||||
*/
|
||||
public ShooterTrenchPosition() {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@@ -11,6 +11,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc4388.robot.Constants.StorageConstants;
|
||||
import frc4388.robot.subsystems.Storage;
|
||||
import frc4388.robot.subsystems.Storage.StorageMode;
|
||||
|
||||
public class ManageStorage extends CommandBase {
|
||||
Storage m_storage;
|
||||
@@ -26,17 +27,13 @@ public class ManageStorage extends CommandBase {
|
||||
|
||||
/* Used for intaking a ball. Keeps track off when the 2nd ball in storage has moved */
|
||||
boolean m_isStorageEmpty = true;
|
||||
|
||||
public enum StorageMode{IDLE, INTAKE, RESET, MANUAL};
|
||||
StorageMode m_storageMode = StorageMode.IDLE;
|
||||
|
||||
/**
|
||||
* Creates a new ManageStorage.
|
||||
*/
|
||||
public ManageStorage(Storage m_robotStorage, StorageMode storageMode) {
|
||||
public ManageStorage(Storage m_robotStorage) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
m_storage = m_robotStorage;
|
||||
m_storageMode = storageMode;
|
||||
addRequirements(m_storage);
|
||||
}
|
||||
|
||||
@@ -50,7 +47,7 @@ public class ManageStorage extends CommandBase {
|
||||
|
||||
m_isStorageEmpty = !m_isBallInStorage;
|
||||
|
||||
if (m_storageMode == StorageMode.RESET) {
|
||||
if (m_storage.m_storageMode == StorageMode.RESET) {
|
||||
m_resetStartTime = System.currentTimeMillis();
|
||||
}
|
||||
}
|
||||
@@ -68,13 +65,13 @@ public class ManageStorage extends CommandBase {
|
||||
SmartDashboard.putBoolean("!Ball Storage!", m_isBallInStorage);
|
||||
SmartDashboard.putBoolean("!Ball Shooter!", m_isBallInShooter);
|
||||
|
||||
if (m_storageMode == StorageMode.IDLE) {
|
||||
if (m_storage.m_storageMode == StorageMode.IDLE) {
|
||||
runIdle();
|
||||
} else if (m_storageMode == StorageMode.INTAKE) {
|
||||
} else if (m_storage.m_storageMode == StorageMode.INTAKE) {
|
||||
runIntake();
|
||||
} else if (m_storageMode == StorageMode.RESET) {
|
||||
} else if (m_storage.m_storageMode == StorageMode.RESET) {
|
||||
runReset();
|
||||
} else if (m_storageMode == StorageMode.MANUAL) {
|
||||
} else if (m_storage.m_storageMode == StorageMode.MANUAL) {
|
||||
runManual();
|
||||
}
|
||||
}
|
||||
@@ -93,10 +90,10 @@ public class ManageStorage extends CommandBase {
|
||||
}
|
||||
if (m_isStorageEmpty && m_isBallInStorage) { // If Ball moves into storage, set storage to full and swtich to idle mode
|
||||
m_isStorageEmpty = false;
|
||||
m_storageMode = StorageMode.IDLE;
|
||||
m_storage.changeStorageMode(StorageMode.IDLE);
|
||||
}
|
||||
} else {
|
||||
m_storageMode = StorageMode.IDLE;
|
||||
m_storage.changeStorageMode(StorageMode.IDLE);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -108,7 +105,7 @@ public class ManageStorage extends CommandBase {
|
||||
m_storage.runStorage(0);
|
||||
|
||||
if (m_isBallInIntake) {
|
||||
m_storageMode = StorageMode.INTAKE;
|
||||
m_storage.changeStorageMode(StorageMode.INTAKE);
|
||||
}
|
||||
m_isStorageEmpty = !m_isBallInStorage;
|
||||
}
|
||||
@@ -122,9 +119,9 @@ public class ManageStorage extends CommandBase {
|
||||
m_storage.runStorage(-StorageConstants.STORAGE_SPEED);
|
||||
|
||||
if (m_isBallInIntake) {
|
||||
m_storageMode = StorageMode.INTAKE;
|
||||
m_storage.changeStorageMode(StorageMode.INTAKE);
|
||||
} else if (m_resetStartTime + StorageConstants.STORAGE_TIMEOUT < System.currentTimeMillis()) {
|
||||
m_storageMode = StorageMode.IDLE;
|
||||
m_storage.changeStorageMode(StorageMode.IDLE);
|
||||
}
|
||||
m_isStorageEmpty = !m_isBallInStorage;
|
||||
}
|
||||
@@ -139,7 +136,7 @@ public class ManageStorage extends CommandBase {
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
m_storageMode = StorageMode.RESET;
|
||||
m_storage.changeStorageMode(StorageMode.RESET);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
|
||||
@@ -11,6 +11,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc4388.robot.Constants.StorageConstants;
|
||||
import frc4388.robot.subsystems.Storage;
|
||||
import frc4388.robot.subsystems.Storage.StorageMode;
|
||||
|
||||
public class ManageStoragePID extends CommandBase {
|
||||
Storage m_storage;
|
||||
@@ -30,16 +31,13 @@ public class ManageStoragePID extends CommandBase {
|
||||
/* Used for intaking a ball. Keeps track off when the 2nd ball in storage has moved */
|
||||
boolean m_isStorageEmpty = true;
|
||||
|
||||
public enum StorageMode{IDLE, INTAKE, RESET};
|
||||
StorageMode m_storageMode = StorageMode.IDLE;
|
||||
|
||||
/**
|
||||
* Creates a new ManageStorage.
|
||||
*/
|
||||
public ManageStoragePID(Storage m_robotStorage, StorageMode storageMode) {
|
||||
public ManageStoragePID(Storage m_robotStorage) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
m_storage = m_robotStorage;
|
||||
m_storageMode = storageMode;
|
||||
addRequirements(m_storage);
|
||||
}
|
||||
|
||||
@@ -55,7 +53,7 @@ public class ManageStoragePID extends CommandBase {
|
||||
|
||||
m_intakeStartPos = m_storage.getEncoderPosInches();
|
||||
|
||||
if (m_storageMode == StorageMode.RESET) {
|
||||
if (m_storage.m_storageMode == StorageMode.RESET) {
|
||||
m_resetStartTime = System.currentTimeMillis();
|
||||
}
|
||||
}
|
||||
@@ -73,11 +71,11 @@ public class ManageStoragePID extends CommandBase {
|
||||
SmartDashboard.putBoolean("!Ball Storage!", m_isBallInStorage);
|
||||
SmartDashboard.putBoolean("!Ball Shooter!", m_isBallInShooter);
|
||||
|
||||
if (m_storageMode == StorageMode.IDLE) {
|
||||
if (m_storage.m_storageMode == StorageMode.IDLE) {
|
||||
runIdle();
|
||||
} else if (m_storageMode == StorageMode.INTAKE) {
|
||||
} else if (m_storage.m_storageMode == StorageMode.INTAKE) {
|
||||
runIntake();
|
||||
} else if (m_storageMode == StorageMode.RESET) {
|
||||
} else if (m_storage.m_storageMode == StorageMode.RESET) {
|
||||
runReset();
|
||||
}
|
||||
}
|
||||
@@ -93,10 +91,10 @@ public class ManageStoragePID extends CommandBase {
|
||||
|
||||
double error = (m_intakeStartPos + StorageConstants.STORAGE_FULL_BALL) - m_storage.getEncoderPosInches();
|
||||
if (m_storage.getEncoderVel() == 0 && Math.abs(error) < 0.5) {
|
||||
m_storageMode = StorageMode.IDLE;
|
||||
m_storage.changeStorageMode(StorageMode.IDLE);
|
||||
}
|
||||
} else {
|
||||
m_storageMode = StorageMode.IDLE;
|
||||
m_storage.changeStorageMode(StorageMode.IDLE);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -108,7 +106,7 @@ public class ManageStoragePID extends CommandBase {
|
||||
m_storage.runStorage(0);
|
||||
|
||||
if (m_isBallInIntake) {
|
||||
m_storageMode = StorageMode.INTAKE;
|
||||
m_storage.changeStorageMode(StorageMode.INTAKE);
|
||||
m_intakeStartPos = m_storage.getEncoderPosInches();
|
||||
}
|
||||
m_isStorageEmpty = !m_isBallInStorage;
|
||||
@@ -123,10 +121,10 @@ public class ManageStoragePID extends CommandBase {
|
||||
m_storage.runStorage(-StorageConstants.STORAGE_SPEED);
|
||||
|
||||
if (m_isBallInIntake) {
|
||||
m_storageMode = StorageMode.INTAKE;
|
||||
m_storage.changeStorageMode(StorageMode.INTAKE);
|
||||
m_intakeStartPos = m_storage.getEncoderPosInches();
|
||||
} else if (m_resetStartTime + StorageConstants.STORAGE_TIMEOUT < System.currentTimeMillis()) {
|
||||
m_storageMode = StorageMode.IDLE;
|
||||
m_storage.changeStorageMode(StorageMode.IDLE);
|
||||
}
|
||||
m_isStorageEmpty = !m_isBallInStorage;
|
||||
}
|
||||
@@ -134,7 +132,7 @@ public class ManageStoragePID extends CommandBase {
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
m_storageMode = StorageMode.RESET;
|
||||
m_storage.changeStorageMode(StorageMode.RESET);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
|
||||
@@ -36,6 +36,9 @@ public class Storage extends SubsystemBase {
|
||||
|
||||
public boolean m_isStorageReadyToFire = false;
|
||||
|
||||
public enum StorageMode{IDLE, INTAKE, RESET, MANUAL};
|
||||
public StorageMode m_storageMode = StorageMode.IDLE;
|
||||
|
||||
/**
|
||||
* Creates a new Storage.
|
||||
*/
|
||||
@@ -134,4 +137,8 @@ public class Storage extends SubsystemBase {
|
||||
public boolean getBeamIntake(){
|
||||
return m_beamIntake.get();
|
||||
}
|
||||
|
||||
public void changeStorageMode(StorageMode storageMode){
|
||||
m_storageMode = storageMode;
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user