wh1ter0se/PowerUp-2018

View on GitHub
wpilib18/java/current/javadoc/edu/wpi/first/wpilibj/ADXRS450_Gyro.html

Summary

Maintainability
Test Coverage
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN" "http://www.w3.org/TR/html4/loose.dtd">
<!-- NewPage -->
<html lang="en">
<head>
<!-- Generated by javadoc (1.8.0_144) on Sat Oct 28 05:22:52 EDT 2017 -->
<title>ADXRS450_Gyro (Documentation - Release API)</title>
<meta name="date" content="2017-10-28">
<link rel="stylesheet" type="text/css" href="../../../../stylesheet.css" title="Style">
<script type="text/javascript" src="../../../../script.js"></script>
</head>
<body>
<script type="text/javascript"><!--
    try {
        if (location.href.indexOf('is-external=true') == -1) {
            parent.document.title="ADXRS450_Gyro (Documentation - Release API)";
        }
    }
    catch(err) {
    }
//-->
var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10};
var tabs = {65535:["t0","All Methods"],2:["t2","Instance Methods"],8:["t4","Concrete Methods"]};
var altColor = "altColor";
var rowColor = "rowColor";
var tableTab = "tableTab";
var activeTableTab = "activeTableTab";
</script>
<noscript>
<div>JavaScript is disabled on your browser.</div>
</noscript>
<!-- ========= START OF TOP NAVBAR ======= -->
<div class="topNav"><a name="navbar.top">
<!--   -->
</a>
<div class="skipNav"><a href="#skip.navbar.top" title="Skip navigation links">Skip navigation links</a></div>
<a name="navbar.top.firstrow">
<!--   -->
</a>
<ul class="navList" title="Navigation">
<li><a href="../../../../overview-summary.html">Overview</a></li>
<li><a href="package-summary.html">Package</a></li>
<li class="navBarCell1Rev">Class</li>
<li><a href="package-tree.html">Tree</a></li>
<li><a href="../../../../deprecated-list.html">Deprecated</a></li>
<li><a href="../../../../index-all.html">Index</a></li>
<li><a href="../../../../help-doc.html">Help</a></li>
</ul>
</div>
<div class="subNav">
<ul class="navList">
<li><a href="../../../../edu/wpi/first/wpilibj/ADXL362.Axes.html" title="enum in edu.wpi.first.wpilibj"><span class="typeNameLink">Prev&nbsp;Class</span></a></li>
<li><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html" title="class in edu.wpi.first.wpilibj"><span class="typeNameLink">Next&nbsp;Class</span></a></li>
</ul>
<ul class="navList">
<li><a href="../../../../index.html?edu/wpi/first/wpilibj/ADXRS450_Gyro.html" target="_top">Frames</a></li>
<li><a href="ADXRS450_Gyro.html" target="_top">No&nbsp;Frames</a></li>
</ul>
<ul class="navList" id="allclasses_navbar_top">
<li><a href="../../../../allclasses-noframe.html">All&nbsp;Classes</a></li>
</ul>
<div>
<script type="text/javascript"><!--
  allClassesLink = document.getElementById("allclasses_navbar_top");
  if(window==top) {
    allClassesLink.style.display = "block";
  }
  else {
    allClassesLink.style.display = "none";
  }
  //-->
