73 explicit AnalogGyro(std::shared_ptr<AnalogInput> channel);
101 AnalogGyro(std::shared_ptr<AnalogInput> channel,
int center,
double offset);
222 std::shared_ptr<AnalogInput> m_analog;
Use a rate gyro to return the robots heading relative to a starting position.
Definition: AnalogGyro.h:33
static constexpr double kCalibrationSampleTime
Definition: AnalogGyro.h:38
void SetDeadband(double volts)
Set the size of the neutral zone.
AnalogGyro(AnalogGyro &&rhs)=default
void Calibrate()
Calibrate the gyro by running for a number of samples and computing the center value.
virtual double GetOffset() const
Return the gyro offset value.
static constexpr int kAverageBits
Definition: AnalogGyro.h:36
AnalogGyro(AnalogInput *channel)
Gyro constructor with a precreated AnalogInput object.
AnalogGyro(std::shared_ptr< AnalogInput > channel, int center, double offset)
Gyro constructor with a precreated AnalogInput object and calibrated parameters.
AnalogGyro(std::shared_ptr< AnalogInput > channel)
Gyro constructor with a precreated AnalogInput object.
AnalogGyro(int channel)
Gyro constructor using the Analog Input channel number.
static constexpr int kOversampleBits
Definition: AnalogGyro.h:35
void Reset()
Reset the gyro.
double GetAngle() const
Return the actual angle in degrees that the robot is currently facing.
std::shared_ptr< AnalogInput > GetAnalogInput() const
Gets the analog input for the gyro.
static constexpr double kDefaultVoltsPerDegreePerSecond
Definition: AnalogGyro.h:39
AnalogGyro(int channel, int center, double offset)
Gyro constructor using the Analog Input channel number with parameters for presetting the center and ...
virtual int GetCenter() const
Return the gyro center value.
void InitGyro()
Initialize the gyro.
void SetSensitivity(double voltsPerDegreePerSecond)
Set the gyro sensitivity.
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
static constexpr double kSamplesPerSecond
Definition: AnalogGyro.h:37
Rotation2d GetRotation2d() const
Return the heading of the robot as a Rotation2d.
double GetRate() const
Return the rate of rotation of the gyro.
AnalogGyro & operator=(AnalogGyro &&rhs)=default
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
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:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: AprilTagPoseEstimator.h:15