diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index 7efbfda..3456b71 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -9,7 +9,7 @@ package frc4388.robot; import com.ctre.phoenix.motorcontrol.InvertType; import com.ctre.phoenix.motorcontrol.NeutralMode; -import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; +import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; import com.ctre.phoenix.sensors.PigeonIMU; import edu.wpi.first.wpilibj.Spark; @@ -37,10 +37,10 @@ public class RobotMap { } /* Drive Subsystem */ - public final WPI_TalonSRX leftFrontMotor = new WPI_TalonSRX(DriveConstants.DRIVE_LEFT_FRONT_CAN_ID); - public final WPI_TalonSRX rightFrontMotor = new WPI_TalonSRX(DriveConstants.DRIVE_RIGHT_FRONT_CAN_ID); - public final WPI_TalonSRX leftBackMotor = new WPI_TalonSRX(DriveConstants.DRIVE_LEFT_BACK_CAN_ID); - public final WPI_TalonSRX rightBackMotor = new WPI_TalonSRX(DriveConstants.DRIVE_RIGHT_BACK_CAN_ID); + public final WPI_TalonFX leftFrontMotor = new WPI_TalonFX(DriveConstants.DRIVE_LEFT_FRONT_CAN_ID); + public final WPI_TalonFX rightFrontMotor = new WPI_TalonFX(DriveConstants.DRIVE_RIGHT_FRONT_CAN_ID); + public final WPI_TalonFX leftBackMotor = new WPI_TalonFX(DriveConstants.DRIVE_LEFT_BACK_CAN_ID); + public final WPI_TalonFX rightBackMotor = new WPI_TalonFX(DriveConstants.DRIVE_RIGHT_BACK_CAN_ID); public final DifferentialDrive driveTrain = new DifferentialDrive(leftFrontMotor, rightFrontMotor); public final RobotGyro gyroDrive = new RobotGyro(new PigeonIMU(DriveConstants.DRIVE_PIGEON_ID)); diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 1703513..9bbdee7 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -7,7 +7,7 @@ package frc4388.robot.subsystems; -import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; +import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -26,18 +26,18 @@ public class Drive extends SubsystemBase { private RobotTime m_robotTime = RobotTime.getInstance(); - private WPI_TalonSRX m_leftFrontMotor; - private WPI_TalonSRX m_rightFrontMotor; - private WPI_TalonSRX m_leftBackMotor; - private WPI_TalonSRX m_rightBackMotor; + private WPI_TalonFX m_leftFrontMotor; + private WPI_TalonFX m_rightFrontMotor; + private WPI_TalonFX m_leftBackMotor; + private WPI_TalonFX m_rightBackMotor; private DifferentialDrive m_driveTrain; private RobotGyro m_gyro; /** * Add your docs here. */ - public Drive(WPI_TalonSRX leftFrontMotor, WPI_TalonSRX rightFrontMotor, WPI_TalonSRX leftBackMotor, - WPI_TalonSRX rightBackMotor, DifferentialDrive driveTrain, RobotGyro gyro) { + public Drive(WPI_TalonFX leftFrontMotor, WPI_TalonFX rightFrontMotor, WPI_TalonFX leftBackMotor, + WPI_TalonFX rightBackMotor, DifferentialDrive driveTrain, RobotGyro gyro) { m_leftFrontMotor = leftFrontMotor; m_rightFrontMotor = rightFrontMotor;