110 bool m_connected{
false};
Use a rate gyro to return the robots heading relative to a starting position.
Definition: ADXRS450_Gyro.h:33
int GetPort() const
Get the SPI port number.
double GetRate() const override
Return the rate of rotation of the gyro.
ADXRS450_Gyro & operator=(ADXRS450_Gyro &&)=default
void Calibrate() final
Initialize the gyro.
void Reset() override
Reset the gyro.
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
double GetAngle() const override
Return the actual angle in degrees that the robot is currently facing.
ADXRS450_Gyro()
Gyro constructor on onboard CS0.
ADXRS450_Gyro(ADXRS450_Gyro &&)=default
Interface for yaw rate gyros.
Definition: Gyro.h:16
SPI bus interface class.
Definition: SPI.h:26
C++ wrapper around a HAL simulator boolean value handle.
Definition: SimDevice.h:610
A move-only C++ wrapper around a HAL simulator device handle.
Definition: SimDevice.h:644
C++ wrapper around a HAL simulator double value handle.
Definition: SimDevice.h:535
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
::uint16_t uint16_t
Definition: Meta.h:54
Definition: AprilTagPoseEstimator.h:15
Definition: AprilTagFieldLayout.h:18