Skip to content

Feature/stow update#64

Merged
CameronMyhre merged 13 commits intodevfrom
feature/stow_update
Apr 11, 2026
Merged

Feature/stow update#64
CameronMyhre merged 13 commits intodevfrom
feature/stow_update

Conversation

@CameronMyhre
Copy link
Copy Markdown
Member

No description provided.

@CameronMyhre CameronMyhre added the Tested This code has been tested on the robot or in a setting enough to guarantee robot functionality. label Apr 11, 2026
Copy link
Copy Markdown
Contributor

@CrumblzTheEgg CrumblzTheEgg left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

works

@CameronMyhre CameronMyhre merged commit 72846a1 into dev Apr 11, 2026
1 check passed
@quipp quipp requested a review from Copilot April 11, 2026 00:50
Copy link
Copy Markdown
Contributor

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Updates turret “stow” behavior and operator controls, while introducing infrastructure for scaling drive speeds during shooting.

Changes:

  • Reworked TurretSubsystem#getStowCommand() to push the hood down open-loop until encoder velocity is stable (with a safety angle cutoff), then reset hood angle.
  • Added a drive output scaling hook (speedScaleSupplier) and a new Constants.Operator.Drive.SHOOTING_SPEED_SCALE constant.
  • Updated RobotContainer bindings to select fixed targets (A/B), track X/Y holds, run turret targeting while shooting, and default the turret to stow in teleop.

Reviewed changes

Copilot reviewed 4 out of 4 changed files in this pull request and generated 9 comments.

File Description
src/main/java/frc/robot/subsystems/TurretSubsystem.java Adds hood velocity accessor and rewrites stow command using velocity/settling logic and an encoder reset.
src/main/java/frc/robot/subsystems/DriveSubsystem.java Adds speed scaling supplier + applies scaling to chassis speeds.
src/main/java/frc/robot/RobotContainer.java Adds/adjusts button bindings for targeting selection and makes turret target only while shoot is held; defaults turret to stow in teleop.
src/main/java/frc/robot/Constants.java Adds/updates constants for shooting speed scale, hood stow tuning, and transfer load delay.

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

Comment on lines +348 to 352
Command settleDown = Commands.run(
() -> {
setHoodAngle(Constants.Turret.HOOD_STOW_POSITION);
},

interrupted -> {
pitchServo.setSpeed((Constants.Turret.PITCH_INVERTED ? -1.0 : 1.0) * -Constants.Turret.STOW_PUSH_DOWN_SPEED);
SmartDashboard.putBoolean("Hood Pushing", true);
},
Copy link

Copilot AI Apr 11, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

settleDown drives the hood servo open-loop but never disables hoodClosedLoopActive; periodic() will keep writing PID output while closed-loop is active, which can override/fight this command. Consider explicitly disabling closed-loop at the start of stow (e.g., call stopHoodServo() / set hoodClosedLoopActive = false) before applying the constant push-down speed.

Copilot uses AI. Check for mistakes.
Comment on lines +374 to +380
// ensure the servo is stopped when this command completes
.andThen(() -> {
pitchServo.setSpeed(0.0);
settleTimer.stop();
settleTimer.reset();
}
);
Copy link

Copilot AI Apr 11, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The servo stop/reset logic is in an .andThen(...), which only runs on normal completion. If getStowCommand() is interrupted (e.g., by a targeting command), the hood servo can be left running at the last push-down speed. Use a command form that defines an end(interrupted)/finallyDo to always stop the servo and reset/stop the timer on both completion and interruption.

Suggested change
// ensure the servo is stopped when this command completes
.andThen(() -> {
pitchServo.setSpeed(0.0);
settleTimer.stop();
settleTimer.reset();
}
);
// ensure the servo and timer are cleaned up on both completion and interruption
.finallyDo(() -> {
pitchServo.setSpeed(0.0);
settleTimer.stop();
settleTimer.reset();
});

Copilot uses AI. Check for mistakes.
},