</script>
</div>
<div>
<ul class="subNavList">
<li>Summary:&nbsp;</li>
<li>Nested&nbsp;|&nbsp;</li>
<li><a href="#fields.inherited.from.class.edu.wpi.first.wpilibj.SensorBase">Field</a>&nbsp;|&nbsp;</li>
<li><a href="#constructor.summary">Constr</a>&nbsp;|&nbsp;</li>
<li><a href="#method.summary">Method</a></li>
</ul>
<ul class="subNavList">
<li>Detail:&nbsp;</li>
<li>Field&nbsp;|&nbsp;</li>
<li><a href="#constructor.detail">Constr</a>&nbsp;|&nbsp;</li>
<li><a href="#method.detail">Method</a></li>
</ul>
</div>
<a name="skip.navbar.top">
<!--   -->
</a></div>
<!-- ========= END OF TOP NAVBAR ========= -->
<!-- ======== START OF CLASS DATA ======== -->
<div class="header">
<div class="subTitle">edu.wpi.first.wpilibj</div>
<h2 title="Class ADXRS450_Gyro" class="title">Class ADXRS450_Gyro</h2>
</div>
<div class="contentContainer">
<ul class="inheritance">
<li>java.lang.Object</li>
<li>
<ul class="inheritance">
<li><a href="../../../../edu/wpi/first/wpilibj/SensorBase.html" title="class in edu.wpi.first.wpilibj">edu.wpi.first.wpilibj.SensorBase</a></li>
<li>
<ul class="inheritance">
<li><a href="../../../../edu/wpi/first/wpilibj/GyroBase.html" title="class in edu.wpi.first.wpilibj">edu.wpi.first.wpilibj.GyroBase</a></li>
<li>
<ul class="inheritance">
<li>edu.wpi.first.wpilibj.ADXRS450_Gyro</li>
</ul>
</li>
</ul>
</li>
</ul>
</li>
</ul>
<div class="description">
<ul class="blockList">
<li class="blockList">
<dl>
<dt>All Implemented Interfaces:</dt>
<dd><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html" title="interface in edu.wpi.first.wpilibj.interfaces">Gyro</a>, <a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html" title="interface in edu.wpi.first.wpilibj.livewindow">LiveWindowSendable</a>, <a href="../../../../edu/wpi/first/wpilibj/PIDSource.html" title="interface in edu.wpi.first.wpilibj">PIDSource</a>, <a href="../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj">Sendable</a></dd>
</dl>
<hr>
<br>
<pre>public class <span class="typeNameLabel">ADXRS450_Gyro</span>
extends <a href="../../../../edu/wpi/first/wpilibj/GyroBase.html" title="class in edu.wpi.first.wpilibj">GyroBase</a>
implements <a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html" title="interface in edu.wpi.first.wpilibj.interfaces">Gyro</a>, <a href="../../../../edu/wpi/first/wpilibj/PIDSource.html" title="interface in edu.wpi.first.wpilibj">PIDSource</a>, <a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html" title="interface in edu.wpi.first.wpilibj.livewindow">LiveWindowSendable</a></pre>
<div class="block">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.

 <p>This class is for the digital ADXRS450 gyro sensor that connects via SPI.</div>
