Package edu.wpi.first.wpilibj
Class AnalogGyro
java.lang.Object
edu.wpi.first.wpilibj.AnalogGyro
- All Implemented Interfaces:
Sendable
,Gyro
,AutoCloseable
- Direct Known Subclasses:
PIDAnalogGyro
public class AnalogGyro extends Object implements Gyro, Sendable
Use a rate gyro to return the robots heading relative to a starting position. The Gyro class
tracks the robots heading based on the starting position. As the robot rotates the new heading is
computed by integrating the rate of rotation returned by the sensor. When the class is
instantiated, it does a short calibration routine where it samples the gyro while at rest to
determine the default offset. This is subtracted from each sample to determine the heading.
This class is for gyro sensors that connect to an analog input.
-
Field Summary
Fields Modifier and Type Field Description protected AnalogInput
m_analog
-
Constructor Summary
Constructors Constructor Description AnalogGyro(int channel)
Gyro constructor using the channel number.AnalogGyro(int channel, int center, double offset)
Gyro constructor using the channel number along with parameters for presetting the center and offset values.AnalogGyro(AnalogInput channel)
Gyro constructor with a precreated analog channel object.AnalogGyro(AnalogInput channel, int center, double offset)
Gyro constructor with a precreated analog channel object along with parameters for presetting the center and offset values. -
Method Summary
Modifier and Type Method Description void
calibrate()
Calibrate the gyro.void
close()
Delete (free) the accumulator and the analog components used for the gyro.AnalogInput
getAnalogInput()
Gets the analog input for the gyro.double
getAngle()
Return the heading of the robot in degrees.int
getCenter()
Return the gyro center value set during calibration to use as a future preset.double
getOffset()
Return the gyro offset value set during calibration to use as a future preset.double
getRate()
Return the rate of rotation of the gyro.void
initGyro()
Initialize the gyro.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.void
reset()
Reset the gyro.void
setDeadband(double volts)
Set the size of the neutral zone.void
setSensitivity(double voltsPerDegreePerSecond)
Set the gyro sensitivity.
-
Field Details
-
Constructor Details
-
AnalogGyro
Gyro constructor using the channel number.- Parameters:
channel
- The analog channel the gyro is connected to. Gyros can only be used on on-board channels 0-1.
-
AnalogGyro
Gyro constructor with a precreated analog channel object. Use this constructor when the analog channel needs to be shared.- Parameters:
channel
- The AnalogInput object that the gyro is connected to. Gyros can only be used on on-board channels 0-1.
-
AnalogGyro
Gyro constructor using the channel number along with parameters for presetting the center and offset values. Bypasses calibration.- Parameters:
channel
- The analog channel the gyro is connected to. Gyros can only be used on on-board channels 0-1.center
- Preset uncalibrated value to use as the accumulator center value.offset
- Preset uncalibrated value to use as the gyro offset.
-
AnalogGyro
Gyro constructor with a precreated analog channel object along with parameters for presetting the center and offset values. Bypasses calibration.- Parameters:
channel
- The analog channel the gyro is connected to. Gyros can only be used on on-board channels 0-1.center
- Preset uncalibrated value to use as the accumulator center value.offset
- Preset uncalibrated value to use as the gyro offset.
-
-
Method Details
-
initGyro
Initialize the gyro. Calibration is handled by calibrate(). -
calibrate
Description copied from interface:Gyro
Calibrate the gyro. It's important to make sure that the robot is not moving while the calibration is in progress, this is typically done when the robot is first turned on while it's sitting at rest before the match starts. -
reset
Description copied from interface:Gyro
Reset the gyro. Resets the gyro to a heading of zero. This can be used if there is significant drift in the gyro and it needs to be recalibrated after it has been running. -
close
Delete (free) the accumulator and the analog components used for the gyro.- Specified by:
close
in interfaceAutoCloseable
-
getAngle
Description copied from interface:Gyro
Return the heading of the robot in degrees.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 clockwise when looked at from the top. It needs to follow the NED axis convention.
This heading is based on integration of the returned rate from the gyro.
-
getRate
Description copied from interface:Gyro
Return the rate of rotation of the gyro.The rate is based on the most recent reading of the gyro analog value
The rate is expected to be positive as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.
-
getOffset
Return the gyro offset value set during calibration to use as a future preset.- Returns:
- the current offset value
-
getCenter
Return the gyro center value set during calibration to use as a future preset.- Returns:
- the current center value
-
setSensitivity
Set the gyro sensitivity. This takes the number of volts/degree/second sensitivity of the gyro and uses it in subsequent calculations to allow the code to work with multiple gyros. This value is typically found in the gyro datasheet.- Parameters:
voltsPerDegreePerSecond
- The sensitivity in Volts/degree/second.
-
setDeadband
Set the size of the neutral zone. Any voltage from the gyro less than this amount from the center is considered stationary. Setting a deadband will decrease the amount of drift when the gyro isn't rotating, but will make it less accurate.- Parameters:
volts
- The size of the deadband in volts
-
getAnalogInput
Gets the analog input for the gyro.- Returns:
- AnalogInput
-
initSendable
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-