Open
Conversation
… 0.1 second delay to the transfer activating
Contributor
There was a problem hiding this comment.
Pull request overview
Updates turret “stow” behavior and shooting bindings so the turret aims only while shooting and the transfer feed is delayed to let the shooter spin up first.
Changes:
- Reworked
TurretSubsystem.getStowCommand()to use a velocity-stability settle routine (and added hood velocity accessor). - Updated
RobotContainerbindings so holding the shoot trigger runs turret targeting and delays transfer loading. - Added new constants for hood settling and transfer load delay.
Reviewed changes
Copilot reviewed 3 out of 3 changed files in this pull request and generated 5 comments.
| File | Description |
|---|---|
src/main/java/frc/robot/subsystems/TurretSubsystem.java |
Adds hood velocity helper and rewrites stow command to settle based on encoder velocity. |
src/main/java/frc/robot/RobotContainer.java |
Binds shoot trigger to turret targeting and adds a delay before transfer load; sets turret default to stow. |
src/main/java/frc/robot/Constants.java |
Introduces constants used by the new stow/settle logic and transfer load delay. |
💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.
Comment on lines
+283
to
+310
| Command settleDown = Commands.run( | ||
| () -> pitchServo.setSpeed((Constants.Turret.PITCH_INVERTED ? -1.0 : 1.0) * -Constants.Turret.STOW_PUSH_DOWN_SPEED), | ||
| this) | ||
| // stop when encoder velocity magnitude <= threshold | ||
| .until(() -> { | ||
| boolean within = Math.abs(getHoodVelocity()) <= stopThreshold; | ||
|
|
||
| if (within) { | ||
| if (!settleTimer.isRunning()) { | ||
| settleTimer.reset(); | ||
| settleTimer.start(); | ||
| } | ||
| //Finish when considered stable | ||
| return settleTimer.hasElapsed(maxSettleTime); | ||
| } else { | ||
| settleTimer.stop(); | ||
| settleTimer.reset(); | ||
| return false; | ||
| } | ||
| } | ||
| ) | ||
| // ensure the servo is stopped when this command completes | ||
| .andThen(() -> { | ||
| pitchServo.setSpeed(0.0); | ||
| settleTimer.stop(); | ||
| settleTimer.reset(); | ||
| } | ||
| ); |
Co-authored-by: Copilot Autofix powered by AI <175728472+Copilot@users.noreply.github.com>
Co-authored-by: Copilot Autofix powered by AI <175728472+Copilot@users.noreply.github.com>
Co-authored-by: Copilot Autofix powered by AI <175728472+Copilot@users.noreply.github.com>
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment
Add this suggestion to a batch that can be applied as a single commit.This suggestion is invalid because no changes were made to the code.Suggestions cannot be applied while the pull request is closed.Suggestions cannot be applied while viewing a subset of changes.Only one suggestion per line can be applied in a batch.Add this suggestion to a batch that can be applied as a single commit.Applying suggestions on deleted lines is not supported.You must change the existing code in this line in order to create a valid suggestion.Outdated suggestions cannot be applied.This suggestion has been applied or marked resolved.Suggestions cannot be applied from pending reviews.Suggestions cannot be applied on multi-line comments.Suggestions cannot be applied while the pull request is queued to merge.Suggestion cannot be applied right now. Please check back later.
No description provided.