mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[hal, wpilib] Remove SPI support (#7678)
This commit is contained in:
@@ -9,7 +9,7 @@ import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.MecanumDrive;
|
||||
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.DriveConstants;
|
||||
@@ -54,7 +54,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
DriveConstants.kRearRightEncoderReversed);
|
||||
|
||||
// The gyro sensor
|
||||
private final ADXRS450_Gyro m_gyro = new ADXRS450_Gyro();
|
||||
private final AnalogGyro m_gyro = new AnalogGyro(0);
|
||||
|
||||
// Odometry class for tracking robot pose
|
||||
MecanumDriveOdometry m_odometry =
|
||||
|
||||
@@ -10,7 +10,7 @@ import edu.wpi.first.math.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
@@ -49,7 +49,7 @@ public class Drive extends SubsystemBase {
|
||||
DriveConstants.kRightEncoderPorts[1],
|
||||
DriveConstants.kRightEncoderReversed);
|
||||
|
||||
private final ADXRS450_Gyro m_gyro = new ADXRS450_Gyro();
|
||||
private final AnalogGyro m_gyro = new AnalogGyro(0);
|
||||
private final ProfiledPIDController m_controller =
|
||||
new ProfiledPIDController(
|
||||
DriveConstants.kTurnP,
|
||||
|
||||
@@ -10,7 +10,7 @@ import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
@@ -53,7 +53,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
DriveConstants.kRearRightTurningEncoderReversed);
|
||||
|
||||
// The gyro sensor
|
||||
private final ADXRS450_Gyro m_gyro = new ADXRS450_Gyro();
|
||||
private final AnalogGyro m_gyro = new AnalogGyro(0);
|
||||
|
||||
// Odometry class for tracking robot pose
|
||||
SwerveDriveOdometry m_odometry =
|
||||
|
||||
Reference in New Issue
Block a user