From 2720626c9f916ba466376bce37ec92f50f98602b Mon Sep 17 00:00:00 2001 From: aarav18 Date: Sat, 22 Jan 2022 13:55:44 -0700 Subject: [PATCH] Update RobotMap.java --- src/main/java/frc4388/robot/RobotMap.java | 42 +++++------------------ 1 file changed, 8 insertions(+), 34 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index 3456b71..b998ca9 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -12,11 +12,12 @@ import com.ctre.phoenix.motorcontrol.NeutralMode; import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; import com.ctre.phoenix.sensors.PigeonIMU; -import edu.wpi.first.wpilibj.Spark; +import edu.wpi.first.wpilibj.motorcontrol.Spark; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import frc4388.robot.Constants.DriveConstants; +import frc4388.robot.Constants.FalconTesterConstants; import frc4388.robot.Constants.LEDConstants; -import frc4388.utility.RobotGyro; +import frc4388.robot.subsystems.FalconTester; /** * Defines and holds all I/O objects on the Roborio. This is useful for unit @@ -26,7 +27,7 @@ public class RobotMap { public RobotMap() { configureLEDMotorControllers(); - configureDriveMotorControllers(); + configureFalconTestMotorControllers(); } /* LED Subsystem */ @@ -36,36 +37,9 @@ public class RobotMap { } - /* Drive Subsystem */ - 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)); - - void configureDriveMotorControllers() { - - /* factory default values */ - leftFrontMotor.configFactoryDefault(); - rightFrontMotor.configFactoryDefault(); - leftBackMotor.configFactoryDefault(); - rightBackMotor.configFactoryDefault(); - - /* set back motors as followers */ - leftBackMotor.follow(leftFrontMotor); - rightBackMotor.follow(rightFrontMotor); - - /* set neutral mode */ - leftFrontMotor.setNeutralMode(NeutralMode.Brake); - rightFrontMotor.setNeutralMode(NeutralMode.Brake); - leftFrontMotor.setNeutralMode(NeutralMode.Brake); - rightFrontMotor.setNeutralMode(NeutralMode.Brake); - - /* flip input so forward becomes back, etc */ - leftFrontMotor.setInverted(false); - rightFrontMotor.setInverted(false); - leftBackMotor.setInverted(InvertType.FollowMaster); - rightBackMotor.setInverted(InvertType.FollowMaster); + public final WPI_TalonFX falconTestMotor = new WPI_TalonFX(FalconTesterConstants.CAN_ID); + void configureFalconTestMotorControllers() { + falconTestMotor.configFactoryDefault(); + falconTestMotor.setNeutralMode(NeutralMode.Brake); } }