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

Commit cdf299b

Browse files
committed
2 parents b556a57 + e24676a commit cdf299b

2 files changed

Lines changed: 19 additions & 12 deletions

File tree

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

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@ public void robotInit() {
6565
intakeEject = new IntakeEject();
6666
lift = new Lift();
6767
dt = new Drivetrain();
68+
rmap.initPIDControllers();
6869
ld = new LeftDrive();
6970
rd = new RightDrive();
7071
oi = new OI();

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

Lines changed: 18 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -103,13 +103,7 @@ public RobotMap() {
103103
dtRight = new SpeedControllerGroup(dtRightDrive, dtRightSlave);
104104

105105
robotDrive = new DifferentialDrive(dtLeft, dtRight);
106-
turnController = new PIDController(Robot.getConst("TurnkP", 1), Robot.getConst("TurnkI", 0),
107-
Robot.getConst("TurnkD", 0), ahrs, Robot.dt);
108-
turnController.disable();
109-
turnController.setInputRange(-180, 180);
110-
turnController.setOutputRange(-1.0, 1.0);
111-
turnController.setContinuous();
112-
turnController.setAbsoluteTolerance(Robot.getConst("TurnTolerance", 1));
106+
113107
// moveController = new PIDController(Robot.getConst("MovekP", 1),
114108
// Robot.getConst("MovekI", 0),
115109
// Robot.getConst("MovekD", 0), Robot.dt, Robot.dt);
@@ -118,6 +112,23 @@ public RobotMap() {
118112
// moveController.setOutputRange(-1.0, 1.0);
119113
// moveController.setContinuous(false);
120114
// moveController.setAbsoluteTolerance(Robot.getConst("MoveTolerance", 2));
115+
116+
117+
ahrs = new AHRS(SerialPort.Port.kMXP);
118+
dtGyro = new AnalogGyro(getPort("Gyro", 0));
119+
dtGear = new DoubleSolenoid(getPort("1dtGearSolenoid", 0), getPort("2dtGearSolenoid", 1));
120+
121+
}
122+
123+
public void initPIDControllers() {
124+
turnController = new PIDController(Robot.getConst("TurnkP", 1), Robot.getConst("TurnkI", 0),
125+
Robot.getConst("TurnkD", 0), ahrs, Robot.dt);
126+
turnController.disable();
127+
turnController.setInputRange(-180, 180);
128+
turnController.setOutputRange(-1.0, 1.0);
129+
turnController.setContinuous();
130+
turnController.setAbsoluteTolerance(Robot.getConst("TurnTolerance", 1));
131+
121132
moveLeftController = new PIDController(Robot.getConst("MoveLeftkP", 1), Robot.getConst("MoveLeftkI", 0),
122133
Robot.getConst("MoveLeftkD", 0), Robot.ld, Robot.ld);
123134
moveLeftController.disable();
@@ -132,11 +143,6 @@ public RobotMap() {
132143
moveRightController.setOutputRange(-1.0, 1.0);
133144
moveRightController.setContinuous(false);
134145
moveRightController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceRight", 2));
135-
136-
ahrs = new AHRS(SerialPort.Port.kMXP);
137-
dtGyro = new AnalogGyro(getPort("Gyro", 0));
138-
dtGear = new DoubleSolenoid(getPort("1dtGearSolenoid", 0), getPort("2dtGearSolenoid", 1));
139-
140146
}
141147

142148
/**

0 commit comments

Comments
 (0)