diff --git a/src/main/java/frc/team3388/robot/Robot.java b/src/main/java/frc/team3388/robot/Robot.java index 2ef4d46..c0ec7a3 100644 --- a/src/main/java/frc/team3388/robot/Robot.java +++ b/src/main/java/frc/team3388/robot/Robot.java @@ -4,11 +4,13 @@ import com.flash3388.flashlib.frc.robot.base.iterative.IterativeFrcRobot; import com.flash3388.flashlib.hid.XboxController; import com.flash3388.flashlib.robot.base.DelegatingRobotControl; +import frc.team3388.robot.actions.DriveAction; import frc.team3388.robot.subsystems.DriveSystem; import frc.team3388.robot.subsystems.HopperSystem; import frc.team3388.robot.subsystems.IntakeSystem; import frc.team3388.robot.subsystems.ShooterSystem; import frc.team3388.robot.subsystems.FeederSystem; +import com.flash3388.flashlib.scheduling.actions.Action; public class Robot extends DelegatingRobotControl implements IterativeFrcRobot { @@ -51,7 +53,8 @@ public void disabledPeriodic() { @Override public void teleopInit() { - + Action drive = new DriveAction(driveSystem, xbox); + drive.start(); } @Override diff --git a/src/main/java/frc/team3388/robot/RobotMap.java b/src/main/java/frc/team3388/robot/RobotMap.java index bea472c..ebf5275 100644 --- a/src/main/java/frc/team3388/robot/RobotMap.java +++ b/src/main/java/frc/team3388/robot/RobotMap.java @@ -21,6 +21,6 @@ public class RobotMap { // drive motors public static final int DRIVE_RIGHT1 = 1; public static final int DRIVE_RIGHT2 = 2; - public static final int DRIVE_LEFT1 = 3; - public static final int DRIVE_LEFT2 = 4; + public static final int DRIVE_LEFT1 = 5; + public static final int DRIVE_LEFT2 = 7; } diff --git a/src/main/java/frc/team3388/robot/SystemFactory.java b/src/main/java/frc/team3388/robot/SystemFactory.java index 736dc8a..7368770 100644 --- a/src/main/java/frc/team3388/robot/SystemFactory.java +++ b/src/main/java/frc/team3388/robot/SystemFactory.java @@ -66,6 +66,7 @@ public DriveSystem createDriveSystem() { .add(new WPI_TalonSRX(RobotMap.DRIVE_LEFT1)) .add(new WPI_TalonSRX(RobotMap.DRIVE_LEFT2)) .build(); + left.setInverted(true); return new DriveSystem(right, left); }