Skip to content

Commit

Permalink
[wpilib] Deprecate Accelerometer and Gyro interfaces
Browse files Browse the repository at this point in the history
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.
  • Loading branch information
calcmogul committed Jul 14, 2023
1 parent 7ac9329 commit e8750b0
Show file tree
Hide file tree
Showing 29 changed files with 422 additions and 120 deletions.
4 changes: 4 additions & 0 deletions wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down
4 changes: 4 additions & 0 deletions wpilibc/src/main/native/cpp/AnalogGyro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<AnalogInput> AnalogGyro::GetAnalogInput() const {
return m_analog;
}
Expand Down
39 changes: 31 additions & 8 deletions wpilibc/src/main/native/include/frc/ADXL345_I2C.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
#include <wpi/sendable/SendableHelper.h>

#include "frc/I2C.h"
#include "frc/interfaces/Accelerometer.h"

namespace frc {

Expand All @@ -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</a> page for details.
*/
class ADXL345_I2C : public Accelerometer,
public nt::NTSendable,
class ADXL345_I2C : public nt::NTSendable,
public wpi::SendableHelper<ADXL345_I2C> {
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 {
Expand All @@ -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.
Expand Down
39 changes: 31 additions & 8 deletions wpilibc/src/main/native/include/frc/ADXL345_SPI.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
#include <wpi/sendable/SendableHelper.h>

#include "frc/SPI.h"
#include "frc/interfaces/Accelerometer.h"

namespace frc {

Expand All @@ -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<ADXL345_SPI> {
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 {
Expand All @@ -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.
Expand Down
40 changes: 31 additions & 9 deletions wpilibc/src/main/native/include/frc/ADXL362.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
#include <wpi/sendable/SendableHelper.h>

#include "frc/SPI.h"
#include "frc/interfaces/Accelerometer.h"

namespace frc {

Expand All @@ -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<ADXL362> {
class ADXL362 : public nt::NTSendable, public wpi::SendableHelper<ADXL362> {
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;
Expand Down Expand Up @@ -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.
Expand Down
30 changes: 21 additions & 9 deletions wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <wpi/sendable/SendableHelper.h>

#include "frc/SPI.h"
#include "frc/interfaces/Gyro.h"
#include "frc/geometry/Rotation2d.h"

namespace frc {

Expand All @@ -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<ADXRS450_Gyro> {
public:
/**
Expand Down Expand Up @@ -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
Expand All @@ -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.
Expand All @@ -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.
Expand All @@ -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.
Expand Down
38 changes: 31 additions & 7 deletions wpilibc/src/main/native/include/frc/AnalogGyro.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include <wpi/sendable/Sendable.h>
#include <wpi/sendable/SendableHelper.h>

#include "frc/interfaces/Gyro.h"
#include "frc/geometry/Rotation2d.h"

namespace frc {

Expand All @@ -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<AnalogGyro> {
public:
static constexpr int kOversampleBits = 10;
Expand Down Expand Up @@ -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
Expand All @@ -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,
Expand Down Expand Up @@ -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.
Expand All @@ -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.
Expand Down
Loading

0 comments on commit e8750b0

Please sign in to comment.