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

Fix some robot container commands #46

Merged
merged 1 commit into from
Feb 15, 2025
Merged
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
74 changes: 23 additions & 51 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -375,17 +375,10 @@ private void configureControllerBindings()


// Driver Left Trigger + Right Bumper: Algae Intake
// m_driver.leftTrigger().and(isCoralMode.negate()).whileTrue(
// Commands.sequence(
// (FieldConstants.getNearestReefBranch(m_drive.getPose(), ReefSide.RIGHT)
// .getTranslation().getX() > 0)
// ? m_profiledElevator.setStateCommand(Elevator.State.ALGAE_HIGH)
// : m_profiledElevator.setStateCommand(Elevator.State.ALGAE_LOW),
// m_clawRoller.setStateCommand(ClawRoller.State.INTAKE),
// Commands.waitUntil(m_clawRoller.stalled)
// .andThen(m_clawRoller.setStateCommand(ClawRoller.State.OFF)))
// .andThen(m_profiledElevator.setStateCommand(Elevator.State.STOW)));
// m_driver.rightTrigger().whileTrue(m_clawRoller.setStateCommand(ClawRoller.State.SCORE));
m_driver.leftTrigger().and(isCoralMode.negate()).onTrue(
(m_clawRoller.getState() == ClawRoller.State.ALGAE_INTAKE)
? m_clawRoller.setStateCommandNoEnd(ClawRoller.State.EJECT)
: m_clawRoller.setStateCommandNoEnd(ClawRoller.State.ALGAE_INTAKE));

// Driver Start Button: Climb Request (toggle)
// m_driver.start().onTrue(Commands.runOnce(() -> {
Expand Down Expand Up @@ -433,9 +426,14 @@ private void configureControllerBindings()

// Driver POV Down: Zero the Elevator (HOMING)
m_driver.povDown().whileTrue(
m_profiledElevator.setStateCommand(Elevator.State.HOMING)
.until(m_profiledElevator.getHomedTrigger())
.andThen(m_profiledElevator.zeroSensorCommand()));
Commands.sequence(
// Always move Arm to STOW position before moving Elevator
m_profiledArm.setStateCommand(Arm.State.STOW).until(() -> m_profiledArm.atPosition(0.1)),
// Move Elevator to homing position
Commands.waitUntil(() -> m_profiledArm.atPosition(0.1))
.andThen(m_profiledElevator.setStateCommand(Elevator.State.HOMING)
.until(m_profiledElevator.getHomedTrigger()))
.andThen(m_profiledElevator.zeroSensorCommand())));

// Driver Right Bumper: Toggle between Coral and Algae Modes.
// Make sure the Approach nearest reef face does not mess with this
Expand All @@ -452,38 +450,23 @@ private void registerNamedCommands()
// Go to the L1 Position
NamedCommands.registerCommand(
"L1",
Commands.parallel(
m_profiledElevator.setStateCommand(Elevator.State.LEVEL_1),
m_profiledArm.setStateCommand(Arm.State.LEVEL_1)));
m_superStruct.getTransitionCommand(Arm.State.LEVEL_1, Elevator.State.LEVEL_1));
// Go to the L2 Position
NamedCommands.registerCommand(
"L2",
Commands.parallel(
m_profiledElevator.setStateCommand(Elevator.State.LEVEL_2),
m_profiledArm.setStateCommand(Arm.State.LEVEL_2)));
m_superStruct.getTransitionCommand(Arm.State.LEVEL_2, Elevator.State.LEVEL_2));
// Go to the L3 Position
NamedCommands.registerCommand(
"L3",
Commands.parallel(
m_profiledElevator.setStateCommand(Elevator.State.LEVEL_3),
m_profiledArm.setStateCommand(Arm.State.LEVEL_3)));
m_superStruct.getTransitionCommand(Arm.State.LEVEL_3, Elevator.State.LEVEL_3));
// Go to the L4 Position
NamedCommands.registerCommand(
"L4",
Commands.parallel(
m_profiledElevator.setStateCommand(Elevator.State.LEVEL_4),
Commands.waitUntil(() -> m_profiledElevator.atPosition(1))
.andThen(m_profiledArm.setStateCommand(Arm.State.LEVEL_4))));
m_superStruct.getTransitionCommand(Arm.State.LEVEL_4, Elevator.State.LEVEL_4));
// Go to the Home Position
NamedCommands.registerCommand(
"Home",
Commands.parallel(
m_profiledElevator.setStateCommand(Elevator.State.STOW),
m_profiledArm.setStateCommand(Arm.State.STOW)));

