mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpilib] Deprecate Accelerometer and Gyro interfaces (#5445)
Accelerometer is hyper-specific to ADXL accelerometers, and Gyro is less useful now that 3D IMUs are prevalent, and if those IMUs want to support the Gyro interface, they also need to provide a way to set the axis used for the Gyro interface, which is confusing. Higher-order functions (e.g., lambdas) are a more flexible interface boundary than interfaces, but they didn't exist when these interfaces were created.
This commit is contained in:
@@ -8,7 +8,6 @@ import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
@@ -44,7 +43,7 @@ public class DriveSubsystem extends Subsystem {
|
||||
DriveConstants.kRightEncoderReversed);
|
||||
|
||||
// The gyro sensor
|
||||
private final Gyro m_gyro = new ADXRS450_Gyro();
|
||||
private final ADXRS450_Gyro m_gyro = new ADXRS450_Gyro();
|
||||
|
||||
/** Creates a new DriveSubsystem. */
|
||||
public DriveSubsystem() {
|
||||
|
||||
@@ -13,7 +13,6 @@ import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.MecanumDrive;
|
||||
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
@@ -55,7 +54,7 @@ public class DriveSubsystem extends Subsystem {
|
||||
DriveConstants.kRearRightEncoderReversed);
|
||||
|
||||
// The gyro sensor
|
||||
private final Gyro m_gyro = new ADXRS450_Gyro();
|
||||
private final ADXRS450_Gyro m_gyro = new ADXRS450_Gyro();
|
||||
|
||||
// Odometry class for tracking robot pose
|
||||
MecanumDriveOdometry m_odometry =
|
||||
|
||||
@@ -11,7 +11,6 @@ import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
@@ -47,7 +46,7 @@ public class DriveSubsystem extends Subsystem {
|
||||
DriveConstants.kRightEncoderReversed);
|
||||
|
||||
// The gyro sensor
|
||||
private final Gyro m_gyro = new ADXRS450_Gyro();
|
||||
private final ADXRS450_Gyro m_gyro = new ADXRS450_Gyro();
|
||||
|
||||
// Odometry class for tracking robot pose
|
||||
private final DifferentialDriveOdometry m_odometry;
|
||||
|
||||
@@ -12,7 +12,6 @@ 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.examples.swervecontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
@@ -54,7 +53,7 @@ public class DriveSubsystem extends Subsystem {
|
||||
DriveConstants.kRearRightTurningEncoderReversed);
|
||||
|
||||
// The gyro sensor
|
||||
private final Gyro m_gyro = new ADXRS450_Gyro();
|
||||
private final ADXRS450_Gyro m_gyro = new ADXRS450_Gyro();
|
||||
|
||||
// Odometry class for tracking robot pose
|
||||
SwerveDriveOdometry m_odometry =
|
||||
|
||||
Reference in New Issue
Block a user