@@ -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
0 commit comments