122 bool m_connected{
false};
129 uint16_t ReadRegister(
int reg);
Use a rate gyro to return the robots heading relative to a starting position.
Definition ADXRS450_Gyro.h:32
int GetPort() const
Get the SPI port number.
void Reset()
Reset the gyro.
double GetAngle() const
Return the actual angle in degrees that the robot is currently facing.
ADXRS450_Gyro & operator=(ADXRS450_Gyro &&)=default
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
ADXRS450_Gyro(SPI::Port port)
Gyro constructor on the specified SPI port.
~ADXRS450_Gyro() override=default
Rotation2d GetRotation2d() const
Return the heading of the robot as a Rotation2d.
double GetRate() const
Return the rate of rotation of the gyro.
ADXRS450_Gyro()
Gyro constructor on onboard CS0.
void Calibrate()
Calibrate the gyro by running for a number of samples and computing the center value.
ADXRS450_Gyro(ADXRS450_Gyro &&)=default
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
SPI bus interface class.
Definition SPI.h:27
Port
SPI port.
Definition SPI.h:32
C++ wrapper around a HAL simulator boolean value handle.
Definition SimDevice.h:611
A move-only C++ wrapper around a HAL simulator device handle.
Definition SimDevice.h:645
C++ wrapper around a HAL simulator double value handle.
Definition SimDevice.h:536
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition SendableHelper.h:21
Interface for Sendable objects.
Definition Sendable.h:16