67 explicit AnalogGyro(std::shared_ptr<AnalogInput> channel) {}
Use a rate gyro to return the robots heading relative to a starting position.
Definition AnalogGyro.h:33
void SetDeadband(double volts)
Set the size of the neutral zone.
Definition AnalogGyro.h:161
AnalogGyro(AnalogGyro &&rhs)=default
void Calibrate()
Calibrate the gyro by running for a number of samples and computing the center value.
Definition AnalogGyro.h:189
virtual double GetOffset() const
Return the gyro offset value.
Definition AnalogGyro.h:139
AnalogGyro(AnalogInput *channel)
Gyro constructor with a precreated AnalogInput object.
Definition AnalogGyro.h:55
~AnalogGyro() override=default
AnalogGyro(std::shared_ptr< AnalogInput > channel, int center, double offset)
Gyro constructor with a precreated AnalogInput object and calibrated parameters.
Definition AnalogGyro.h:95
AnalogGyro(std::shared_ptr< AnalogInput > channel)
Gyro constructor with a precreated AnalogInput object.
Definition AnalogGyro.h:67
AnalogGyro(int channel)
Gyro constructor using the Analog Input channel number.
Definition AnalogGyro.h:41
void Reset()
Reset the gyro.
Definition AnalogGyro.h:170
double GetAngle() const
Return the actual angle in degrees that the robot is currently facing.
Definition AnalogGyro.h:114
std::shared_ptr< AnalogInput > GetAnalogInput() const
Gets the analog input for the gyro.
Definition AnalogGyro.h:211
AnalogGyro(int channel, int center, double offset)
Gyro constructor using the Analog Input channel number with parameters for presetting the center and ...
Definition AnalogGyro.h:79
virtual int GetCenter() const
Return the gyro center value.
Definition AnalogGyro.h:131
void InitGyro()
Initialize the gyro.
Definition AnalogGyro.h:177
void SetSensitivity(double voltsPerDegreePerSecond)
Set the gyro sensitivity.
Definition AnalogGyro.h:150
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
Definition AnalogGyro.h:213
Rotation2d GetRotation2d() const
Return the heading of the robot as a Rotation2d.
Definition AnalogGyro.h:204
double GetRate() const
Return the rate of rotation of the gyro.
Definition AnalogGyro.h:123
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:26
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
Definition SystemServer.h:9