From c9da9d85851a5e5de02a7b87af7c2f2b0b57bd52 Mon Sep 17 00:00:00 2001 From: HFocus Date: Wed, 7 Aug 2019 19:20:10 -0600 Subject: [PATCH] Implement Drive Code --- build.gradle | 2 +- src/main/java/frc4388/robot/Robot.java | 2 ++ .../java/frc4388/robot/subsystems/Drive.java | 17 ++++++++++++----- 3 files changed, 15 insertions(+), 6 deletions(-) diff --git a/build.gradle b/build.gradle index 9128ffc..9216a46 100644 --- a/build.gradle +++ b/build.gradle @@ -3,7 +3,7 @@ plugins { id "edu.wpi.first.GradleRIO" version "2019.1.1" } -def ROBOT_MAIN_CLASS = "frc.robot.Main" +def ROBOT_MAIN_CLASS = "frc4388.robot.Main" // Define my targets (RoboRIO) and artifacts (deployable files) // This is added by GradleRIO's backing project EmbeddedTools. diff --git a/src/main/java/frc4388/robot/Robot.java b/src/main/java/frc4388/robot/Robot.java index ed3e072..aa44e07 100644 --- a/src/main/java/frc4388/robot/Robot.java +++ b/src/main/java/frc4388/robot/Robot.java @@ -13,6 +13,7 @@ import edu.wpi.first.wpilibj.command.Scheduler; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import frc4388.robot.commands.ExampleCommand; +import frc4388.robot.subsystems.Drive; import frc4388.robot.subsystems.ExampleSubsystem; import frc4388.robot.subsystems.LED; import frc4388.utility.controller.XboxController; @@ -27,6 +28,7 @@ import frc4388.utility.controller.XboxController; public class Robot extends TimedRobot { public static ExampleSubsystem m_subsystem = new ExampleSubsystem(); public static LED m_led = new LED(); + public static Drive m_Drive = new Drive(); public static OI m_oi; Command m_autonomousCommand; diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index d6be580..080c5eb 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -17,6 +17,7 @@ import edu.wpi.first.wpilibj.Talon; import edu.wpi.first.wpilibj.command.Subsystem; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import frc4388.robot.RobotMap; +import frc4388.robot.OI; import frc4388.robot.Robot; import frc4388.utility.controller.XboxController; @@ -27,12 +28,14 @@ public class Drive extends Subsystem { // Put methods for controlling this subsystem // here. Call these from Commands. - WPI_TalonSRX m_leftFrontMotor = new WPI_TalonSRX(RobotMap.DRIVE_LEFT_FRONT_CAN_ID); - WPI_TalonSRX m_rightFrontMotor = new WPI_TalonSRX(RobotMap.DRIVE_RIGHT_FRONT_CAN_ID); - WPI_TalonSRX m_leftBackMotor = new WPI_TalonSRX(RobotMap.DRIVE_LEFT_BACK_CAN_ID); - WPI_TalonSRX m_rightBackMotor = new WPI_TalonSRX(RobotMap.DRIVE_RIGHT_BACK_CAN_ID); + public static WPI_TalonSRX m_leftFrontMotor = new WPI_TalonSRX(RobotMap.DRIVE_LEFT_FRONT_CAN_ID); + public static WPI_TalonSRX m_rightFrontMotor = new WPI_TalonSRX(RobotMap.DRIVE_RIGHT_FRONT_CAN_ID); + public static WPI_TalonSRX m_leftBackMotor = new WPI_TalonSRX(RobotMap.DRIVE_LEFT_BACK_CAN_ID); + public static WPI_TalonSRX m_rightBackMotor = new WPI_TalonSRX(RobotMap.DRIVE_RIGHT_BACK_CAN_ID); - DifferentialDrive m_driveTrain = new DifferentialDrive(m_leftFrontMotor, m_rightFrontMotor); + public static DifferentialDrive m_driveTrain = new DifferentialDrive(m_leftFrontMotor, m_rightFrontMotor); + + private static double m_inputMove, m_inputSteer; public Drive(){ /* factory default values */ @@ -60,6 +63,10 @@ public class Drive extends Subsystem { @Override public void periodic() { + m_inputMove = OI.getInstance().getDriverController().getLeftYAxis(); + m_inputSteer = -(OI.getInstance().getDriverController().getRightXAxis()); + + m_driveTrain.arcadeDrive(m_inputMove, m_inputSteer); } @Override