</li>
</ul>
</div>
<div class="summary">
<ul class="blockList">
<li class="blockList">
<!-- =========== FIELD SUMMARY =========== -->
<ul class="blockList">
<li class="blockList"><a name="field.summary">
<!--   -->
</a>
<h3>Field Summary</h3>
<ul class="blockList">
<li class="blockList"><a name="fields.inherited.from.class.edu.wpi.first.wpilibj.SensorBase">
<!--   -->
</a>
<h3>Fields inherited from class&nbsp;edu.wpi.first.wpilibj.<a href="../../../../edu/wpi/first/wpilibj/SensorBase.html" title="class in edu.wpi.first.wpilibj">SensorBase</a></h3>
<code><a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#kAnalogInputChannels">kAnalogInputChannels</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#kAnalogOutputChannels">kAnalogOutputChannels</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#kDigitalChannels">kDigitalChannels</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#kPCMModules">kPCMModules</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#kPDPChannels">kPDPChannels</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#kPDPModules">kPDPModules</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#kPwmChannels">kPwmChannels</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#kRelayChannels">kRelayChannels</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#kSolenoidChannels">kSolenoidChannels</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#kSystemClockTicksPerMicrosecond">kSystemClockTicksPerMicrosecond</a></code></li>
</ul>
</li>
</ul>
<!-- ======== CONSTRUCTOR SUMMARY ======== -->
<ul class="blockList">
<li class="blockList"><a name="constructor.summary">
<!--   -->
</a>
<h3>Constructor Summary</h3>
<table class="memberSummary" border="0" cellpadding="3" cellspacing="0" summary="Constructor Summary table, listing constructors, and an explanation">
<caption><span>Constructors</span><span class="tabEnd">&nbsp;</span></caption>
<tr>
<th class="colOne" scope="col">Constructor and Description</th>
</tr>
<tr class="altColor">
<td class="colOne"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/ADXRS450_Gyro.html#ADXRS450_Gyro--">ADXRS450_Gyro</a></span>()</code>
<div class="block">Constructor.</div>
</td>
</tr>
<tr class="rowColor">
<td class="colOne"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/ADXRS450_Gyro.html#ADXRS450_Gyro-edu.wpi.first.wpilibj.SPI.Port-">ADXRS450_Gyro</a></span>(<a href="../../../../edu/wpi/first/wpilibj/SPI.Port.html" title="enum in edu.wpi.first.wpilibj">SPI.Port</a>&nbsp;port)</code>
<div class="block">Constructor.</div>
</td>
</tr>
</table>
</li>
</ul>
<!-- ========== METHOD SUMMARY =========== -->
<ul class="blockList">
<li class="blockList"><a name="method.summary">
<!--   -->
</a>
<h3>Method Summary</h3>
<table class="memberSummary" border="0" cellpadding="3" cellspacing="0" summary="Method Summary table, listing methods, and an explanation">
<caption><span id="t0" class="activeTableTab"><span>All Methods</span><span class="tabEnd">&nbsp;</span></span><span id="t2" class="tableTab"><span><a href="javascript:show(2);">Instance Methods</a></span><span class="tabEnd">&nbsp;</span></span><span id="t4" class="tableTab"><span><a href="javascript:show(8);">Concrete Methods</a></span><span class="tabEnd">&nbsp;</span></span></caption>
<tr>
<th class="colFirst" scope="col">Modifier and Type</th>
<th class="colLast" scope="col">Method and Description</th>
</tr>
<tr id="i0" class="altColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/ADXRS450_Gyro.html#calibrate--">calibrate</a></span>()</code>
<div class="block">Calibrate the gyro by running for a number of samples and computing the center value.</div>
</td>
</tr>
<tr id="i1" class="rowColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/ADXRS450_Gyro.html#free--">free</a></span>()</code>
<div class="block">Delete (free) the spi port used for the gyro and stop accumulating.</div>
</td>
</tr>
<tr id="i2" class="altColor">
<td class="colFirst"><code>double</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/ADXRS450_Gyro.html#getAngle--">getAngle</a></span>()</code>
<div class="block">Return the actual angle in degrees that the robot is currently facing.</div>
</td>
</tr>
<tr id="i3" class="rowColor">
<td class="colFirst"><code>double</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/ADXRS450_Gyro.html#getRate--">getRate</a></span>()</code>
<div class="block">Return the rate of rotation of the gyro.</div>
</td>
</tr>
<tr id="i4" class="altColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/ADXRS450_Gyro.html#reset--">reset</a></span>()</code>
<div class="block">Reset the gyro.</div>
</td>
</tr>
</table>
<ul class="blockList">
<li class="blockList"><a name="methods.inherited.from.class.edu.wpi.first.wpilibj.GyroBase">
<!--   -->
</a>
<h3>Methods inherited from class&nbsp;edu.wpi.first.wpilibj.<a href="../../../../edu/wpi/first/wpilibj/GyroBase.html" title="class in edu.wpi.first.wpilibj">GyroBase</a></h3>
<code><a href="../../../../edu/wpi/first/wpilibj/GyroBase.html#getPIDSourceType--">getPIDSourceType</a>, <a href="../../../../edu/wpi/first/wpilibj/GyroBase.html#getSmartDashboardType--">getSmartDashboardType</a>, <a href="../../../../edu/wpi/first/wpilibj/GyroBase.html#initTable-edu.wpi.first.networktables.NetworkTable-">initTable</a>, <a href="../../../../edu/wpi/first/wpilibj/GyroBase.html#pidGet--">pidGet</a>, <a href="../../../../edu/wpi/first/wpilibj/GyroBase.html#setPIDSourceType-edu.wpi.first.wpilibj.PIDSourceType-">setPIDSourceType</a>, <a href="../../../../edu/wpi/first/wpilibj/GyroBase.html#startLiveWindowMode--">startLiveWindowMode</a>, <a href="../../../../edu/wpi/first/wpilibj/GyroBase.html#stopLiveWindowMode--">stopLiveWindowMode</a>, <a href="../../../../edu/wpi/first/wpilibj/GyroBase.html#updateTable--">updateTable</a></code></li>
</ul>
<ul class="blockList">
<li class="blockList"><a name="methods.inherited.from.class.edu.wpi.first.wpilibj.SensorBase">
<!--   -->
</a>
<h3>Methods inherited from class&nbsp;edu.wpi.first.wpilibj.<a href="../../../../edu/wpi/first/wpilibj/SensorBase.html" title="class in edu.wpi.first.wpilibj">SensorBase</a></h3>
<code><a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#checkAnalogInputChannel-int-">checkAnalogInputChannel</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#checkAnalogOutputChannel-int-">checkAnalogOutputChannel</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#checkDigitalChannel-int-">checkDigitalChannel</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#checkPDPChannel-int-">checkPDPChannel</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#checkPDPModule-int-">checkPDPModule</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#checkPWMChannel-int-">checkPWMChannel</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#checkRelayChannel-int-">checkRelayChannel</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#checkSolenoidChannel-int-">checkSolenoidChannel</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#checkSolenoidModule-int-">checkSolenoidModule</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#getDefaultSolenoidModule--">getDefaultSolenoidModule</a>, <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#setDefaultSolenoidModule-int-">setDefaultSolenoidModule</a></code></li>
</ul>
<ul class="blockList">
<li class="blockList"><a name="methods.inherited.from.class.java.lang.Object">
<!--   -->
</a>
<h3>Methods inherited from class&nbsp;java.lang.Object</h3>
<code>clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait</code></li>
</ul>
<ul class="blockList">
<li class="blockList"><a name="methods.inherited.from.class.edu.wpi.first.wpilibj.PIDSource">
<!--   -->
</a>
<h3>Methods inherited from interface&nbsp;edu.wpi.first.wpilibj.<a href="../../../../edu/wpi/first/wpilibj/PIDSource.html" title="interface in edu.wpi.first.wpilibj">PIDSource</a></h3>
<code><a href="../../../../edu/wpi/first/wpilibj/PIDSource.html#getPIDSourceType--">getPIDSourceType</a>, <a href="../../../../edu/wpi/first/wpilibj/PIDSource.html#pidGet--">pidGet</a>, <a href="../../../../edu/wpi/first/wpilibj/PIDSource.html#setPIDSourceType-edu.wpi.first.wpilibj.PIDSourceType-">setPIDSourceType</a></code></li>
</ul>
<ul class="blockList">
<li class="blockList"><a name="methods.inherited.from.class.edu.wpi.first.wpilibj.livewindow.LiveWindowSendable">
<!--   -->
</a>
<h3>Methods inherited from interface&nbsp;edu.wpi.first.wpilibj.livewindow.<a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html" title="interface in edu.wpi.first.wpilibj.livewindow">LiveWindowSendable</a></h3>
<code><a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html#startLiveWindowMode--">startLiveWindowMode</a>, <a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html#stopLiveWindowMode--">stopLiveWindowMode</a>, <a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html#updateTable--">updateTable</a></code></li>
</ul>
<ul class="blockList">
<li class="blockList"><a name="methods.inherited.from.class.edu.wpi.first.wpilibj.Sendable">
<!--   -->
</a>
<h3>Methods inherited from interface&nbsp;edu.wpi.first.wpilibj.<a href="../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj">Sendable</a></h3>
<code><a href="../../../../edu/wpi/first/wpilibj/Sendable.html#getSmartDashboardType--">getSmartDashboardType</a>, <a href="../../../../edu/wpi/first/wpilibj/Sendable.html#initTable-edu.wpi.first.networktables.NetworkTable-">initTable</a></code></li>
</ul>
</li>
</ul>
</li>
</ul>
</div>
<div class="details">
<ul class="blockList">
<li class="blockList">
<!-- ========= CONSTRUCTOR DETAIL ======== -->
<ul class="blockList">
<li class="blockList"><a name="constructor.detail">
<!--   -->
</a>
<h3>Constructor Detail</h3>
<a name="ADXRS450_Gyro--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>ADXRS450_Gyro</h4>
<pre>public&nbsp;ADXRS450_Gyro()</pre>
<div class="block">Constructor.  Uses the onboard CS0.</div>
</li>
</ul>
<a name="ADXRS450_Gyro-edu.wpi.first.wpilibj.SPI.Port-">
<!--   -->
</a>
<ul class="blockListLast">
<li class="blockList">
<h4>ADXRS450_Gyro</h4>
<pre>public&nbsp;ADXRS450_Gyro(<a href="../../../../edu/wpi/first/wpilibj/SPI.Port.html" title="enum in edu.wpi.first.wpilibj">SPI.Port</a>&nbsp;port)</pre>
<div class="block">Constructor.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>port</code> - The SPI port that the gyro is connected to</dd>
</dl>
</li>
</ul>
</li>
</ul>
<!-- ============ METHOD DETAIL ========== -->
<ul class="blockList">
<li class="blockList"><a name="method.detail">
<!--   -->
</a>
<h3>Method Detail</h3>
<a name="calibrate--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>calibrate</h4>
<pre>public&nbsp;void&nbsp;calibrate()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface:&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html#calibrate--">Gyro</a></code></span></div>
<div class="block">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.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html#calibrate--">calibrate</a></code>&nbsp;in interface&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html" title="interface in edu.wpi.first.wpilibj.interfaces">Gyro</a></code></dd>
</dl>
</li>
</ul>
<a name="reset--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>reset</h4>
<pre>public&nbsp;void&nbsp;reset()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface:&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html#reset--">Gyro</a></code></span></div>
<div class="block">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.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html#reset--">reset</a></code>&nbsp;in interface&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html" title="interface in edu.wpi.first.wpilibj.interfaces">Gyro</a></code></dd>
</dl>
</li>
</ul>
<a name="free--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>free</h4>
<pre>public&nbsp;void&nbsp;free()</pre>
<div class="block">Delete (free) the spi port used for the gyro and stop accumulating.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html#free--">free</a></code>&nbsp;in interface&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html" title="interface in edu.wpi.first.wpilibj.interfaces">Gyro</a></code></dd>
<dt><span class="overrideSpecifyLabel">Overrides:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#free--">free</a></code>&nbsp;in class&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/SensorBase.html" title="class in edu.wpi.first.wpilibj">SensorBase</a></code></dd>
</dl>
</li>
</ul>
<a name="getAngle--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getAngle</h4>
<pre>public&nbsp;double&nbsp;getAngle()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface:&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html#getAngle--">Gyro</a></code></span></div>
<div class="block">Return the actual angle in degrees that the robot is currently facing.

 <p>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.

 <p>This heading is based on integration of the returned rate from the gyro.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html#getAngle--">getAngle</a></code>&nbsp;in interface&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html" title="interface in edu.wpi.first.wpilibj.interfaces">Gyro</a></code></dd>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>the current heading of the robot in degrees.</dd>
