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 all commits
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
11 changes: 8 additions & 3 deletions src/main/java/frc/team3128/commands/CmdAlign.java
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;
Expand All @@ -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
Expand All @@ -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
Expand All @@ -62,6 +65,7 @@ public void execute() {
currHorizontalOffset = limelights.getShooterTX();
prevError = goalHorizontalOffset - currHorizontalOffset;
aimState = VisionState.FEEDBACK;
controller.enableContinuousInput(-180, 180);
}
break;

Expand All @@ -70,16 +74,17 @@ public void execute() {
if(!limelights.getShooterHasValidTarget()) {
aimState = VisionState.SEARCHING;
plateauCount = 0;
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 ff = Math.signum(currError) * VISION_PID_kF;
double feedbackPower = VISION_PID_kP * currError + VISION_PID_kD * (currError - prevError) / (currTime - prevTime) + ff;

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

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

drive.tankDrive(-feedbackPower, feedbackPower);
Expand Down