diff --git a/src/org/usfirst/frc/team4737/robot/OI.java b/src/org/usfirst/frc/team4737/robot/OI.java index d5afb1a..ec11a87 100644 --- a/src/org/usfirst/frc/team4737/robot/OI.java +++ b/src/org/usfirst/frc/team4737/robot/OI.java @@ -68,7 +68,8 @@ public boolean get() { // User override to take control of driving new Trigger() { public boolean get() { - return driver.getThumbstick("LS").Y.get() != 0 || driver.getThumbstick("RS").Y.get() != 0; + return driver.getThumbstick("LS").X.get() != 0 || driver.getAxis("LT").get() != 0 + || driver.getAxis("RT").get() != 0; } }.whileActive(new TeleopRacingDrive()); diff --git a/src/org/usfirst/frc/team4737/robot/subsystems/Drivetrain.java b/src/org/usfirst/frc/team4737/robot/subsystems/Drivetrain.java index dca19de..07b8e37 100644 --- a/src/org/usfirst/frc/team4737/robot/subsystems/Drivetrain.java +++ b/src/org/usfirst/frc/team4737/robot/subsystems/Drivetrain.java @@ -1,6 +1,7 @@ package org.usfirst.frc.team4737.robot.subsystems; import org.usfirst.frc.team4737.robot.RobotMap; +import org.usfirst.frc.team4737.robot.commands.drivetrain.TeleopRacingDrive; import org.usfirst.frc.team4737.robot.commands.drivetrain.TeleopTankDrive; import com.ctre.phoenix.motorcontrol.NeutralMode; @@ -42,8 +43,7 @@ public Drivetrain() { } public void initDefaultCommand() { - // Set the default command for a subsystem here. - setDefaultCommand(new TeleopTankDrive()); + setDefaultCommand(new TeleopRacingDrive()); } public void setBrakeMode() {