Class AnalogGyro
- java.lang.Object
-
- edu.wpi.first.wpilibj.SendableBase
-
- edu.wpi.first.wpilibj.GyroBase
-
- edu.wpi.first.wpilibj.AnalogGyro
-
- All Implemented Interfaces:
Gyro
,PIDSource
,Sendable
,AutoCloseable
public class AnalogGyro extends GyroBase implements Gyro, PIDSource, 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
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
calibrate()
Calibrate the gyro by running for a number of samples and computing the center value.void
close()
Delete (free) the accumulator and the analog components used for the gyro.double
getAngle()
Return the actual angle in degrees that the robot is currently facing.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
reset()
Reset the gyro.void
setSensitivity(double voltsPerDegreePerSecond)
Set the gyro sensitivity.-
Methods inherited from class edu.wpi.first.wpilibj.GyroBase
getPIDSourceType, initSendable, pidGet, setPIDSourceType
-
Methods inherited from class edu.wpi.first.wpilibj.SendableBase
addChild, free, getName, getSubsystem, setName, setName, setName, setSubsystem
-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface edu.wpi.first.wpilibj.PIDSource
getPIDSourceType, pidGet, setPIDSourceType
-
Methods inherited from interface edu.wpi.first.wpilibj.Sendable
getName, getSubsystem, initSendable, setName, setName, setSubsystem
-
-
-
-
Field Detail
-
m_analog
protected AnalogInput m_analog
-
-
Constructor Detail
-
AnalogGyro
public AnalogGyro(int channel)
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
public AnalogGyro(AnalogInput channel)
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
public AnalogGyro(int channel, int center, double offset)
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
public 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. 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 Detail
-
initGyro
public void initGyro()
Initialize the gyro. Calibration is handled by calibrate().
-
calibrate
public void calibrate()
Description copied from interface:Gyro
Calibrate the gyro by running for a number of samples and computing the center value. Then use the center value as the Accumulator center value for subsequent measurements. It's important to make sure that the robot is not moving while the centering calculations are in progress, this is typically done when the robot is first turned on while it's sitting at rest before the competition starts.
-
reset
public void 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
public void close()
Delete (free) the accumulator and the analog components used for the gyro.- Specified by:
close
in interfaceAutoCloseable
- Overrides:
close
in classSendableBase
-
getAngle
public double getAngle()
Description copied from interface:Gyro
Return the actual angle in degrees that the robot is currently facing.The angle is based on the current accumulator value corrected by the oversampling rate, the gyro type and the A/D calibration values. 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 NED axis conventions in order to work properly with dependent control loops.
This heading is based on integration of the returned rate from the gyro.
-
getRate
public double 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 NED axis conventions in order to work properly with dependent control loops.
-
getOffset
public double getOffset()
Return the gyro offset value set during calibration to use as a future preset.- Returns:
- the current offset value
-
getCenter
public int getCenter()
Return the gyro center value set during calibration to use as a future preset.- Returns:
- the current center value
-
setSensitivity
public void setSensitivity(double voltsPerDegreePerSecond)
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.
-
-