// Wait for intake laserCAN to be triggered
NamedCommands.registerCommand("WaitForCoral",
Commands.waitUntil(m_intakeLaserCAN.triggered));
m_superStruct.getTransitionCommand(Arm.State.STOW, Elevator.State.STOW));

// Wait for intake laserCAN to be triggered
NamedCommands.registerCommand("WaitForCoral",
Expand All @@ -492,23 +475,12 @@ private void registerNamedCommands()
// Intake Coral
NamedCommands.registerCommand(
"IntakeCoral",
m_clawRoller.setStateCommand(ClawRoller.State.INTAKE)
.until(m_clawRollerLaserCAN.triggered)
.andThen(m_clawRoller.setStateCommandNoEnd(ClawRoller.State.HOLDCORAL))
.andThen(Commands.waitUntil(() -> m_clawRoller.atPosition(1))));

// Intake Algae
NamedCommands.registerCommand(
"IntakeAlgae",
Commands.sequence(
(FieldConstants.getNearestReefBranch(m_drive.getPose(), ReefSide.RIGHT)
.getTranslation().getX() > 0)
? m_profiledElevator.setStateCommand(Elevator.State.ALGAE_HIGH)
: m_profiledElevator.setStateCommand(Elevator.State.ALGAE_LOW),
m_clawRoller.setStateCommand(ClawRoller.State.INTAKE),
Commands.waitUntil(m_clawRoller.stalled)
.andThen(m_clawRoller.setStateCommand(ClawRoller.State.OFF)))
.andThen(m_profiledElevator.setStateCommand(Elevator.State.STOW)));
Commands.parallel(
m_superStruct.getTransitionCommand(Arm.State.CORAL_INTAKE, Elevator.State.CORAL_INTAKE),
m_clawRoller.setStateCommand(ClawRoller.State.INTAKE)
.until(m_clawRollerLaserCAN.triggered)
.andThen(m_clawRoller.setStateCommandNoEnd(ClawRoller.State.HOLDCORAL))
.andThen(Commands.waitUntil(() -> m_clawRoller.atPosition(1)))));

NamedCommands.registerCommand(
"Score",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ public class ClawRoller
// numbers

static LoggedTunableNumber holdCoralSP = new LoggedTunableNumber("ClawRoller/HoldCoralSP", 0.0);
static LoggedTunableNumber algaeIntakeSP = new LoggedTunableNumber("ClawRoller/AlgaeIntakeSP", -15.0);

@RequiredArgsConstructor
@Getter
Expand All @@ -29,8 +30,8 @@ public enum State implements TargetState {
INTAKE(() -> 2.0, ProfileType.OPEN_VOLTAGE),
EJECT(() -> 6.0, ProfileType.OPEN_VOLTAGE),
SCORE(() -> 8.0, ProfileType.OPEN_VOLTAGE),
HOLDCORAL(() -> 0.6, ProfileType.MM_POSITION), // Wheels should spin x rotations before stopping
TUNING(() -> holdCoralSP.getAsDouble(), ProfileType.MM_POSITION);
HOLDCORAL(() -> holdCoralSP.getAsDouble(), ProfileType.MM_POSITION),
ALGAE_INTAKE(() -> algaeIntakeSP.getAsDouble(), ProfileType.OPEN_CURRENT);

private final DoubleSupplier output;
private final ProfileType profileType;
Expand Down