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

Commit dfd6217

Browse files
VPID works with shifting gears!
yes it works now w/ shifting btwn high and low gears (i.e. max target and kf changes correctly) VPID targets are a little funky though (i.e. +- when they should be the opposite) due to DifferentialDrive auto inversion, joystick inversion, etc. Wheels still moving in intended joystick direction though. Will just have to see if this becomes problematic
1 parent fd1b3b4 commit dfd6217

2 files changed

Lines changed: 4 additions & 4 deletions

File tree

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

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -116,7 +116,7 @@ public RobotMap() {
116116

117117
leftVelocityController = new VelocityPIDController(Robot.getConst("VelocityLeftkP", 0),
118118
Robot.getConst("VelocityLeftkI", 0), Robot.getConst("VelocityLeftkD", 0),
119-
/*1 / Robot.getConst("Max Low Speed", 84)*/ Robot.getConst("VelocityLeftkF", 1/84.0), leftEncRate, dtLeft);
119+
1 / Robot.getConst("Max Low Speed", 84), leftEncRate, dtLeft);
120120
leftVelocityController.setInputRange(-Robot.getConst("Max High Speed", 204),
121121
Robot.getConst("Max High Speed", 204));
122122
leftVelocityController.setOutputRange(-1.0, 1.0);
@@ -140,16 +140,14 @@ public RobotMap() {
140140

141141
rightVelocityController = new VelocityPIDController(Robot.getConst("VelocityRightkP", 0),
142142
Robot.getConst("VelocityRightkI", 0), Robot.getConst("VelocityRightkD", 0),
143-
/*1 / Robot.getConst("Max Low Speed", 84)*/ Robot.getConst("VelocityRightkF", 1/84.0), rightEncRate, dtRight);
143+
1 / Robot.getConst("Max Low Speed", 84), rightEncRate, dtRight);
144144
rightVelocityController.setInputRange(-Robot.getConst("Max High Speed", 204),
145145
Robot.getConst("Max High Speed", 204));
146146
rightVelocityController.setOutputRange(-1.0, 1.0);
147147
rightVelocityController.setContinuous(false);
148148
rightVelocityController.setAbsoluteTolerance(Robot.getConst("VelocityToleranceRight", 2));
149149

150150
robotDrive = new DifferentialDrive(leftVelocityController, rightVelocityController);
151-
// robotDrive = new DifferentialDrive(dtLeft, dtRight);
152-
153151
robotDrive.setMaxOutput(Robot.getConst("Max High Speed", 204));
154152

155153
distEncAvg = new PIDSourceAverage(leftEncDist, rightEncDist);

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

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -266,12 +266,14 @@ public double resetVelocityPIDkFConsts() {
266266
double newKF = 1 / getCurrentMaxSpeed();
267267
leftVelocityController.setF(newKF);
268268
rightVelocityController.setF(newKF);
269+
SmartDashboard.putNumber("VPID kF", newKF);
269270
return newKF;
270271
}
271272

272273
public double resetVPIDInputRanges() {
273274
double currentMaxSpd = getCurrentMaxSpeed();
274275
leftVelocityController.setInputRange(-currentMaxSpd, currentMaxSpd);
276+
rightVelocityController.setInputRange(-currentMaxSpd, currentMaxSpd);
275277
return currentMaxSpd;
276278
}
277279

0 commit comments

Comments
 (0)