interrupted -> {
pitchServo.setSpeed((Constants.Turret.PITCH_INVERTED ? -1.0 : 1.0) * -Constants.Turret.STOW_PUSH_DOWN_SPEED);
Copy link

Copilot AI Apr 11, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

STOW_PUSH_DOWN_SPEED is defined as a positive magnitude, but it is negated at the callsite and then conditionally inverted again via PITCH_INVERTED. This makes the sign convention hard to reason about and easy to break if PITCH_INVERTED changes. Prefer keeping STOW_PUSH_DOWN_SPEED in the motor/servo's native sign convention and remove the extra negation here (or rename it to STOW_PUSH_DOWN_MAGNITUDE and handle sign in one place).

Suggested change
pitchServo.setSpeed((Constants.Turret.PITCH_INVERTED ? -1.0 : 1.0) * -Constants.Turret.STOW_PUSH_DOWN_SPEED);
pitchServo.setSpeed((Constants.Turret.PITCH_INVERTED ? 1.0 : -1.0) * Constants.Turret.STOW_PUSH_DOWN_SPEED);

Copilot uses AI. Check for mistakes.
Comment on lines +270 to +289
new Trigger(
() -> operatorController.getAButton()).onTrue(
new InstantCommand(() -> selectedFixedTarget = FixedTarget.A));

new Trigger(
() -> operatorController.getBButton()).onTrue(
new InstantCommand(() -> selectedFixedTarget = FixedTarget.B));

new Trigger(
() -> operatorController.getXButton()).onTrue(
new InstantCommand(() -> xHeld = true))
.onFalse(
new InstantCommand(() -> xHeld = false));

new Trigger(
() -> operatorController.getYButton()).onTrue(
new InstantCommand(() -> yHeld = true))
.onFalse(
new InstantCommand(() -> yHeld = false));

Copy link

Copilot AI Apr 11, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

configureBindings() now registers A/B/X/Y button triggers near the top of the method, but the file already registers A/B/X triggers again later in the same method. This duplication schedules redundant InstantCommands and makes the binding logic harder to maintain; consolidate these into a single set of bindings (and keep Y consistent as well).

Suggested change
new Trigger(
() -> operatorController.getAButton()).onTrue(
new InstantCommand(() -> selectedFixedTarget = FixedTarget.A));
new Trigger(
() -> operatorController.getBButton()).onTrue(
new InstantCommand(() -> selectedFixedTarget = FixedTarget.B));
new Trigger(
() -> operatorController.getXButton()).onTrue(
new InstantCommand(() -> xHeld = true))
.onFalse(
new InstantCommand(() -> xHeld = false));
new Trigger(
() -> operatorController.getYButton()).onTrue(
new InstantCommand(() -> yHeld = true))
.onFalse(
new InstantCommand(() -> yHeld = false));

Copilot uses AI. Check for mistakes.
Comment on lines +61 to +63
// Speed scaling (e.g. 0.5 to limit to 50% while shooting)
private Supplier<Double> speedScaleSupplier = () -> 1.0;

Copy link

Copilot AI Apr 11, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The speed-scale feature is currently not wired up anywhere (no calls to setSpeedScaleSupplier in the codebase), so speedScaleSupplier will always be 1.0 and this change has no effect. Either connect it from RobotContainer (e.g., scale while shootTrigger is active using Constants.Operator.Drive.SHOOTING_SPEED_SCALE) or remove the unused API/constant.

Suggested change
// Speed scaling (e.g. 0.5 to limit to 50% while shooting)
private Supplier<Double> speedScaleSupplier = () -> 1.0;

Copilot uses AI. Check for mistakes.
}

// Apply speed scale (e.g. 50% while shooting)
double scale = MathUtil.clamp(speedScaleSupplier.get(), 0.0, 1.0);
Copy link

Copilot AI Apr 11, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

MathUtil.clamp(...) does not guard against NaN/Infinity; if the supplier ever returns a non-finite value, the chassis speeds become non-finite and could propagate into the swerve drive. Consider sanitizing the supplier output (e.g., treat non-finite as 1.0 or 0.0) before applying it.

Suggested change
double scale = MathUtil.clamp(speedScaleSupplier.get(), 0.0, 1.0);
double rawScale = speedScaleSupplier.get();
double scale = MathUtil.clamp(Double.isFinite(rawScale) ? rawScale : 1.0, 0.0, 1.0);

Copilot uses AI. Check for mistakes.
public static final double STOW_PUSH_DOWN_SPEED = -0.3; // percent of max speed
public static final double STOW_PUSH_DOWN_TIME = 0.5; // seconds
public static final double STOW_PUSH_DOWN_SPEED = 0.6; // percent of max speed
public static final double STOW_PUSH_DOWN_TIME = 0.1; // seconds
Copy link

Copilot AI Apr 11, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

STOW_PUSH_DOWN_TIME is still defined but is no longer used by getStowCommand(). Either remove the constant or reintroduce a timeout/safety bound that uses it (especially if the velocity-based settle condition could fail due to encoder noise).

Suggested change
public static final double STOW_PUSH_DOWN_TIME = 0.1; // seconds

Copilot uses AI. Check for mistakes.
public static final Rotation2d HOOD_START_POSITION = Rotation2d.fromDegrees(8.00);

public static final double HOOD_STABLE_TIME = 0.1;
public static final double HOOD_STABLE = 5;
Copy link

Copilot AI Apr 11, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

HOOD_STABLE is newly added but not referenced anywhere. If it was intended as a stability threshold/count, wire it into the stow/settle logic; otherwise remove it to avoid stale/unused configuration values.

Suggested change
public static final double HOOD_STABLE = 5;

Copilot uses AI. Check for mistakes.
Comment on lines 530 to +531

public static final double LOAD_DELAY = 0.1; //Time between shooter and transfer being triggered, shooter should always activate first
Copy link

Copilot AI Apr 11, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LOAD_DELAY is newly added but not referenced anywhere in the codebase. If the intent is to enforce a shooter-before-transfer delay, incorporate this into the relevant command scheduling logic; otherwise remove the unused constant.

Suggested change
public static final double LOAD_DELAY = 0.1; //Time between shooter and transfer being triggered, shooter should always activate first

Copilot uses AI. Check for mistakes.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

Tested This code has been tested on the robot or in a setting enough to guarantee robot functionality.

Projects

None yet

Development

Successfully merging this pull request may close these issues.

5 participants