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

Commit f7c3e56

Browse files
committed
added kF
VelocityPIDController: added constructor param and javadoc RobotMap: initial instantiation Drivetrain: updatePIDConstants method
1 parent 536e792 commit f7c3e56

3 files changed

Lines changed: 14 additions & 9 deletions

File tree

Robot2018/src/org/usfirst/frc/team199/Robot2018/RobotMap.java

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -114,12 +114,13 @@ public RobotMap() {
114114
dtLeft = new SpeedControllerGroup(dtLeftDrive, dtLeftSlave);
115115

116116
leftVelocityController = new VelocityPIDController(Robot.getConst("MoveLeftkP", 1),
117-
Robot.getConst("MoveLeftkI", 0), Robot.getConst("MoveLeftkD", 0), leftEncRate, dtLeft);
117+
Robot.getConst("MoveLeftkI", 0), Robot.getConst("MoveLeftkD", 0), 1 / Robot.getConst("MaxSpeed", 17),
118+
leftEncRate, dtLeft);
118119
leftVelocityController.enable();
119120
leftVelocityController.setInputRange(0, Double.MAX_VALUE);
120121
leftVelocityController.setOutputRange(-1.0, 1.0);
121122
leftVelocityController.setContinuous(false);
122-
leftVelocityController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceLeft", 2));
123+
leftVelocityController.setAbsoluteTolerance(Robot.getConst("MoveToleranceLeft", 2));
123124

124125
rightEncPort1 = new DigitalInput(getPort("1RightEnc", 2));
125126
rightEncPort2 = new DigitalInput(getPort("2RightEnc", 3));
@@ -133,13 +134,14 @@ public RobotMap() {
133134
configSPX(dtRightSlave);
134135
dtRight = new SpeedControllerGroup(dtRightDrive, dtRightSlave);
135136

136-
rightVelocityController = new VelocityPIDController(Robot.getConst("ConstMoveRightkP", 1),
137-
Robot.getConst("ConstMoveRightkI", 0), Robot.getConst("ConstMoveRightkD", 0), rightEncRate, dtRight);
137+
rightVelocityController = new VelocityPIDController(Robot.getConst("MoveRightkP", 1),
138+
Robot.getConst("MoveRightkI", 0), Robot.getConst("MoveRightkD", 0), 1 / Robot.getConst("MaxSpeed", 17),
139+
rightEncRate, dtRight);
138140
rightVelocityController.enable();
139141
rightVelocityController.setInputRange(0, Double.MAX_VALUE);
140142
rightVelocityController.setOutputRange(-1.0, 1.0);
141143
rightVelocityController.setContinuous(false);
142-
rightVelocityController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceRight", 2));
144+
rightVelocityController.setAbsoluteTolerance(Robot.getConst("MoveToleranceRight", 2));
143145

144146
robotDrive = new DifferentialDrive(leftVelocityController, rightVelocityController);
145147

Robot2018/src/org/usfirst/frc/team199/Robot2018/autonomous/VelocityPIDController.java

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,13 +20,16 @@ public class VelocityPIDController extends PIDController implements SpeedControl
2020
* the integral PID constant
2121
* @param kd
2222
* the derivative PID constant
23+
* @param kf
24+
* the feed forward value: should be 1/MaxSpeed
2325
* @param source
2426
* the sensor (e.g. velocity encoder) you are reading from
2527
* @param output
2628
* the SpeedController you are telling what to do
2729
*/
28-
public VelocityPIDController(double kp, double ki, double kd, PIDSource source, SpeedControllerGroup output) {
29-
super(kp, ki, kd, source, output);
30+
public VelocityPIDController(double kp, double ki, double kd, double kf, PIDSource source,
31+
SpeedControllerGroup output) {
32+
super(kp, ki, kd, kf, source, output);
3033
out = output;
3134
}
3235

Robot2018/src/org/usfirst/frc/team199/Robot2018/subsystems/Drivetrain.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -112,9 +112,9 @@ public double getDtRightSpeed() {
112112
@Override
113113
public void updatePidConstants() {
114114
leftVelocityController.setPID(Robot.getConst("MoveLeftkP", 1), Robot.getConst("MoveLeftkI", 0),
115-
Robot.getConst("MoveLeftkD", 0));
115+
Robot.getConst("MoveLeftkD", 0), 1 / Robot.getConst("MaxSpeed", 17));
116116
rightVelocityController.setPID(Robot.getConst("MoveRightkP", 1), Robot.getConst("MoveRightkI", 0),
117-
Robot.getConst("MoveRightkD", 0));
117+
Robot.getConst("MoveRightkD", 0), 1 / Robot.getConst("MaxSpeed", 17));
118118
}
119119

120120
/**

0 commit comments

Comments
 (0)