-
Notifications
You must be signed in to change notification settings - Fork 28
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
base: dev
Are you sure you want to change the base?
Changes from 1 commit
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,6 +1,7 @@ | ||
package frc.team3128.commands; | ||
|
||
import edu.wpi.first.math.MathUtil; | ||
import edu.wpi.first.math.controller.PIDController; | ||
import edu.wpi.first.wpilibj.RobotController; | ||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; | ||
import edu.wpi.first.wpilibj2.command.CommandBase; | ||
|
@@ -25,6 +26,7 @@ private enum VisionState { | |
private boolean isAligned; | ||
|
||
private VisionState aimState = VisionState.SEARCHING; | ||
private PIDController controller; | ||
|
||
/** | ||
* Aligns the robot to the hub using the limelight | ||
|
@@ -45,6 +47,7 @@ public void initialize() { | |
// limelights.turnShooterLEDOn(); | ||
prevTime = RobotController.getFPGATime() / 1e6; | ||
plateauCount = 0; | ||
controller = new PIDController(VISION_PID_kP, VISION_PID_kI, VISION_PID_kD); | ||
} | ||
|
||
@Override | ||
|
@@ -62,6 +65,7 @@ public void execute() { | |
currHorizontalOffset = limelights.getShooterTX(); | ||
prevError = goalHorizontalOffset - currHorizontalOffset; | ||
aimState = VisionState.FEEDBACK; | ||
controller.disableContinuousInput(); | ||
} | ||
break; | ||
|
||
|
@@ -70,16 +74,16 @@ public void execute() { | |
if(!limelights.getShooterHasValidTarget()) { | ||
aimState = VisionState.SEARCHING; | ||
plateauCount = 0; | ||
controller.enableContinuousInput(-180, 180); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. this should be .disable |
||
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 ff = Math.signum(currError) * VISION_PID_kF; | ||
double feedbackPower = VISION_PID_kP * currError + VISION_PID_kD * (currError - prevError) / (currTime - prevTime) + ff; | ||
|
||
double feedbackPower = controller.calculate(currHorizontalOffset); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. keep the ff line in here and set feedbackPower = the code you have in here with .calculate() + ff |
||
|
||
feedbackPower = MathUtil.clamp(feedbackPower, -1, 1); | ||
|
||
drive.tankDrive(-feedbackPower, feedbackPower); | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
this should be .enable not .disable because you're switching from searching to feedback