Merge "Re-tuned PID for PacGoat."

This commit is contained in:
Alex Henning
2014-06-30 19:35:44 -07:00
committed by Gerrit Code Review
9 changed files with 21 additions and 21 deletions

View File

@@ -70,8 +70,8 @@ public class Robot extends IterativeRobot {
}
public void autonomousInit() {
Command auto = (Command) autoChooser.getSelected();
auto.start();
autonomousCommand = (Command) autoChooser.getSelected();
autonomousCommand.start();
}
// This function is called periodically during autonomous

View File

@@ -10,14 +10,14 @@ import edu.wpi.first.wpilibj.command.CommandGroup;
*/
public class DriveAndShootAutonomous extends CommandGroup {
public DriveAndShootAutonomous() {
addSequential(new CloseClaw());
addSequential(new WaitForPressure(), 2);
if (Robot.isReal()) {
// NOTE: Simulation doesn't currently have the concept of hot.
addSequential(new CheckForHotGoal(2));
}
addSequential(new CloseClaw());
}
addSequential(new SetPivotSetpoint(45));
addSequential(new DriveForward(8, 0.4));
addSequential(new DriveForward(8, 0.3));
addSequential(new Shoot());
}
}

View File

@@ -11,9 +11,9 @@ import edu.wpi.first.wpilibj.command.Command;
public class DriveForward extends Command {
private double driveForwardSpeed;
private double distance;
private final double tolerance = .1; // TODO: Was 5
private double error;
private final double Kp = -1.0 / 5.0;
private final double TOLERANCE = .1;
private final double KP = -1.0 / 5.0;
public DriveForward() {
this(10, 0.5);
@@ -36,16 +36,16 @@ public class DriveForward extends Command {
protected void execute() {
error = (distance - Robot.drivetrain.getRightEncoder().getDistance());
if (driveForwardSpeed * Kp * error >= driveForwardSpeed) {
if (driveForwardSpeed * KP * error >= driveForwardSpeed) {
Robot.drivetrain.tankDrive(driveForwardSpeed, driveForwardSpeed);
} else {
Robot.drivetrain.tankDrive(driveForwardSpeed * Kp * error,
driveForwardSpeed * Kp * error);
Robot.drivetrain.tankDrive(driveForwardSpeed * KP * error,
driveForwardSpeed * KP * error);
}
}
protected boolean isFinished() {
return (Math.abs(error) <= tolerance) || isTimedOut();
return (Math.abs(error) <= TOLERANCE) || isTimedOut();
}
protected void end() {

View File

@@ -31,4 +31,4 @@ public class DriveWithJoystick extends Command {
protected void interrupted() {
end();
}
}
}

View File

@@ -51,7 +51,7 @@ public class DriveTrain extends Subsystem {
// Configure encoders
rightEncoder = new Encoder(1, 2, true, EncodingType.k4X);
leftEncoder = new Encoder(5, 6, false, EncodingType.k4X); // XXX: Module 2
leftEncoder = new Encoder(3, 4, false, EncodingType.k4X);
rightEncoder.setPIDSourceParameter(PIDSourceParameter.kDistance);
leftEncoder.setPIDSourceParameter(PIDSourceParameter.kDistance);
@@ -126,4 +126,4 @@ public class DriveTrain extends Subsystem {
public double getAngle() {
return gyro.getAngle();
}
}
}

View File

@@ -29,8 +29,8 @@ public class Pivot extends PIDSubsystem {
setAbsoluteTolerance(0.005);
getPIDController().setContinuous(false);
if (Robot.isSimulation()) { // PID is different in simulation.
getPIDController().setPID(0.5, 0.00001, 4.5);
setAbsoluteTolerance(2.5);
getPIDController().setPID(0.5, 0.001, 2);
setAbsoluteTolerance(5);
}
// Motor to move the pivot.