Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fallback trajectories v2 #136

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 12 additions & 7 deletions src/main/java/com/team1701/robot/commands/AutonomousCommands.java
Original file line number Diff line number Diff line change
Expand Up @@ -196,11 +196,7 @@ private Command followChoreoPath(String pathName, boolean resetPose) {
}

private Command driveBackPreWarmAndShoot(String pathName) {
return loggedSequence(
pauseDrive(pathName),
followChoreoPathAndPreWarm(pathName),
aimAndShoot(),
runOnce(() -> mRobotState.setUseAutonFallback(false)));
return loggedSequence(pauseDrive(pathName), followChoreoPathAndPreWarm(pathName), aimAndShoot());
}

private Command driveToNextPiece(AutoNote nextNote) {
Expand Down Expand Up @@ -246,15 +242,24 @@ private Pose2d getFinalPose(String pathName) {
return trajectory == null ? GeometryUtil.kPoseIdentity : trajectory.getFinalPose();
}

private class UseEfficientAutonFallback {
boolean useFallback = false;

public UseEfficientAutonFallback(boolean use) {
useFallback = use;
}
}

private Command efficientlyPreWarmShootAndDrive(String pathName, String returnPath, AutoNote nextNote) {
var useAutonFallback = new UseEfficientAutonFallback(false);
return race(
driveBackPreWarmAndShoot(pathName).andThen(followChoreoPathAndSeekNote(returnPath)),
waitSeconds(.7)
.andThen(either(
idle(),
runOnce(() -> mRobotState.setUseAutonFallback(true)),
runOnce(() -> useAutonFallback.useFallback = true),
mRobotState::hasNote)))
.andThen(either(driveToNextPiece(nextNote), none(), mRobotState::getUseAutonFallback));
.andThen(either(driveToNextPiece(nextNote), none(), () -> useAutonFallback.useFallback));
}

private Command followChoreoPathAndSeekNote(String pathName) {
Expand Down
11 changes: 0 additions & 11 deletions src/main/java/com/team1701/robot/states/RobotState.java
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,6 @@ public class RobotState {

private ShootingState mShootingState = ShootingState.kDefault;

private boolean mUseAutonFallback = false;

public RobotState() {
mField = new Field2d();
SmartDashboard.putData("Field", mField);
Expand Down Expand Up @@ -391,15 +389,6 @@ public boolean isClimbMode() {
return mScoringMode == ScoringMode.CLIMB;
}

public boolean getUseAutonFallback() {
return mUseAutonFallback;
}

public boolean setUseAutonFallback(boolean use) {
mUseAutonFallback = use;
return mUseAutonFallback;
}

public enum ScoringMode {
SPEAKER,
AMP,
Expand Down