diff --git a/src/org/usfirst/frc/team4737/robot/subsystems/Intake.java b/src/org/usfirst/frc/team4737/robot/subsystems/Intake.java index 24c0250..f13bc76 100644 --- a/src/org/usfirst/frc/team4737/robot/subsystems/Intake.java +++ b/src/org/usfirst/frc/team4737/robot/subsystems/Intake.java @@ -15,18 +15,20 @@ public class Intake extends Subsystem { // Put methods for controlling this subsystem // here. Call these from Commands. - private WPI_TalonSRX leftMotor; - private WPI_TalonSRX rightMotor; + private WPI_TalonSRX leftMotorMaster; + private WPI_TalonSRX rightMotorSlave; public Intake() { - leftMotor = new WPI_TalonSRX(RobotMap.INTAKE_LEFT); - rightMotor = new WPI_TalonSRX(RobotMap.INTAKE_RIGHT); + leftMotorMaster = new WPI_TalonSRX(RobotMap.INTAKE_LEFT); + rightMotorSlave = new WPI_TalonSRX(RobotMap.INTAKE_RIGHT); + + rightMotorSlave.setInverted(true); + rightMotorSlave.follow(leftMotorMaster); } public void initDefaultCommand() { // Set the default command for a subsystem here. setDefaultCommand(new StopIntake()); - } /** @@ -35,7 +37,7 @@ public void initDefaultCommand() { * ranges from -1 to 1. */ public void setSpeed(double speed) { - // TODO + leftMotorMaster.set(speed); } - + }