</dl>
</li>
</ul>
<a name="getRate--">
<!--   -->
</a>
<ul class="blockListLast">
<li class="blockList">
<h4>getRate</h4>
<pre>public&nbsp;double&nbsp;getRate()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface:&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html#getRate--">Gyro</a></code></span></div>
<div class="block">Return the rate of rotation of the gyro.

 <p>The rate is based on the most recent reading of the gyro analog value</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html#getRate--">getRate</a></code>&nbsp;in interface&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/interfaces/Gyro.html" title="interface in edu.wpi.first.wpilibj.interfaces">Gyro</a></code></dd>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>the current rate in degrees per second</dd>
</dl>
</li>
</ul>
</li>
</ul>
</li>
</ul>
</div>
</div>
<!-- ========= END OF CLASS DATA ========= -->
<!-- ======= START OF BOTTOM NAVBAR ====== -->
<div class="bottomNav"><a name="navbar.bottom">
<!--   -->
</a>
<div class="skipNav"><a href="#skip.navbar.bottom" title="Skip navigation links">Skip navigation links</a></div>
<a name="navbar.bottom.firstrow">
<!--   -->
</a>
<ul class="navList" title="Navigation">
<li><a href="../../../../overview-summary.html">Overview</a></li>
<li><a href="package-summary.html">Package</a></li>
<li class="navBarCell1Rev">Class</li>
<li><a href="package-tree.html">Tree</a></li>
<li><a href="../../../../deprecated-list.html">Deprecated</a></li>
<li><a href="../../../../index-all.html">Index</a></li>
<li><a href="../../../../help-doc.html">Help</a></li>
</ul>
</div>
<div class="subNav">
<ul class="navList">
<li><a href="../../../../edu/wpi/first/wpilibj/ADXL362.Axes.html" title="enum in edu.wpi.first.wpilibj"><span class="typeNameLink">Prev&nbsp;Class</span></a></li>
<li><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html" title="class in edu.wpi.first.wpilibj"><span class="typeNameLink">Next&nbsp;Class</span></a></li>
</ul>
<ul class="navList">
<li><a href="../../../../index.html?edu/wpi/first/wpilibj/ADXRS450_Gyro.html" target="_top">Frames</a></li>
<li><a href="ADXRS450_Gyro.html" target="_top">No&nbsp;Frames</a></li>
</ul>
<ul class="navList" id="allclasses_navbar_bottom">
<li><a href="../../../../allclasses-noframe.html">All&nbsp;Classes</a></li>
</ul>
<div>
<script type="text/javascript"><!--
  allClassesLink = document.getElementById("allclasses_navbar_bottom");
  if(window==top) {
    allClassesLink.style.display = "block";
  }
  else {
    allClassesLink.style.display = "none";
  }
  //-->
</script>
</div>
<div>
<ul class="subNavList">
<li>Summary:&nbsp;</li>
<li>Nested&nbsp;|&nbsp;</li>
<li><a href="#fields.inherited.from.class.edu.wpi.first.wpilibj.SensorBase">Field</a>&nbsp;|&nbsp;</li>
<li><a href="#constructor.summary">Constr</a>&nbsp;|&nbsp;</li>
<li><a href="#method.summary">Method</a></li>
</ul>
<ul class="subNavList">
<li>Detail:&nbsp;</li>
<li>Field&nbsp;|&nbsp;</li>
<li><a href="#constructor.detail">Constr</a>&nbsp;|&nbsp;</li>
<li><a href="#method.detail">Method</a></li>
</ul>
</div>
<a name="skip.navbar.bottom">
<!--   -->
</a></div>
<!-- ======== END OF BOTTOM NAVBAR ======= -->
</body>
</html>