From 42f19ea2c70caf9385b8c19ad7fe9993b0ffbcef Mon Sep 17 00:00:00 2001 From: Gordon Chen Date: Sat, 27 Jan 2024 14:49:43 -0500 Subject: [PATCH] update gyro CAN ID and remove TalonSRX --- src/main/java/frc/robot/constants/RobotMap.java | 2 +- src/main/java/frc/robot/subsystems/Drivetrain.java | 4 +--- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/constants/RobotMap.java b/src/main/java/frc/robot/constants/RobotMap.java index a2bcc10..0568ab3 100644 --- a/src/main/java/frc/robot/constants/RobotMap.java +++ b/src/main/java/frc/robot/constants/RobotMap.java @@ -10,7 +10,7 @@ public static class Drivetrain { public static final int[] STEER = {5, 6, 7, 8}; public static final int[] CANCoder = {1, 2, 3, 4}; - public static final int GYRO = 9; + public static final int GYRO = 1; } } } diff --git a/src/main/java/frc/robot/subsystems/Drivetrain.java b/src/main/java/frc/robot/subsystems/Drivetrain.java index 5c8d658..bd94014 100644 --- a/src/main/java/frc/robot/subsystems/Drivetrain.java +++ b/src/main/java/frc/robot/subsystems/Drivetrain.java @@ -3,7 +3,6 @@ import java.text.DecimalFormat; -import com.ctre.phoenix.motorcontrol.can.TalonSRX; import com.ctre.phoenix.sensors.PigeonIMU; import edu.wpi.first.math.geometry.Pose2d; @@ -70,8 +69,7 @@ private Drivetrain() { } // Create and reset gyro. - TalonSRX gyroController = new TalonSRX(RobotMap.canIDs.Drivetrain.GYRO); - m_gyro = new PigeonIMU(gyroController); + m_gyro = new PigeonIMU(RobotMap.canIDs.Drivetrain.GYRO); resetGyro(); // Odometry.