Skip to content

Manual shooting adjustment#132

Open
kirbythepuffdragon wants to merge 5 commits intomainfrom
manual_shooting_adjustment
Open

Manual shooting adjustment#132
kirbythepuffdragon wants to merge 5 commits intomainfrom
manual_shooting_adjustment

Conversation

@kirbythepuffdragon
Copy link
Contributor

Added manual offset and refresh to adjust position for accuracy. It is a manual turret correction

After modifying offset, it moves turret to the updated position using the offset.
@kirbythepuffdragon kirbythepuffdragon requested a review from a team March 20, 2026 01:11
operator
.axisLessThan(Axis.kRightX.value, -0.5)
.and(() -> fineControl)
.onTrue(this.robot.getTurret().modifyOffsetAngle(Degrees.of(3)));
Copy link
Collaborator

Choose a reason for hiding this comment

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

We want these offsets to be roughly proportional to the joystick position, now just ±3 if the magnitudes of the joystick values are greater than 0.5.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I changed the line temporarily to:
.onTrue(this.robot.getTurret().modifyOffsetAngle(Degrees.of(operator.getRawMagnitude(Axis.kRight.value)*-2)));

I don't know the code for finding the position of the joystick

* @return a Command that, while scheduled, continuously moves the turret toward the supplied
* target angle while attempting to maintain the supplied target velocity
*/
public Command track(
Copy link
Collaborator

Choose a reason for hiding this comment

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

Add the offset to track().

@@ -1,9 +1,19 @@
{
Copy link
Collaborator

Choose a reason for hiding this comment

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

Undo changes to this file. It's a configuration that we just want to leave the same.

.axisLessThan(Axis.kRightX.value, -0.5)
.and(() -> fineControl)
.onTrue(this.robot.getTurret().modifyOffsetAngle(Degrees.of(3)));

Copy link
Collaborator

Choose a reason for hiding this comment

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

We also need to be able to offset the hood.

kirbythepuffdragon and others added 3 commits March 21, 2026 11:31
Still some major issues, but it's an improvement
we had to change the return type of setOffsetAngle to void instead of Command so that it constantly updates the input parameter newOffset
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants