Skip to content
This repository was archived by the owner on Sep 14, 2019. It is now read-only.

Commit 645330d

Browse files
committed
PID command documentation
1 parent 87d1e16 commit 645330d

File tree

2 files changed

+107
-24
lines changed

2 files changed

+107
-24
lines changed

Robot2018/src/org/usfirst/frc/team199/Robot2018/commands/PIDMove.java

Lines changed: 52 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -9,26 +9,43 @@
99
import edu.wpi.first.wpilibj.command.Command;
1010

1111
/**
12-
*
12+
* Drives the robot a certain target distance using PID. Implements PIDOutput in
13+
* order to keep move PID centralized in this command.
1314
*/
1415
public class PIDMove extends Command implements PIDOutput {
1516

1617
private double target;
1718
private DrivetrainInterface dt;
1819
private PIDController moveController;
1920

21+
/**
22+
* Constructs this command with a new PIDController. Sets all of the
23+
* controller's PID constants based on SD prefs. Sets the controller's PIDSource
24+
* to the encoder average object and sets its PIDOutput to this command which
25+
* implements PIDOutput's pidWrite() method.
26+
*
27+
* @param targ
28+
* the target distance (in inches) to move to
29+
* @param dt
30+
* the Drivetrain (for actual code) or a DrivetrainInterface (for
31+
* testing)
32+
* @param avg
33+
* the PIDSourceAverage of the DT's two Encoders
34+
*/
2035
public PIDMove(double targ, DrivetrainInterface dt, PIDSourceAverage avg) {
2136
// Use requires() here to declare subsystem dependencies
22-
// eg. requires(chassis);
37+
requires(Robot.dt);
2338
target = targ;
2439
this.dt = dt;
25-
requires(Robot.dt);
2640
double kf = 1 / (dt.getCurrentMaxSpeed() * Robot.getConst("Default PID Update Time", 0.05));
2741
moveController = new PIDController(Robot.getConst("MovekP", 1), Robot.getConst("MovekI", 0),
2842
Robot.getConst("MovekD", 0), kf, avg, this);
2943
}
3044

31-
// Called just before this Command runs the first time
45+
/**
46+
* Called just before this Command runs the first time. Resets the distance
47+
* encoders, sets the moveController's settings, and then enables it.
48+
*/
3249
@Override
3350
public void initialize() {
3451
dt.resetDistEncs();
@@ -42,33 +59,57 @@ public void initialize() {
4259
moveController.enable();
4360
}
4461

45-
// Called repeatedly when this Command is scheduled to run
62+
/**
63+
* Called repeatedly when this Command is scheduled to run. This method is empty
64+
* bc the moveController runs on a different thread as soon as it is enabled in
65+
* initialize().
66+
*/
4667
@Override
4768
protected void execute() {
48-
// This method is empty bc the moveController runs on a different thread as soon
49-
// as it is enabled.
5069
}
5170

52-
// Make this return true when this Command no longer needs to run execute()
71+
/**
72+
* Tells this command to terminate when the moveController has reached its
73+
* target.
74+
*
75+
* @return true if the robot has moved the correct distance, false if not
76+
*/
5377
@Override
5478
protected boolean isFinished() {
5579
return moveController.onTarget();
5680
}
5781

58-
// Called once after isFinished returns true
82+
/**
83+
* Called once after isFinished returns true. Disables and frees the
84+
* moveController, essentially turning it "off" and "deleting" the thread it was
85+
* running on.
86+
*/
5987
@Override
6088
protected void end() {
6189
moveController.disable();
6290
moveController.free();
6391
}
6492

65-
// Called when another command which requires one or more of the same
66-
// subsystems is scheduled to run
93+
/**
94+
* Called when another command which requires one or more of the same subsystems
95+
* is scheduled to run. Disables and frees the moveController, essentially
96+
* turning it "off" and "deleting" the thread it was running on.
97+
*/
6798
@Override
6899
protected void interrupted() {
69100
end();
70101
}
71102

103+
/**
104+
* Implementation of PIDOutput's pidWrite method. Sends the moveController's
105+
* output speed to the motors as the drive/forward speed in DifferentialDrive's
106+
* arcadeDrive method.
107+
*
108+
* @param output
109+
* the output drive/forward speed [-1, 1], calculated by the move
110+
* PIDController, to pass in as the drive/forward speed in
111+
* arcadeDrive()
112+
*/
72113
@Override
73114
public void pidWrite(double output) {
74115
dt.arcadeDrive(output, 0);

Robot2018/src/org/usfirst/frc/team199/Robot2018/commands/PIDTurn.java

Lines changed: 55 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -10,20 +10,35 @@
1010
import edu.wpi.first.wpilibj.command.Command;
1111

1212
/**
13-
*
13+
* Turns the robot to a certain target bearing using PID. Implements PIDOutput
14+
* in order to keep turn PID centralized in this command.
1415
*/
1516
public class PIDTurn extends Command implements PIDOutput {
1617

17-
double target;
18-
DrivetrainInterface dt;
18+
private double target;
19+
private DrivetrainInterface dt;
1920
private PIDController turnController;
2021

22+
/**
23+
* Constructs this command with a new PIDController. Sets all of the
24+
* controller's PID constants based on SD prefs. Sets the controller's PIDSource
25+
* to the AHRS (gyro) object and sets its PIDOutput to this command which
26+
* implements PIDOutput's pidWrite() method.
27+
*
28+
* @param targ
29+
* the target bearing (in degrees) to turn to (so negative if turning
30+
* left, positive if turning right)
31+
* @param dt
32+
* the Drivetrain (for actual code) or a DrivetrainInterface (for
33+
* testing)
34+
* @param ahrs
35+
* the AHRS (gyro)
36+
*/
2137
public PIDTurn(double targ, DrivetrainInterface dt, AHRS ahrs) {
2238
// Use requires() here to declare subsystem dependencies
23-
// eg. requires(chassis);
39+
requires(Robot.dt);
2440
target = targ;
2541
this.dt = dt;
26-
requires(Robot.dt);
2742
// calculates the maximum turning speed in degrees/sec based on the max linear
2843
// speed in inches/s and the distance (inches) between sides of the DT
2944
double maxTurnSpeed = dt.getCurrentMaxSpeed() * 360
@@ -33,7 +48,10 @@ public PIDTurn(double targ, DrivetrainInterface dt, AHRS ahrs) {
3348
Robot.getConst("TurnkD", 0), kf, ahrs, this);
3449
}
3550

36-
// Called just before this Command runs the first time
51+
/**
52+
* Called just before this Command runs the first time. Resets the gyro, sets
53+
* the turnController's settings, and then enables it.
54+
*/
3755
@Override
3856
protected void initialize() {
3957
dt.resetAHRS();
@@ -48,33 +66,57 @@ protected void initialize() {
4866
turnController.enable();
4967
}
5068

51-
// Called repeatedly when this Command is scheduled to run
69+
/**
70+
* Called repeatedly when this Command is scheduled to run. This method is empty
71+
* bc the turnController runs on a different thread as soon as it is enabled in
72+
* initialize().
73+
*/
5274
@Override
5375
protected void execute() {
54-
// This method is empty bc the moveController runs on a different thread as soon
55-
// as it is enabled.
5676
}
5777

58-
// Make this return true when this Command no longer needs to run execute()
78+
/**
79+
* Tells this command to terminate when the turnController has reached its
80+
* target.
81+
*
82+
* @return true if the robot has turned to the correct target bearing, false if
83+
* not
84+
*/
5985
@Override
6086
protected boolean isFinished() {
6187
return turnController.onTarget();
6288
}
6389

64-
// Called once after isFinished returns true
90+
/**
91+
* Called once after isFinished returns true. Disables and frees the
92+
* turnController, essentially turning it "off" and "deleting" the thread it was
93+
* running on.
94+
*/
6595
@Override
6696
protected void end() {
6797
turnController.disable();
6898
turnController.free();
6999
}
70100

71-
// Called when another command which requires one or more of the same
72-
// subsystems is scheduled to run
101+
/**
102+
* Called when another command which requires one or more of the same subsystems
103+
* is scheduled to run. Disables and frees the turnController, essentially
104+
* turning it "off" and "deleting" the thread it was running on.
105+
*/
73106
@Override
74107
protected void interrupted() {
75108
end();
76109
}
77110

111+
/**
112+
* Implementation of PIDOutput's pidWrite method. Sends the turnController's
113+
* output speed to the motors as the turn speed in DifferentialDrive's
114+
* arcadeDrive method.
115+
*
116+
* @param output
117+
* the output turn speed [-1, 1], calculated by the turn
118+
* PIDController, to pass in as the turn speed in arcadeDrive()
119+
*/
78120
@Override
79121
public void pidWrite(double output) {
80122
dt.arcadeDrive(0, output);

0 commit comments

Comments
 (0)