From e8750b0764232d2092a20ca0d677584a2e2db0ab Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Thu, 13 Jul 2023 15:40:26 -0700 Subject: [PATCH] [wpilib] Deprecate Accelerometer and Gyro interfaces The former is hyper-specific to ADXL accelerometers, and the latter is no longer useful now that 3D IMUs are prevalent. Also, higher-order functions (e.g., lambdas) are a more flexible interface boundary than, well, interfaces, but they didn't exist when these interfaces were created. --- wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp | 4 ++ wpilibc/src/main/native/cpp/AnalogGyro.cpp | 4 ++ .../src/main/native/include/frc/ADXL345_I2C.h | 39 ++++++++--- .../src/main/native/include/frc/ADXL345_SPI.h | 39 ++++++++--- wpilibc/src/main/native/include/frc/ADXL362.h | 40 +++++++++--- .../main/native/include/frc/ADXRS450_Gyro.h | 30 ++++++--- .../src/main/native/include/frc/AnalogGyro.h | 38 +++++++++-- .../native/include/frc/BuiltInAccelerometer.h | 19 +++--- .../include/frc/interfaces/Accelerometer.h | 5 +- .../main/native/include/frc/interfaces/Gyro.h | 5 +- .../native/cpp/simulation/ADXL345SimTest.cpp | 2 +- .../native/cpp/simulation/ADXL362SimTest.cpp | 2 +- .../cpp/simulation/AccelerometerSimTest.cpp | 11 ++-- .../edu/wpi/first/wpilibj/ADXL345_I2C.java | 35 ++++++++-- .../edu/wpi/first/wpilibj/ADXL345_SPI.java | 35 ++++++++-- .../java/edu/wpi/first/wpilibj/ADXL362.java | 35 ++++++++-- .../edu/wpi/first/wpilibj/ADXRS450_Gyro.java | 64 +++++++++++++++++-- .../edu/wpi/first/wpilibj/AnalogGyro.java | 64 +++++++++++++++++-- .../first/wpilibj/BuiltInAccelerometer.java | 20 ++++-- .../wpilibj/interfaces/Accelerometer.java | 7 +- .../wpi/first/wpilibj/interfaces/Gyro.java | 7 +- .../wpilibj/shuffleboard/BuiltInWidgets.java | 3 - .../wpilibj/simulation/ADXL345SimTest.java | 9 ++- .../wpilibj/simulation/ADXL362SimTest.java | 5 +- .../simulation/AccelerometerSimTest.java | 12 ++-- .../subsystems/DriveSubsystem.java | 2 +- .../subsystems/DriveSubsystem.java | 2 +- .../subsystems/DriveSubsystem.java | 2 +- .../subsystems/DriveSubsystem.java | 2 +- 29 files changed, 422 insertions(+), 120 deletions(-) diff --git a/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp b/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp index 37313a08d9c..c134b5c1ee2 100644 --- a/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp +++ b/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp @@ -140,6 +140,10 @@ void ADXRS450_Gyro::Calibrate() { m_spi.ResetAccumulator(); } +Rotation2d ADXRS450_Gyro::GetRotation2d() const { + return units::degree_t{-GetAngle()}; +} + int ADXRS450_Gyro::GetPort() const { return m_port; } diff --git a/wpilibc/src/main/native/cpp/AnalogGyro.cpp b/wpilibc/src/main/native/cpp/AnalogGyro.cpp index cab9f940b00..df6d33f458d 100644 --- a/wpilibc/src/main/native/cpp/AnalogGyro.cpp +++ b/wpilibc/src/main/native/cpp/AnalogGyro.cpp @@ -133,6 +133,10 @@ void AnalogGyro::Calibrate() { FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel()); } +Rotation2d AnalogGyro::GetRotation2d() const { + return units::degree_t{-GetAngle()}; +} + std::shared_ptr AnalogGyro::GetAnalogInput() const { return m_analog; } diff --git a/wpilibc/src/main/native/include/frc/ADXL345_I2C.h b/wpilibc/src/main/native/include/frc/ADXL345_I2C.h index 6b6b76c64ad..96c028929dd 100644 --- a/wpilibc/src/main/native/include/frc/ADXL345_I2C.h +++ b/wpilibc/src/main/native/include/frc/ADXL345_I2C.h @@ -9,7 +9,6 @@ #include #include "frc/I2C.h" -#include "frc/interfaces/Accelerometer.h" namespace frc { @@ -24,10 +23,11 @@ namespace frc { * href="https://docs.wpilib.org/en/stable/docs/yearly-overview/known-issues.html#onboard-i2c-causing-system-lockups"> * WPILib Known Issues page for details. */ -class ADXL345_I2C : public Accelerometer, - public nt::NTSendable, +class ADXL345_I2C : public nt::NTSendable, public wpi::SendableHelper { public: + enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2, kRange_16G = 3 }; + enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 }; struct AllAxes { @@ -53,11 +53,34 @@ class ADXL345_I2C : public Accelerometer, I2C::Port GetI2CPort() const; int GetI2CDeviceAddress() const; - // Accelerometer interface - void SetRange(Range range) final; - double GetX() override; - double GetY() override; - double GetZ() override; + /** + * Set the measuring range of the accelerometer. + * + * @param range The maximum acceleration, positive or negative, that the + * accelerometer will measure. Not all accelerometers support all ranges. + */ + void SetRange(Range range); + + /** + * Returns the acceleration along the X axis in g-forces. + * + * @return The acceleration along the X axis in g-forces. + */ + double GetX(); + + /** + * Returns the acceleration along the Y axis in g-forces. + * + * @return The acceleration along the Y axis in g-forces. + */ + double GetY(); + + /** + * Returns the acceleration along the Z axis in g-forces. + * + * @return The acceleration along the Z axis in g-forces. + */ + double GetZ(); /** * Get the acceleration of one axis in Gs. diff --git a/wpilibc/src/main/native/include/frc/ADXL345_SPI.h b/wpilibc/src/main/native/include/frc/ADXL345_SPI.h index 18d48a3c5a9..04c88b24892 100644 --- a/wpilibc/src/main/native/include/frc/ADXL345_SPI.h +++ b/wpilibc/src/main/native/include/frc/ADXL345_SPI.h @@ -9,7 +9,6 @@ #include #include "frc/SPI.h" -#include "frc/interfaces/Accelerometer.h" namespace frc { @@ -19,10 +18,11 @@ namespace frc { * This class allows access to an Analog Devices ADXL345 3-axis accelerometer * via SPI. This class assumes the sensor is wired in 4-wire SPI mode. */ -class ADXL345_SPI : public Accelerometer, - public nt::NTSendable, +class ADXL345_SPI : public nt::NTSendable, public wpi::SendableHelper { public: + enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2, kRange_16G = 3 }; + enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 }; struct AllAxes { @@ -46,11 +46,34 @@ class ADXL345_SPI : public Accelerometer, SPI::Port GetSpiPort() const; - // Accelerometer interface - void SetRange(Range range) final; - double GetX() override; - double GetY() override; - double GetZ() override; + /** + * Set the measuring range of the accelerometer. + * + * @param range The maximum acceleration, positive or negative, that the + * accelerometer will measure. Not all accelerometers support all ranges. + */ + void SetRange(Range range); + + /** + * Returns the acceleration along the X axis in g-forces. + * + * @return The acceleration along the X axis in g-forces. + */ + double GetX(); + + /** + * Returns the acceleration along the Y axis in g-forces. + * + * @return The acceleration along the Y axis in g-forces. + */ + double GetY(); + + /** + * Returns the acceleration along the Z axis in g-forces. + * + * @return The acceleration along the Z axis in g-forces. + */ + double GetZ(); /** * Get the acceleration of one axis in Gs. diff --git a/wpilibc/src/main/native/include/frc/ADXL362.h b/wpilibc/src/main/native/include/frc/ADXL362.h index 451b5fb508d..67ed413ee7b 100644 --- a/wpilibc/src/main/native/include/frc/ADXL362.h +++ b/wpilibc/src/main/native/include/frc/ADXL362.h @@ -9,7 +9,6 @@ #include #include "frc/SPI.h" -#include "frc/interfaces/Accelerometer.h" namespace frc { @@ -18,10 +17,10 @@ namespace frc { * * This class allows access to an Analog Devices ADXL362 3-axis accelerometer. */ -class ADXL362 : public Accelerometer, - public nt::NTSendable, - public wpi::SendableHelper { +class ADXL362 : public nt::NTSendable, public wpi::SendableHelper { public: + enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2, kRange_16G = 3 }; + enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 }; struct AllAxes { double XAxis; @@ -52,11 +51,34 @@ class ADXL362 : public Accelerometer, SPI::Port GetSpiPort() const; - // Accelerometer interface - void SetRange(Range range) final; - double GetX() override; - double GetY() override; - double GetZ() override; + /** + * Set the measuring range of the accelerometer. + * + * @param range The maximum acceleration, positive or negative, that the + * accelerometer will measure. Not all accelerometers support all ranges. + */ + void SetRange(Range range); + + /** + * Returns the acceleration along the X axis in g-forces. + * + * @return The acceleration along the X axis in g-forces. + */ + double GetX(); + + /** + * Returns the acceleration along the Y axis in g-forces. + * + * @return The acceleration along the Y axis in g-forces. + */ + double GetY(); + + /** + * Returns the acceleration along the Z axis in g-forces. + * + * @return The acceleration along the Z axis in g-forces. + */ + double GetZ(); /** * Get the acceleration of one axis in Gs. diff --git a/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h b/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h index 55414d464ab..d923e13ff27 100644 --- a/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h +++ b/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h @@ -11,7 +11,7 @@ #include #include "frc/SPI.h" -#include "frc/interfaces/Gyro.h" +#include "frc/geometry/Rotation2d.h" namespace frc { @@ -28,8 +28,7 @@ namespace frc { * This class is for the digital ADXRS450 gyro sensor that connects via SPI. * Only one instance of an ADXRS %Gyro is supported. */ -class ADXRS450_Gyro : public Gyro, - public wpi::Sendable, +class ADXRS450_Gyro : public wpi::Sendable, public wpi::SendableHelper { public: /** @@ -61,7 +60,7 @@ class ADXRS450_Gyro : public Gyro, * * @return the current heading of the robot in degrees. */ - double GetAngle() const override; + double GetAngle() const; /** * Return the rate of rotation of the gyro @@ -70,7 +69,7 @@ class ADXRS450_Gyro : public Gyro, * * @return the current rate in degrees per second */ - double GetRate() const override; + double GetRate() const; /** * Reset the gyro. @@ -79,11 +78,9 @@ class ADXRS450_Gyro : public Gyro, * significant drift in the gyro and it needs to be recalibrated after it has * been running. */ - void Reset() override; + void Reset(); /** - * Initialize the gyro. - * * Calibrate the gyro by running for a number of samples and computing the * center value. Then use the center value as the Accumulator center value for * subsequent measurements. @@ -93,7 +90,22 @@ class ADXRS450_Gyro : public Gyro, * robot is first turned on while it's sitting at rest before the competition * starts. */ - void Calibrate() final; + void Calibrate(); + + /** + * Return the heading of the robot as a Rotation2d. + * + * The angle is continuous, that is it will continue from 360 to 361 degrees. + * This allows algorithms that wouldn't want to see a discontinuity in the + * gyro output as it sweeps past from 360 to 0 on the second time around. + * + * The angle is expected to increase as the gyro turns counterclockwise when + * looked at from the top. It needs to follow the NWU axis convention. + * + * @return the current heading of the robot as a Rotation2d. This heading is + * based on integration of the returned rate from the gyro. + */ + Rotation2d GetRotation2d() const; /** * Get the SPI port number. diff --git a/wpilibc/src/main/native/include/frc/AnalogGyro.h b/wpilibc/src/main/native/include/frc/AnalogGyro.h index 6565c93013f..0c472fbf7f8 100644 --- a/wpilibc/src/main/native/include/frc/AnalogGyro.h +++ b/wpilibc/src/main/native/include/frc/AnalogGyro.h @@ -10,7 +10,7 @@ #include #include -#include "frc/interfaces/Gyro.h" +#include "frc/geometry/Rotation2d.h" namespace frc { @@ -29,8 +29,7 @@ class AnalogInput; * * This class is for gyro sensors that connect to an analog input. */ -class AnalogGyro : public Gyro, - public wpi::Sendable, +class AnalogGyro : public wpi::Sendable, public wpi::SendableHelper { public: static constexpr int kOversampleBits = 10; @@ -118,7 +117,7 @@ class AnalogGyro : public Gyro, * @return The current heading of the robot in degrees. This heading is based * on integration of the returned rate from the gyro. */ - double GetAngle() const override; + double GetAngle() const; /** * Return the rate of rotation of the gyro @@ -127,7 +126,7 @@ class AnalogGyro : public Gyro, * * @return the current rate in degrees per second */ - double GetRate() const override; + double GetRate() const; /** * Return the gyro center value. If run after calibration, @@ -174,7 +173,7 @@ class AnalogGyro : public Gyro, * significant drift in the gyro and it needs to be recalibrated after it has * been running. */ - void Reset() final; + void Reset(); /** * Initialize the gyro. @@ -183,7 +182,32 @@ class AnalogGyro : public Gyro, */ void InitGyro(); - void Calibrate() final; + /** + * Calibrate the gyro by running for a number of samples and computing the + * center value. Then use the center value as the Accumulator center value for + * subsequent measurements. + * + * It's important to make sure that the robot is not moving while the + * centering calculations are in progress, this is typically done when the + * robot is first turned on while it's sitting at rest before the competition + * starts. + */ + void Calibrate(); + + /** + * Return the heading of the robot as a Rotation2d. + * + * The angle is continuous, that is it will continue from 360 to 361 degrees. + * This allows algorithms that wouldn't want to see a discontinuity in the + * gyro output as it sweeps past from 360 to 0 on the second time around. + * + * The angle is expected to increase as the gyro turns counterclockwise when + * looked at from the top. It needs to follow the NWU axis convention. + * + * @return the current heading of the robot as a Rotation2d. This heading is + * based on integration of the returned rate from the gyro. + */ + Rotation2d GetRotation2d() const; /** * Gets the analog input for the gyro. diff --git a/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h b/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h index 0e5bee68f37..b4e1bf4993f 100644 --- a/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h +++ b/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h @@ -7,8 +7,6 @@ #include #include -#include "frc/interfaces/Accelerometer.h" - namespace frc { /** @@ -16,10 +14,11 @@ namespace frc { * * This class allows access to the roboRIO's internal accelerometer. */ -class BuiltInAccelerometer : public Accelerometer, - public wpi::Sendable, +class BuiltInAccelerometer : public wpi::Sendable, public wpi::SendableHelper { public: + enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2, kRange_16G = 3 }; + /** * Constructor. * @@ -30,30 +29,28 @@ class BuiltInAccelerometer : public Accelerometer, BuiltInAccelerometer(BuiltInAccelerometer&&) = default; BuiltInAccelerometer& operator=(BuiltInAccelerometer&&) = default; - // Accelerometer interface /** * Set the measuring range of the accelerometer. * * @param range The maximum acceleration, positive or negative, that the - * accelerometer will measure. Not all accelerometers support all - * ranges. + * accelerometer will measure. Not all accelerometers support all ranges. */ - void SetRange(Range range) final; + void SetRange(Range range); /** * @return The acceleration of the roboRIO along the X axis in g-forces */ - double GetX() override; + double GetX(); /** * @return The acceleration of the roboRIO along the Y axis in g-forces */ - double GetY() override; + double GetY(); /** * @return The acceleration of the roboRIO along the Z axis in g-forces */ - double GetZ() override; + double GetZ(); void InitSendable(wpi::SendableBuilder& builder) override; }; diff --git a/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h b/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h index c95466a13fd..77f1d5bc3bd 100644 --- a/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h +++ b/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h @@ -8,8 +8,11 @@ namespace frc { /** * Interface for 3-axis accelerometers. + * + * @deprecated This interface is being removed with no replacement. */ -class Accelerometer { +class [[deprecated( + "This interface is being removed with no replacement.")]] Accelerometer { public: Accelerometer() = default; virtual ~Accelerometer() = default; diff --git a/wpilibc/src/main/native/include/frc/interfaces/Gyro.h b/wpilibc/src/main/native/include/frc/interfaces/Gyro.h index b74a3cf5d6f..51fea7dffcc 100644 --- a/wpilibc/src/main/native/include/frc/interfaces/Gyro.h +++ b/wpilibc/src/main/native/include/frc/interfaces/Gyro.h @@ -12,8 +12,11 @@ namespace frc { /** * Interface for yaw rate gyros. + * + * @deprecated This interface is being removed with no replacement. */ -class Gyro { +class [[deprecated( + "This interface is being removed with no replacement.")]] Gyro { public: Gyro() = default; virtual ~Gyro() = default; diff --git a/wpilibc/src/test/native/cpp/simulation/ADXL345SimTest.cpp b/wpilibc/src/test/native/cpp/simulation/ADXL345SimTest.cpp index 2bec0ed107d..832db943377 100644 --- a/wpilibc/src/test/native/cpp/simulation/ADXL345SimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/ADXL345SimTest.cpp @@ -15,7 +15,7 @@ namespace frc::sim { TEST(ADXL345SimTest, SetSpiAttributes) { HAL_Initialize(500, 0); - ADXL345_SPI accel(SPI::kMXP, Accelerometer::kRange_2G); + ADXL345_SPI accel(SPI::kMXP, ADXL345_SPI::kRange_2G); ADXL345Sim sim(accel); EXPECT_EQ(0, accel.GetX()); diff --git a/wpilibc/src/test/native/cpp/simulation/ADXL362SimTest.cpp b/wpilibc/src/test/native/cpp/simulation/ADXL362SimTest.cpp index 13f6c00e1da..aab0a129194 100644 --- a/wpilibc/src/test/native/cpp/simulation/ADXL362SimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/ADXL362SimTest.cpp @@ -14,7 +14,7 @@ namespace frc::sim { TEST(ADXL362SimTest, SetAttributes) { HAL_Initialize(500, 0); - ADXL362 accel(SPI::kMXP, Accelerometer::kRange_2G); + ADXL362 accel(SPI::kMXP, ADXL362::kRange_2G); ADXL362Sim sim(accel); EXPECT_EQ(0, accel.GetX()); diff --git a/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp index 3dc8582edad..91e72557b50 100644 --- a/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp @@ -99,7 +99,7 @@ TEST(AcclerometerSimTest, SetRange) { EnumCallback callback; - Accelerometer::Range range = Accelerometer::kRange_4G; + BuiltInAccelerometer::Range range = BuiltInAccelerometer::kRange_4G; auto cb = sim.RegisterRangeCallback(callback.GetCallback(), false); BuiltInAccelerometer accel(range); EXPECT_TRUE(callback.WasTriggered()); @@ -108,7 +108,7 @@ TEST(AcclerometerSimTest, SetRange) { // 2G callback.Reset(); - range = Accelerometer::kRange_2G; + range = BuiltInAccelerometer::kRange_2G; accel.SetRange(range); EXPECT_TRUE(callback.WasTriggered()); EXPECT_EQ(static_cast(range), sim.GetRange()); @@ -116,7 +116,7 @@ TEST(AcclerometerSimTest, SetRange) { // 4G callback.Reset(); - range = Accelerometer::kRange_4G; + range = BuiltInAccelerometer::kRange_4G; accel.SetRange(range); EXPECT_TRUE(callback.WasTriggered()); EXPECT_EQ(static_cast(range), sim.GetRange()); @@ -124,7 +124,7 @@ TEST(AcclerometerSimTest, SetRange) { // 8G callback.Reset(); - range = Accelerometer::kRange_8G; + range = BuiltInAccelerometer::kRange_8G; accel.SetRange(range); EXPECT_TRUE(callback.WasTriggered()); EXPECT_EQ(static_cast(range), sim.GetRange()); @@ -132,7 +132,8 @@ TEST(AcclerometerSimTest, SetRange) { // 16G - Not supported callback.Reset(); - EXPECT_THROW(accel.SetRange(Accelerometer::kRange_16G), std::runtime_error); + EXPECT_THROW(accel.SetRange(BuiltInAccelerometer::kRange_16G), + std::runtime_error); EXPECT_FALSE(callback.WasTriggered()); } } // namespace frc::sim diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java index fddc01d51f4..60ef6cc106a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java @@ -15,7 +15,6 @@ import edu.wpi.first.networktables.NTSendable; import edu.wpi.first.networktables.NTSendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.interfaces.Accelerometer; import java.nio.ByteBuffer; import java.nio.ByteOrder; @@ -27,7 +26,7 @@ * WPILib Known Issues page for details. */ @SuppressWarnings({"TypeName", "PMD.UnusedPrivateField"}) -public class ADXL345_I2C implements Accelerometer, NTSendable, AutoCloseable { +public class ADXL345_I2C implements NTSendable, AutoCloseable { private static final byte kAddress = 0x1D; private static final byte kPowerCtlRegister = 0x2D; private static final byte kDataFormatRegister = 0x31; @@ -44,6 +43,13 @@ public class ADXL345_I2C implements Accelerometer, NTSendable, AutoCloseable { private static final byte kDataFormat_FullRes = 0x08; private static final byte kDataFormat_Justify = 0x04; + public enum Range { + k2G, + k4G, + k8G, + k16G + } + public enum Axes { kX((byte) 0x00), kY((byte) 0x02), @@ -137,7 +143,12 @@ public void close() { } } - @Override + /** + * Set the measuring range of the accelerometer. + * + * @param range The maximum acceleration, positive or negative, that the accelerometer will + * measure. Not all accelerometers support all ranges. + */ public void setRange(Range range) { final byte value; @@ -166,17 +177,29 @@ public void setRange(Range range) { } } - @Override + /** + * Returns the acceleration along the X axis in g-forces. + * + * @return The acceleration along the X axis in g-forces. + */ public double getX() { return getAcceleration(Axes.kX); } - @Override + /** + * Returns the acceleration along the Y axis in g-forces. + * + * @return The acceleration along the Y axis in g-forces. + */ public double getY() { return getAcceleration(Axes.kY); } - @Override + /** + * Returns the acceleration along the Z axis in g-forces. + * + * @return The acceleration along the Z axis in g-forces. + */ public double getZ() { return getAcceleration(Axes.kZ); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java index 4806979983a..3c4fa9866d9 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java @@ -15,13 +15,12 @@ import edu.wpi.first.networktables.NTSendable; import edu.wpi.first.networktables.NTSendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.interfaces.Accelerometer; import java.nio.ByteBuffer; import java.nio.ByteOrder; /** ADXL345 SPI Accelerometer. */ @SuppressWarnings({"TypeName", "PMD.UnusedPrivateField"}) -public class ADXL345_SPI implements Accelerometer, NTSendable, AutoCloseable { +public class ADXL345_SPI implements NTSendable, AutoCloseable { private static final int kPowerCtlRegister = 0x2D; private static final int kDataFormatRegister = 0x31; private static final int kDataRegister = 0x32; @@ -41,6 +40,13 @@ public class ADXL345_SPI implements Accelerometer, NTSendable, AutoCloseable { private static final int kDataFormat_FullRes = 0x08; private static final int kDataFormat_Justify = 0x04; + public enum Range { + k2G, + k4G, + k8G, + k16G + } + public enum Axes { kX((byte) 0x00), kY((byte) 0x02), @@ -133,7 +139,12 @@ private void init(Range range) { HAL.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_SPI); } - @Override + /** + * Set the measuring range of the accelerometer. + * + * @param range The maximum acceleration, positive or negative, that the accelerometer will + * measure. Not all accelerometers support all ranges. + */ public void setRange(Range range) { final byte value; @@ -163,17 +174,29 @@ public void setRange(Range range) { } } - @Override + /** + * Returns the acceleration along the X axis in g-forces. + * + * @return The acceleration along the X axis in g-forces. + */ public double getX() { return getAcceleration(Axes.kX); } - @Override + /** + * Returns the acceleration along the Y axis in g-forces. + * + * @return The acceleration along the Y axis in g-forces. + */ public double getY() { return getAcceleration(Axes.kY); } - @Override + /** + * Returns the acceleration along the Z axis in g-forces. + * + * @return The acceleration along the Z axis in g-forces. + */ public double getZ() { return getAcceleration(Axes.kZ); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java index afd76d66566..373be81c969 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java @@ -14,7 +14,6 @@ import edu.wpi.first.networktables.NTSendable; import edu.wpi.first.networktables.NTSendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.interfaces.Accelerometer; import java.nio.ByteBuffer; import java.nio.ByteOrder; @@ -23,7 +22,7 @@ * *

This class allows access to an Analog Devices ADXL362 3-axis accelerometer. */ -public class ADXL362 implements Accelerometer, NTSendable, AutoCloseable { +public class ADXL362 implements NTSendable, AutoCloseable { private static final byte kRegWrite = 0x0A; private static final byte kRegRead = 0x0B; @@ -44,6 +43,13 @@ public class ADXL362 implements Accelerometer, NTSendable, AutoCloseable { private static final byte kPowerCtl_Measure = 0x02; + public enum Range { + k2G, + k4G, + k8G, + k16G + } + public enum Axes { kX((byte) 0x00), kY((byte) 0x02), @@ -153,7 +159,12 @@ public void close() { } } - @Override + /** + * Set the measuring range of the accelerometer. + * + * @param range The maximum acceleration, positive or negative, that the accelerometer will + * measure. Not all accelerometers support all ranges. + */ public void setRange(Range range) { if (m_spi == null) { return; @@ -188,17 +199,29 @@ public void setRange(Range range) { } } - @Override + /** + * Returns the acceleration along the X axis in g-forces. + * + * @return The acceleration along the X axis in g-forces. + */ public double getX() { return getAcceleration(Axes.kX); } - @Override + /** + * Returns the acceleration along the Y axis in g-forces. + * + * @return The acceleration along the Y axis in g-forces. + */ public double getY() { return getAcceleration(Axes.kY); } - @Override + /** + * Returns the acceleration along the Z axis in g-forces. + * + * @return The acceleration along the Z axis in g-forces. + */ public double getZ() { return getAcceleration(Axes.kZ); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java index 145e6e215a1..cbe34c83370 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java @@ -9,10 +9,10 @@ import edu.wpi.first.hal.SimBoolean; import edu.wpi.first.hal.SimDevice; import edu.wpi.first.hal.SimDouble; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.interfaces.Gyro; import java.nio.ByteBuffer; import java.nio.ByteOrder; @@ -27,7 +27,7 @@ * an ADXRS Gyro is supported. */ @SuppressWarnings({"TypeName", "PMD.UnusedPrivateField"}) -public class ADXRS450_Gyro implements Gyro, Sendable { +public class ADXRS450_Gyro implements Sendable, AutoCloseable { private static final double kSamplePeriod = 0.0005; private static final double kCalibrationSampleTime = 5.0; private static final double kDegreePerSecondPerLSB = 0.0125; @@ -105,7 +105,14 @@ public boolean isConnected() { return m_spi != null; } - @Override + /** + * Calibrate the gyro by running for a number of samples and computing the center value. Then use + * the center value as the Accumulator center value for subsequent measurements. + * + *

It's important to make sure that the robot is not moving while the centering calculations + * are in progress, this is typically done when the robot is first turned on while it's sitting at + * rest before the competition starts. + */ public void calibrate() { if (m_spi == null) { return; @@ -160,7 +167,12 @@ private int readRegister(int reg) { return (buf.getInt(0) >> 5) & 0xffff; } - @Override + /** + * Reset the gyro. + * + *

Resets the gyro to a heading of zero. This can be used if there is significant drift in the + * gyro, and it needs to be recalibrated after it has been running. + */ public void reset() { if (m_simAngle != null) { m_simAngle.reset(); @@ -184,7 +196,20 @@ public void close() { } } - @Override + /** + * Return the heading of the robot in degrees. + * + *

The angle is continuous, that is it will continue from 360 to 361 degrees. This allows + * algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from + * 360 to 0 on the second time around. + * + *

The angle is expected to increase as the gyro turns clockwise when looked at from the top. + * It needs to follow the NED axis convention. + * + *

This heading is based on integration of the returned rate from the gyro. + * + * @return the current heading of the robot in degrees. + */ public double getAngle() { if (m_simAngle != null) { return m_simAngle.get(); @@ -195,7 +220,16 @@ public double getAngle() { return m_spi.getAccumulatorIntegratedValue() * kDegreePerSecondPerLSB; } - @Override + /** + * Return the rate of rotation of the gyro. + * + *

The rate is based on the most recent reading of the gyro analog value + * + *

The rate is expected to be positive as the gyro turns clockwise when looked at from the top. + * It needs to follow the NED axis convention. + * + * @return the current rate in degrees per second + */ public double getRate() { if (m_simRate != null) { return m_simRate.get(); @@ -206,6 +240,24 @@ public double getRate() { return m_spi.getAccumulatorLastValue() * kDegreePerSecondPerLSB; } + /** + * Return the heading of the robot as a {@link edu.wpi.first.math.geometry.Rotation2d}. + * + *

The angle is continuous, that is it will continue from 360 to 361 degrees. This allows + * algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from + * 360 to 0 on the second time around. + * + *

The angle is expected to increase as the gyro turns counterclockwise when looked at from the + * top. It needs to follow the NWU axis convention. + * + *

This heading is based on integration of the returned rate from the gyro. + * + * @return the current heading of the robot as a {@link edu.wpi.first.math.geometry.Rotation2d}. + */ + public Rotation2d getRotation2d() { + return Rotation2d.fromDegrees(-getAngle()); + } + @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Gyro"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java index 06c7e460785..f5be4ad2d9f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java @@ -9,10 +9,10 @@ import edu.wpi.first.hal.AnalogGyroJNI; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.interfaces.Gyro; /** * Use a rate gyro to return the robots heading relative to a starting position. The Gyro class @@ -23,7 +23,7 @@ * *

This class is for gyro sensors that connect to an analog input. */ -public class AnalogGyro implements Gyro, Sendable { +public class AnalogGyro implements Sendable, AutoCloseable { private static final double kDefaultVoltsPerDegreePerSecond = 0.007; protected AnalogInput m_analog; private boolean m_channelAllocated; @@ -42,11 +42,36 @@ public void initGyro() { SendableRegistry.addLW(this, "AnalogGyro", m_analog.getChannel()); } - @Override + /** + * Calibrate the gyro by running for a number of samples and computing the center value. Then use + * the center value as the Accumulator center value for subsequent measurements. + * + *

It's important to make sure that the robot is not moving while the centering calculations + * are in progress, this is typically done when the robot is first turned on while it's sitting at + * rest before the competition starts. + */ public void calibrate() { AnalogGyroJNI.calibrateAnalogGyro(m_gyroHandle); } + /** + * Return the heading of the robot as a {@link edu.wpi.first.math.geometry.Rotation2d}. + * + *

The angle is continuous, that is it will continue from 360 to 361 degrees. This allows + * algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from + * 360 to 0 on the second time around. + * + *

The angle is expected to increase as the gyro turns counterclockwise when looked at from the + * top. It needs to follow the NWU axis convention. + * + *

This heading is based on integration of the returned rate from the gyro. + * + * @return the current heading of the robot as a {@link edu.wpi.first.math.geometry.Rotation2d}. + */ + public Rotation2d getRotation2d() { + return Rotation2d.fromDegrees(-getAngle()); + } + /** * Gyro constructor using the channel number. * @@ -109,7 +134,12 @@ public AnalogGyro(AnalogInput channel, int center, double offset) { reset(); } - @Override + /** + * Reset the gyro. + * + *

Resets the gyro to a heading of zero. This can be used if there is significant drift in the + * gyro, and it needs to be recalibrated after it has been running. + */ public void reset() { AnalogGyroJNI.resetAnalogGyro(m_gyroHandle); } @@ -125,7 +155,20 @@ public void close() { AnalogGyroJNI.freeAnalogGyro(m_gyroHandle); } - @Override + /** + * Return the heading of the robot in degrees. + * + *

The angle is continuous, that is it will continue from 360 to 361 degrees. This allows + * algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from + * 360 to 0 on the second time around. + * + *

The angle is expected to increase as the gyro turns clockwise when looked at from the top. + * It needs to follow the NED axis convention. + * + *

This heading is based on integration of the returned rate from the gyro. + * + * @return the current heading of the robot in degrees. + */ public double getAngle() { if (m_analog == null) { return 0.0; @@ -134,7 +177,16 @@ public double getAngle() { } } - @Override + /** + * Return the rate of rotation of the gyro. + * + *

The rate is based on the most recent reading of the gyro analog value + * + *

The rate is expected to be positive as the gyro turns clockwise when looked at from the top. + * It needs to follow the NED axis convention. + * + * @return the current rate in degrees per second + */ public double getRate() { if (m_analog == null) { return 0.0; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java index 76c282a5374..15275db20cc 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java @@ -10,14 +10,20 @@ import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.interfaces.Accelerometer; /** * Built-in accelerometer. * *

This class allows access to the roboRIO's internal accelerometer. */ -public class BuiltInAccelerometer implements Accelerometer, Sendable, AutoCloseable { +public class BuiltInAccelerometer implements Sendable, AutoCloseable { + public enum Range { + k2G, + k4G, + k8G, + k16G + } + /** * Constructor. * @@ -39,7 +45,12 @@ public void close() { SendableRegistry.remove(this); } - @Override + /** + * Set the measuring range of the accelerometer. + * + * @param range The maximum acceleration, positive or negative, that the accelerometer will + * measure. Not all accelerometers support all ranges. + */ public void setRange(Range range) { AccelerometerJNI.setAccelerometerActive(false); @@ -66,7 +77,6 @@ public void setRange(Range range) { * * @return The acceleration of the roboRIO along the X axis in g-forces */ - @Override public double getX() { return AccelerometerJNI.getAccelerometerX(); } @@ -76,7 +86,6 @@ public double getX() { * * @return The acceleration of the roboRIO along the Y axis in g-forces */ - @Override public double getY() { return AccelerometerJNI.getAccelerometerY(); } @@ -86,7 +95,6 @@ public double getY() { * * @return The acceleration of the roboRIO along the Z axis in g-forces */ - @Override public double getZ() { return AccelerometerJNI.getAccelerometerZ(); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java index 3cfd27d2272..d33b7ae4c13 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java @@ -4,7 +4,12 @@ package edu.wpi.first.wpilibj.interfaces; -/** Interface for 3-axis accelerometers. */ +/** + * Interface for 3-axis accelerometers. + * + * @deprecated This interface is being removed with no replacement. + */ +@Deprecated(since = "2024", forRemoval = true) public interface Accelerometer { enum Range { k2G, diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java index 660aad82e05..dad85ca3427 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java @@ -6,7 +6,12 @@ import edu.wpi.first.math.geometry.Rotation2d; -/** Interface for yaw rate gyros. */ +/** + * Interface for yaw rate gyros. + * + * @deprecated This interface is being removed with no replacement. + */ +@Deprecated(since = "2024", forRemoval = true) public interface Gyro extends AutoCloseable { /** * Calibrate the gyro. It's important to make sure that the robot is not moving while the diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java index 9c96a2fc1be..c034a4a433a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java @@ -4,8 +4,6 @@ package edu.wpi.first.wpilibj.shuffleboard; -import edu.wpi.first.wpilibj.interfaces.Accelerometer.Range; - /** * The types of the widgets bundled with Shuffleboard. * @@ -362,7 +360,6 @@ public enum BuiltInWidgets implements WidgetType { * * * - * * * * diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL345SimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL345SimTest.java index 559526132ef..2917ec27e83 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL345SimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL345SimTest.java @@ -11,14 +11,13 @@ import edu.wpi.first.wpilibj.ADXL345_SPI; import edu.wpi.first.wpilibj.I2C; import edu.wpi.first.wpilibj.SPI; -import edu.wpi.first.wpilibj.interfaces.Accelerometer; import org.junit.jupiter.params.ParameterizedTest; import org.junit.jupiter.params.provider.EnumSource; class ADXL345SimTest { @ParameterizedTest - @EnumSource(Accelerometer.Range.class) - void testInitI2C(Accelerometer.Range range) { + @EnumSource(ADXL345_I2C.Range.class) + void testInitI2C(ADXL345_I2C.Range range) { HAL.initialize(500, 0); try (ADXL345_I2C accel = new ADXL345_I2C(I2C.Port.kMXP, range)) { @@ -40,8 +39,8 @@ void testInitI2C(Accelerometer.Range range) { } @ParameterizedTest - @EnumSource(Accelerometer.Range.class) - void testInitSPi(Accelerometer.Range range) { + @EnumSource(ADXL345_SPI.Range.class) + void testInitSPi(ADXL345_SPI.Range range) { HAL.initialize(500, 0); try (ADXL345_SPI accel = new ADXL345_SPI(SPI.Port.kMXP, range)) { diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL362SimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL362SimTest.java index 7ab6b6be172..0f524b918a5 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL362SimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL362SimTest.java @@ -9,14 +9,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.ADXL362; import edu.wpi.first.wpilibj.SPI; -import edu.wpi.first.wpilibj.interfaces.Accelerometer; import org.junit.jupiter.params.ParameterizedTest; import org.junit.jupiter.params.provider.EnumSource; class ADXL362SimTest { @ParameterizedTest - @EnumSource(Accelerometer.Range.class) - void testAccel(Accelerometer.Range range) { + @EnumSource(ADXL362.Range.class) + void testAccel(ADXL362.Range range) { HAL.initialize(500, 0); try (ADXL362 accel = new ADXL362(SPI.Port.kMXP, range)) { diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AccelerometerSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AccelerometerSimTest.java index 998b66aa114..8be3af45870 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AccelerometerSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AccelerometerSimTest.java @@ -11,7 +11,6 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.BuiltInAccelerometer; -import edu.wpi.first.wpilibj.interfaces.Accelerometer; import edu.wpi.first.wpilibj.simulation.testutils.BooleanCallback; import edu.wpi.first.wpilibj.simulation.testutils.DoubleCallback; import edu.wpi.first.wpilibj.simulation.testutils.EnumCallback; @@ -102,7 +101,7 @@ void testRange() { EnumCallback callback = new EnumCallback(); - Accelerometer.Range range = Accelerometer.Range.k4G; + BuiltInAccelerometer.Range range = BuiltInAccelerometer.Range.k4G; try (CallbackStore cb = sim.registerRangeCallback(callback, false); BuiltInAccelerometer accel = new BuiltInAccelerometer(range)) { assertTrue(callback.wasTriggered()); @@ -111,7 +110,7 @@ void testRange() { // 2G callback.reset(); - range = Accelerometer.Range.k2G; + range = BuiltInAccelerometer.Range.k2G; accel.setRange(range); assertTrue(callback.wasTriggered()); assertEquals(range.ordinal(), sim.getRange()); @@ -119,7 +118,7 @@ void testRange() { // 4G callback.reset(); - range = Accelerometer.Range.k4G; + range = BuiltInAccelerometer.Range.k4G; accel.setRange(range); assertTrue(callback.wasTriggered()); assertEquals(range.ordinal(), sim.getRange()); @@ -127,7 +126,7 @@ void testRange() { // 8G callback.reset(); - range = Accelerometer.Range.k8G; + range = BuiltInAccelerometer.Range.k8G; accel.setRange(range); assertTrue(callback.wasTriggered()); assertEquals(range.ordinal(), sim.getRange()); @@ -135,7 +134,8 @@ void testRange() { // 16G - Not supported callback.reset(); - assertThrows(IllegalArgumentException.class, () -> accel.setRange(Accelerometer.Range.k16G)); + assertThrows( + IllegalArgumentException.class, () -> accel.setRange(BuiltInAccelerometer.Range.k16G)); assertFalse(callback.wasTriggered()); } } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java index a2fdf6ef9fe..a4064030a35 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java @@ -44,7 +44,7 @@ public class DriveSubsystem extends SubsystemBase { 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() { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java index 83b9c9fa3fc..9168d174574 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java @@ -55,7 +55,7 @@ public class DriveSubsystem extends SubsystemBase { 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 = diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java index 90625ce59ab..5829bd2fcf5 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java @@ -47,7 +47,7 @@ public class DriveSubsystem extends SubsystemBase { 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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java index 326efee93f6..f331dc0d7ca 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java @@ -54,7 +54,7 @@ public class DriveSubsystem extends SubsystemBase { 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 =
NameTypeDefault ValueNotes
Range{@link Range}k16GThe accelerometer range
Show valueBooleantrueShow or hide the acceleration values
PrecisionNumber2