Skip to content
This repository was archived by the owner on Sep 14, 2019. It is now read-only.
Merged
Show file tree
Hide file tree
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
Original file line number Diff line number Diff line change
Expand Up @@ -9,26 +9,43 @@
import edu.wpi.first.wpilibj.command.Command;

/**
*
* Drives the robot a certain target distance using PID. Implements PIDOutput in
* order to keep move PID centralized in this command.
*/
public class PIDMove extends Command implements PIDOutput {

private double target;
private DrivetrainInterface dt;
private PIDController moveController;

/**
* Constructs this command with a new PIDController. Sets all of the
* controller's PID constants based on SD prefs. Sets the controller's PIDSource
* to the encoder average object and sets its PIDOutput to this command which
* implements PIDOutput's pidWrite() method.
*
* @param targ
* the target distance (in inches) to move to
* @param dt
* the Drivetrain (for actual code) or a DrivetrainInterface (for
* testing)
* @param avg
* the PIDSourceAverage of the DT's two Encoders
*/
public PIDMove(double targ, DrivetrainInterface dt, PIDSourceAverage avg) {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.dt);
target = targ;
this.dt = dt;
requires(Robot.dt);
double kf = 1 / (dt.getCurrentMaxSpeed() * Robot.getConst("Default PID Update Time", 0.05));
moveController = new PIDController(Robot.getConst("MovekP", 1), Robot.getConst("MovekI", 0),
Robot.getConst("MovekD", 0), kf, avg, this);
}

// Called just before this Command runs the first time
/**
* Called just before this Command runs the first time. Resets the distance
* encoders, sets the moveController's settings, and then enables it.
*/
@Override
public void initialize() {
dt.resetDistEncs();
Expand All @@ -42,33 +59,57 @@ public void initialize() {
moveController.enable();
}

// Called repeatedly when this Command is scheduled to run
/**
* Called repeatedly when this Command is scheduled to run. This method is empty
* bc the moveController runs on a different thread as soon as it is enabled in
* initialize().
*/
@Override
protected void execute() {
// This method is empty bc the moveController runs on a different thread as soon
// as it is enabled.
}

// Make this return true when this Command no longer needs to run execute()
/**
* Tells this command to terminate when the moveController has reached its
* target.
*
* @return true if the robot has moved the correct distance, false if not
*/
@Override
protected boolean isFinished() {
return moveController.onTarget();
}

// Called once after isFinished returns true
/**
* Called once after isFinished returns true. Disables and frees the
* moveController, essentially turning it "off" and "deleting" the thread it was
* running on.
*/
@Override
protected void end() {
moveController.disable();
moveController.free();
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
/**
* Called when another command which requires one or more of the same subsystems
* is scheduled to run. Disables and frees the moveController, essentially
* turning it "off" and "deleting" the thread it was running on.
*/
@Override
protected void interrupted() {
end();
}

/**
* Implementation of PIDOutput's pidWrite method. Sends the moveController's
* output speed to the motors as the drive/forward speed in DifferentialDrive's
* arcadeDrive method.
*
* @param output
* the output drive/forward speed [-1, 1], calculated by the move
* PIDController, to pass in as the drive/forward speed in
* arcadeDrive()
*/
@Override
public void pidWrite(double output) {
dt.arcadeDrive(output, 0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,20 +10,35 @@
import edu.wpi.first.wpilibj.command.Command;

/**
*
* Turns the robot to a certain target bearing using PID. Implements PIDOutput
* in order to keep turn PID centralized in this command.
*/
public class PIDTurn extends Command implements PIDOutput {

double target;
DrivetrainInterface dt;
private double target;
private DrivetrainInterface dt;
private PIDController turnController;

/**
* Constructs this command with a new PIDController. Sets all of the
* controller's PID constants based on SD prefs. Sets the controller's PIDSource
* to the AHRS (gyro) object and sets its PIDOutput to this command which
* implements PIDOutput's pidWrite() method.
*
* @param targ
* the target bearing (in degrees) to turn to (so negative if turning
* left, positive if turning right)
* @param dt
* the Drivetrain (for actual code) or a DrivetrainInterface (for
* testing)
* @param ahrs
* the AHRS (gyro)
*/
public PIDTurn(double targ, DrivetrainInterface dt, AHRS ahrs) {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.dt);
target = targ;
this.dt = dt;
requires(Robot.dt);
// calculates the maximum turning speed in degrees/sec based on the max linear
// speed in inches/s and the distance (inches) between sides of the DT
double maxTurnSpeed = dt.getCurrentMaxSpeed() * 360
Expand All @@ -33,7 +48,10 @@ public PIDTurn(double targ, DrivetrainInterface dt, AHRS ahrs) {
Robot.getConst("TurnkD", 0), kf, ahrs, this);
}

// Called just before this Command runs the first time
/**
* Called just before this Command runs the first time. Resets the gyro, sets
* the turnController's settings, and then enables it.
*/
@Override
protected void initialize() {
dt.resetAHRS();
Expand All @@ -48,33 +66,57 @@ protected void initialize() {
turnController.enable();
}

// Called repeatedly when this Command is scheduled to run
/**
* Called repeatedly when this Command is scheduled to run. This method is empty
* bc the turnController runs on a different thread as soon as it is enabled in
* initialize().
*/
@Override
protected void execute() {
// This method is empty bc the moveController runs on a different thread as soon
// as it is enabled.
}

// Make this return true when this Command no longer needs to run execute()
/**
* Tells this command to terminate when the turnController has reached its
* target.
*
* @return true if the robot has turned to the correct target bearing, false if
* not
*/
@Override
protected boolean isFinished() {
return turnController.onTarget();
}

// Called once after isFinished returns true
/**
* Called once after isFinished returns true. Disables and frees the
* turnController, essentially turning it "off" and "deleting" the thread it was
* running on.
*/
@Override
protected void end() {
turnController.disable();
turnController.free();
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
/**
* Called when another command which requires one or more of the same subsystems
* is scheduled to run. Disables and frees the turnController, essentially
* turning it "off" and "deleting" the thread it was running on.
*/
@Override
protected void interrupted() {
end();
}

/**
* Implementation of PIDOutput's pidWrite method. Sends the turnController's
* output speed to the motors as the turn speed in DifferentialDrive's
* arcadeDrive method.
*
* @param output
* the output turn speed [-1, 1], calculated by the turn
* PIDController, to pass in as the turn speed in arcadeDrive()
*/
@Override
public void pidWrite(double output) {
dt.arcadeDrive(0, output);
Expand Down