"

2013 FRC Java API

"

edu.wpi.first.wpilibj
Class Gyro

java.lang.Object
  extended by edu.wpi.first.wpilibj.SensorBase
      extended by edu.wpi.first.wpilibj.Gyro
All Implemented Interfaces:
LiveWindowSendable, IDevice, ISensor, PIDSource, Sendable

public class Gyro
extends SensorBase
implements PIDSource, ISensor, LiveWindowSendable

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.


Nested Class Summary
 
Nested classes/interfaces inherited from interface edu.wpi.first.wpilibj.PIDSource
PIDSource.PIDSourceParameter
 
Field Summary
 
Fields inherited from class edu.wpi.first.wpilibj.SensorBase
kAnalogChannels, kAnalogModules, kDigitalChannels, kPwmChannels, kRelayChannels, kSolenoidChannels, kSolenoidModules, kSystemClockTicksPerMicrosecond
 
Constructor Summary
Gyro(AnalogChannel channel)
          Gyro constructor with a precreated analog channel object.
Gyro(int channel)
          Gyro constructor with only a channel.
Gyro(int slot, int channel)
          Gyro constructor given a slot and a channel.
 
Method Summary
 void free()
          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.
 double getRate()
          Return the rate of rotation of the gyro The rate is based on the most recent reading of the gyro analog value
 String getSmartDashboardType()
           
 ITable getTable()
          
 void initTable(ITable subtable)
          Initializes a table for this sendable object.
 double pidGet()
          Get the angle of the gyro for use with PIDControllers
 void reset()
          Reset the gyro.
 void setPIDSourceParameter(PIDSource.PIDSourceParameter pidSource)
          Set which parameter of the encoder you are using as a process control variable.
 void setSensitivity(double voltsPerDegreePerSecond)
          Set the gyro type based on the sensitivity.
 void startLiveWindowMode()
          Start having this sendable object automatically respond to value changes reflect the value on the table.
 void stopLiveWindowMode()
          Stop having this sendable object automatically respond to value changes.
 void updateTable()
          Update the table for this sendable object with the latest values.
 
Methods inherited from class edu.wpi.first.wpilibj.SensorBase
checkAnalogChannel, checkAnalogModule, checkDigitalChannel, checkDigitalModule, checkPWMChannel, checkPWMModule, checkRelayChannel, checkRelayModule, checkSolenoidChannel, checkSolenoidModule, getDefaultAnalogModule, getDefaultDigitalModule, getDefaultSolenoidModule, setDefaultAnalogModule, setDefaultDigitalModule, setDefaultSolenoidModule
 
Methods inherited from class java.lang.Object
equals, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Constructor Detail

Gyro

public Gyro(int slot,
            int channel)
Gyro constructor given a slot and a channel. .

Parameters:
slot - The cRIO slot for the analog module the gyro is connected to.
channel - The analog channel the gyro is connected to.

Gyro

public Gyro(int channel)
Gyro constructor with only a channel. Use the default analog module slot.

Parameters:
channel - The analog channel the gyro is connected to.

Gyro

public Gyro(AnalogChannel channel)
Gyro constructor with a precreated analog channel object. Use this constructor when the analog channel needs to be shared. There is no reference counting when an AnalogChannel is passed to the gyro.

Parameters:
channel - The AnalogChannel object that the gyro is connected to.
Method Detail

reset

public void reset()
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.


free

public void free()
Delete (free) the accumulator and the analog components used for the gyro.

Overrides:
free in class SensorBase

getAngle

public double getAngle()
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 can go beyond 360 degrees. This make algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past 0 on the second time around.

Returns:
the current heading of the robot in degrees. This heading is based on integration of the returned rate from the gyro.

getRate

public double getRate()
Return the rate of rotation of the gyro The rate is based on the most recent reading of the gyro analog value

Returns:
the current rate in degrees per second

setSensitivity

public void setSensitivity(double voltsPerDegreePerSecond)
Set the gyro type based on the 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.

Parameters:
voltsPerDegreePerSecond - The type of gyro specified as the voltage that represents one degree/second.

setPIDSourceParameter

public void setPIDSourceParameter(PIDSource.PIDSourceParameter pidSource)
Set which parameter of the encoder you are using as a process control variable. The Gyro class supports the rate and angle parameters

Parameters:
pidSource - An enum to select the parameter.

pidGet

public double pidGet()
Get the angle of the gyro for use with PIDControllers

Specified by:
pidGet in interface PIDSource
Returns:
the current angle according to the gyro

getSmartDashboardType

public String getSmartDashboardType()
Specified by:
getSmartDashboardType in interface Sendable
Returns:
the string representation of the named data type that will be used by the smart dashboard for this sendable

initTable

public void initTable(ITable subtable)
Initializes a table for this sendable object.

Specified by:
initTable in interface Sendable
Parameters:
subtable - The table to put the values in.

getTable

public ITable getTable()

Specified by:
getTable in interface Sendable
Returns:
the table that is currently associated with the sendable

updateTable

public void updateTable()
Update the table for this sendable object with the latest values.

Specified by:
updateTable in interface LiveWindowSendable

startLiveWindowMode

public void startLiveWindowMode()
Start having this sendable object automatically respond to value changes reflect the value on the table.

Specified by:
startLiveWindowMode in interface LiveWindowSendable

stopLiveWindowMode

public void stopLiveWindowMode()
Stop having this sendable object automatically respond to value changes.

Specified by:
stopLiveWindowMode in interface LiveWindowSendable

"

2013 FRC Java API

"

"
For updated information see the Java FRC site
"