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

Commit 54c5bea

Browse files
Other misc. offseason robot configurations to ensure smooth use
Includes motor inversions, joystick input inversions, etc.
1 parent e24676a commit 54c5bea

3 files changed

Lines changed: 18 additions & 14 deletions

File tree

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,9 +65,9 @@ public void robotInit() {
6565
intakeEject = new IntakeEject();
6666
lift = new Lift();
6767
dt = new Drivetrain();
68-
rmap.initPIDControllers();
6968
ld = new LeftDrive();
7069
rd = new RightDrive();
70+
rmap.initPIDControllers();
7171
oi = new OI();
7272
listen = new Listener();
7373
// chooser.addObject("My Auto", new MyAutoCommand());

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

Lines changed: 14 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -87,18 +87,26 @@ private void configSPX(WPI_VictorSPX mc) {
8787
}
8888

8989
public RobotMap() {
90-
90+
91+
ahrs = new AHRS(SerialPort.Port.kMXP);
92+
dtGyro = new AnalogGyro(getPort("Gyro", 0));
93+
//dtGear = new DoubleSolenoid(getPort("1dtGearSolenoid", 0), getPort("2dtGearSolenoid", 1));
94+
9195
leftEnc = new Encoder(getPort("1LeftEnc", 0), getPort("2LeftEnc", 1));
92-
dtLeftDrive = new WPI_TalonSRX(getPort("LeftTalonSRXDrive", 0));
96+
dtLeftDrive = new WPI_TalonSRX(2);
97+
//getPort("LeftTalonSRXDrive", 2));
9398
configSRX(dtLeftDrive);
94-
dtLeftSlave = new WPI_VictorSPX(getPort("LeftTalonSPXSlave", 1));
99+
dtLeftSlave = new WPI_VictorSPX(0);
100+
//getPort("LeftTalonSPXSlave", 0));
95101
configSPX(dtLeftSlave);
96102
dtLeft = new SpeedControllerGroup(dtLeftDrive, dtLeftSlave);
97103

98104
rightEnc = new Encoder(getPort("1RightEnc", 2), getPort("2RightEnc", 3));
99-
dtRightDrive = new WPI_TalonSRX(getPort("RightTalonSRXDrive", 2));
105+
dtRightDrive = new WPI_TalonSRX(1);
106+
//getPort("RightTalonSRXDrive", 1));
100107
configSRX(dtRightDrive);
101-
dtRightSlave = new WPI_VictorSPX(getPort("RightTalonSPXSlave", 3));
108+
dtRightSlave = new WPI_VictorSPX(3);
109+
//getPort("RightTalonSPXSlave", 3));
102110
configSPX(dtRightSlave);
103111
dtRight = new SpeedControllerGroup(dtRightDrive, dtRightSlave);
104112

@@ -112,14 +120,10 @@ public RobotMap() {
112120
// moveController.setOutputRange(-1.0, 1.0);
113121
// moveController.setContinuous(false);
114122
// 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));
120123

121124
}
122125

126+
/** Initializes pid controllers seperately from robotMap because the required parameters have not been initialized yet.*/
123127
public void initPIDControllers() {
124128
turnController = new PIDController(Robot.getConst("TurnkP", 1), Robot.getConst("TurnkI", 0),
125129
Robot.getConst("TurnkD", 0), ahrs, Robot.dt);

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

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -153,12 +153,12 @@ public void resetEnc() {
153153
public void teleopDrive() {
154154
if (Robot.getBool("Arcade Drive", true)) {
155155
if (Robot.getBool("Arcade Drive Default Setup", true)) {
156-
Robot.dt.arcadeDrive(Robot.oi.leftJoy.getY(), Robot.oi.rightJoy.getX());
156+
Robot.dt.arcadeDrive(-Robot.oi.leftJoy.getY(), Robot.oi.rightJoy.getX());
157157
} else {
158-
Robot.dt.arcadeDrive(Robot.oi.rightJoy.getY(), Robot.oi.leftJoy.getX());
158+
Robot.dt.arcadeDrive(-Robot.oi.rightJoy.getY(), Robot.oi.leftJoy.getX());
159159
}
160160
} else {
161-
Robot.dt.tankDrive(Robot.oi.leftJoy.getY(), Robot.oi.rightJoy.getY());
161+
Robot.dt.tankDrive(-Robot.oi.leftJoy.getY(), Robot.oi.rightJoy.getY());
162162
}
163163
}
164164

0 commit comments

Comments
 (0)