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

PIDController in CmdAlign #137

Open
wants to merge 3 commits into
base: dev
Choose a base branch
from
Open
Changes from 1 commit
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
7 changes: 4 additions & 3 deletions src/main/java/frc/team3128/commands/CmdAlign.java
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ public void execute() {
currHorizontalOffset = limelights.getShooterTX();
prevError = goalHorizontalOffset - currHorizontalOffset;
aimState = VisionState.FEEDBACK;
controller.disableContinuousInput();
controller.enableContinuousInput(-180, 180);
}
break;

Expand All @@ -74,15 +74,16 @@ public void execute() {
if(!limelights.getShooterHasValidTarget()) {
aimState = VisionState.SEARCHING;
plateauCount = 0;
controller.enableContinuousInput(-180, 180);
controller.disableContinuousInput();
break;
}

// turn with PID loop using input as horizontal tx error to target
currHorizontalOffset = limelights.getShooterTX();
currError = goalHorizontalOffset - currHorizontalOffset; // currError is positive if we are too far left

double feedbackPower = controller.calculate(currHorizontalOffset);
double ff = Math.signum(currError) * VISION_PID_kF;
double feedbackPower = controller.calculate(currHorizontalOffset) + ff;
Copy link
Author

Choose a reason for hiding this comment

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

use currError instead of currHorizontalOffset


feedbackPower = MathUtil.clamp(feedbackPower, -1, 1);

Expand Down