wpilib18/java/current/javadoc/edu/wpi/first/wpilibj/AnalogAccelerometer.html
<!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>AnalogAccelerometer (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="AnalogAccelerometer (Documentation - Release API)";
}
}
catch(err) {
}
//-->
var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10,"i5":10,"i6":10,"i7":10,"i8":10,"i9":10,"i10":10,"i11":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/ADXRS450_Gyro.html" title="class in edu.wpi.first.wpilibj"><span class="typeNameLink">Prev Class</span></a></li>
<li><a href="../../../../edu/wpi/first/wpilibj/AnalogGyro.html" title="class in edu.wpi.first.wpilibj"><span class="typeNameLink">Next Class</span></a></li>
</ul>
<ul class="navList">
<li><a href="../../../../index.html?edu/wpi/first/wpilibj/AnalogAccelerometer.html" target="_top">Frames</a></li>
<li><a href="AnalogAccelerometer.html" target="_top">No Frames</a></li>
</ul>
<ul class="navList" id="allclasses_navbar_top">
<li><a href="../../../../allclasses-noframe.html">All 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: </li>
<li>Nested | </li>
<li><a href="#field.summary">Field</a> | </li>
<li><a href="#constructor.summary">Constr</a> | </li>
<li><a href="#method.summary">Method</a></li>
</ul>
<ul class="subNavList">
<li>Detail: </li>
<li><a href="#field.detail">Field</a> | </li>
<li><a href="#constructor.detail">Constr</a> | </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 AnalogAccelerometer" class="title">Class AnalogAccelerometer</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>edu.wpi.first.wpilibj.AnalogAccelerometer</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/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">AnalogAccelerometer</span>
extends <a href="../../../../edu/wpi/first/wpilibj/SensorBase.html" title="class in edu.wpi.first.wpilibj">SensorBase</a>
implements <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">Handle operation of an analog accelerometer. The accelerometer reads acceleration directly
through the sensor. Many sensors have multiple axis and can be treated as multiple devices. Each
is calibrated by finding the center value over a period of time.</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>
<table class="memberSummary" border="0" cellpadding="3" cellspacing="0" summary="Field Summary table, listing fields, and an explanation">
<caption><span>Fields</span><span class="tabEnd"> </span></caption>
<tr>
<th class="colFirst" scope="col">Modifier and Type</th>
<th class="colLast" scope="col">Field and Description</th>
</tr>
<tr class="altColor">
<td class="colFirst"><code>protected <a href="../../../../edu/wpi/first/wpilibj/PIDSourceType.html" title="enum in edu.wpi.first.wpilibj">PIDSourceType</a></code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#m_pidSource">m_pidSource</a></span></code> </td>
</tr>
</table>
<ul class="blockList">
<li class="blockList"><a name="fields.inherited.from.class.edu.wpi.first.wpilibj.SensorBase">
<!-- -->
</a>
<h3>Fields inherited from class 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"> </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/AnalogAccelerometer.html#AnalogAccelerometer-edu.wpi.first.wpilibj.AnalogInput-">AnalogAccelerometer</a></span>(<a href="../../../../edu/wpi/first/wpilibj/AnalogInput.html" title="class in edu.wpi.first.wpilibj">AnalogInput</a> channel)</code>
<div class="block">Create a new instance of Accelerometer from an existing AnalogChannel.</div>
</td>
</tr>
<tr class="rowColor">
<td class="colOne"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#AnalogAccelerometer-int-">AnalogAccelerometer</a></span>(int channel)</code>
<div class="block">Create a new instance of an accelerometer.</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"> </span></span><span id="t2" class="tableTab"><span><a href="javascript:show(2);">Instance Methods</a></span><span class="tabEnd"> </span></span><span id="t4" class="tableTab"><span><a href="javascript:show(8);">Concrete Methods</a></span><span class="tabEnd"> </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/AnalogAccelerometer.html#free--">free</a></span>()</code>
<div class="block">Delete the analog components used for the accelerometer.</div>
</td>
</tr>
<tr id="i1" class="rowColor">
<td class="colFirst"><code>double</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#getAcceleration--">getAcceleration</a></span>()</code>
<div class="block">Return the acceleration in Gs.</div>
</td>
</tr>
<tr id="i2" class="altColor">
<td class="colFirst"><code><a href="../../../../edu/wpi/first/wpilibj/PIDSourceType.html" title="enum in edu.wpi.first.wpilibj">PIDSourceType</a></code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#getPIDSourceType--">getPIDSourceType</a></span>()</code>
<div class="block">Get which parameter of the device you are using as a process control variable.</div>
</td>
</tr>
<tr id="i3" class="rowColor">
<td class="colFirst"><code>java.lang.String</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#getSmartDashboardType--">getSmartDashboardType</a></span>()</code>
<div class="block">The string representation of the named data type that will be used by the smart dashboard for
this <a href="../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj"><code>Sendable</code></a>.</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/AnalogAccelerometer.html#initTable-edu.wpi.first.networktables.NetworkTable-">initTable</a></span>(<a href="../../../../edu/wpi/first/networktables/NetworkTable.html" title="class in edu.wpi.first.networktables">NetworkTable</a> subtable)</code>
<div class="block">Initializes a table for this <a href="../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj"><code>Sendable</code></a> object.</div>
</td>
</tr>
<tr id="i5" class="rowColor">
<td class="colFirst"><code>double</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#pidGet--">pidGet</a></span>()</code>
<div class="block">Get the Acceleration for the PID Source parent.</div>
</td>
</tr>
<tr id="i6" class="altColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#setPIDSourceType-edu.wpi.first.wpilibj.PIDSourceType-">setPIDSourceType</a></span>(<a href="../../../../edu/wpi/first/wpilibj/PIDSourceType.html" title="enum in edu.wpi.first.wpilibj">PIDSourceType</a> pidSource)</code>
<div class="block">Set which parameter of the device you are using as a process control variable.</div>
</td>
</tr>
<tr id="i7" class="rowColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#setSensitivity-double-">setSensitivity</a></span>(double sensitivity)</code>
<div class="block">Set the accelerometer sensitivity.</div>
</td>
</tr>
<tr id="i8" class="altColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#setZero-double-">setZero</a></span>(double zero)</code>
<div class="block">Set the voltage that corresponds to 0 G.</div>
</td>
</tr>
<tr id="i9" class="rowColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#startLiveWindowMode--">startLiveWindowMode</a></span>()</code>
<div class="block">Analog Channels don't have to do anything special when entering the LiveWindow.</div>
</td>
</tr>
<tr id="i10" class="altColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#stopLiveWindowMode--">stopLiveWindowMode</a></span>()</code>
<div class="block">Analog Channels don't have to do anything special when exiting the LiveWindow.</div>
</td>
</tr>
<tr id="i11" class="rowColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/AnalogAccelerometer.html#updateTable--">updateTable</a></span>()</code>
<div class="block">Update the table for this sendable object with the latest values.</div>
</td>
</tr>
</table>
<ul class="blockList">
<li class="blockList"><a name="methods.inherited.from.class.edu.wpi.first.wpilibj.SensorBase">
<!-- -->
</a>
<h3>Methods inherited from class 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 java.lang.Object</h3>
<code>clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait</code></li>
</ul>
</li>
</ul>
</li>
</ul>
</div>
<div class="details">
<ul class="blockList">
<li class="blockList">
<!-- ============ FIELD DETAIL =========== -->
<ul class="blockList">
<li class="blockList"><a name="field.detail">
<!-- -->
</a>
<h3>Field Detail</h3>
<a name="m_pidSource">
<!-- -->
</a>
<ul class="blockListLast">
<li class="blockList">
<h4>m_pidSource</h4>
<pre>protected <a href="../../../../edu/wpi/first/wpilibj/PIDSourceType.html" title="enum in edu.wpi.first.wpilibj">PIDSourceType</a> m_pidSource</pre>
</li>
</ul>
</li>
</ul>
<!-- ========= CONSTRUCTOR DETAIL ======== -->
<ul class="blockList">
<li class="blockList"><a name="constructor.detail">
<!-- -->
</a>
<h3>Constructor Detail</h3>
<a name="AnalogAccelerometer-int-">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>AnalogAccelerometer</h4>
<pre>public AnalogAccelerometer(int channel)</pre>
<div class="block">Create a new instance of an accelerometer.
<p>The constructor allocates desired analog channel.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>channel</code> - The channel number for the analog input the accelerometer is connected to</dd>
</dl>
</li>
</ul>
<a name="AnalogAccelerometer-edu.wpi.first.wpilibj.AnalogInput-">
<!-- -->
</a>
<ul class="blockListLast">
<li class="blockList">
<h4>AnalogAccelerometer</h4>
<pre>public AnalogAccelerometer(<a href="../../../../edu/wpi/first/wpilibj/AnalogInput.html" title="class in edu.wpi.first.wpilibj">AnalogInput</a> channel)</pre>
<div class="block">Create a new instance of Accelerometer from an existing AnalogChannel. Make a new instance of
accelerometer given an AnalogChannel. This is particularly useful if the port is going to be
read as an analog channel as well as through the Accelerometer class.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>channel</code> - The existing AnalogInput object for the analog input the accelerometer 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="free--">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>free</h4>
<pre>public void free()</pre>
<div class="block">Delete the analog components used for the accelerometer.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Overrides:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/SensorBase.html#free--">free</a></code> in class <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="getAcceleration--">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getAcceleration</h4>
<pre>public double getAcceleration()</pre>
<div class="block">Return the acceleration in Gs.
<p>The acceleration is returned units of Gs.</div>
<dl>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>The current acceleration of the sensor in Gs.</dd>
</dl>
</li>
</ul>
<a name="setSensitivity-double-">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setSensitivity</h4>
<pre>public void setSensitivity(double sensitivity)</pre>
<div class="block">Set the accelerometer sensitivity.
<p>This sets the sensitivity of the accelerometer used for calculating the acceleration. The
sensitivity varies by accelerometer model. There are constants defined for various models.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>sensitivity</code> - The sensitivity of accelerometer in Volts per G.</dd>
</dl>
</li>
</ul>
<a name="setZero-double-">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setZero</h4>
<pre>public void setZero(double zero)</pre>
<div class="block">Set the voltage that corresponds to 0 G.
<p>The zero G voltage varies by accelerometer model. There are constants defined for various
models.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>zero</code> - The zero G voltage.</dd>
</dl>
</li>
</ul>
<a name="setPIDSourceType-edu.wpi.first.wpilibj.PIDSourceType-">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setPIDSourceType</h4>
<pre>public void setPIDSourceType(<a href="../../../../edu/wpi/first/wpilibj/PIDSourceType.html" title="enum in edu.wpi.first.wpilibj">PIDSourceType</a> pidSource)</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface: <code><a href="../../../../edu/wpi/first/wpilibj/PIDSource.html#setPIDSourceType-edu.wpi.first.wpilibj.PIDSourceType-">PIDSource</a></code></span></div>
<div class="block">Set which parameter of the device you are using as a process control variable.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/PIDSource.html#setPIDSourceType-edu.wpi.first.wpilibj.PIDSourceType-">setPIDSourceType</a></code> in interface <code><a href="../../../../edu/wpi/first/wpilibj/PIDSource.html" title="interface in edu.wpi.first.wpilibj">PIDSource</a></code></dd>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>pidSource</code> - An enum to select the parameter.</dd>
</dl>
</li>
</ul>
<a name="getPIDSourceType--">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getPIDSourceType</h4>
<pre>public <a href="../../../../edu/wpi/first/wpilibj/PIDSourceType.html" title="enum in edu.wpi.first.wpilibj">PIDSourceType</a> getPIDSourceType()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface: <code><a href="../../../../edu/wpi/first/wpilibj/PIDSource.html#getPIDSourceType--">PIDSource</a></code></span></div>
<div class="block">Get which parameter of the device you are using as a process control variable.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/PIDSource.html#getPIDSourceType--">getPIDSourceType</a></code> in interface <code><a href="../../../../edu/wpi/first/wpilibj/PIDSource.html" title="interface in edu.wpi.first.wpilibj">PIDSource</a></code></dd>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>the currently selected PID source parameter</dd>
</dl>
</li>
</ul>
<a name="pidGet--">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>pidGet</h4>
<pre>public double pidGet()</pre>
<div class="block">Get the Acceleration for the PID Source parent.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/PIDSource.html#pidGet--">pidGet</a></code> in interface <code><a href="../../../../edu/wpi/first/wpilibj/PIDSource.html" title="interface in edu.wpi.first.wpilibj">PIDSource</a></code></dd>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>The current acceleration in Gs.</dd>
</dl>
</li>
</ul>
<a name="getSmartDashboardType--">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getSmartDashboardType</h4>
<pre>public java.lang.String getSmartDashboardType()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface: <code><a href="../../../../edu/wpi/first/wpilibj/Sendable.html#getSmartDashboardType--">Sendable</a></code></span></div>
<div class="block">The string representation of the named data type that will be used by the smart dashboard for
this <a href="../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj"><code>Sendable</code></a>.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/Sendable.html#getSmartDashboardType--">getSmartDashboardType</a></code> in interface <code><a href="../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj">Sendable</a></code></dd>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>The type of this <a href="../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj"><code>Sendable</code></a>.</dd>
</dl>
</li>
</ul>
<a name="initTable-edu.wpi.first.networktables.NetworkTable-">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>initTable</h4>
<pre>public void initTable(<a href="../../../../edu/wpi/first/networktables/NetworkTable.html" title="class in edu.wpi.first.networktables">NetworkTable</a> subtable)</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface: <code><a href="../../../../edu/wpi/first/wpilibj/Sendable.html#initTable-edu.wpi.first.networktables.NetworkTable-">Sendable</a></code></span></div>
<div class="block">Initializes a table for this <a href="../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj"><code>Sendable</code></a> object.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/Sendable.html#initTable-edu.wpi.first.networktables.NetworkTable-">initTable</a></code> in interface <code><a href="../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj">Sendable</a></code></dd>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>subtable</code> - The table to put the values in.</dd>
</dl>
</li>
</ul>
<a name="updateTable--">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>updateTable</h4>
<pre>public void updateTable()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface: <code><a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html#updateTable--">LiveWindowSendable</a></code></span></div>
<div class="block">Update the table for this sendable object with the latest values.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html#updateTable--">updateTable</a></code> in interface <code><a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html" title="interface in edu.wpi.first.wpilibj.livewindow">LiveWindowSendable</a></code></dd>
</dl>
</li>
</ul>
<a name="startLiveWindowMode--">
<!-- -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>startLiveWindowMode</h4>
<pre>public void startLiveWindowMode()</pre>
<div class="block">Analog Channels don't have to do anything special when entering the LiveWindow. Start having this sendable object automatically respond to value changes reflect the value on
the table.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html#startLiveWindowMode--">startLiveWindowMode</a></code> in interface <code><a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html" title="interface in edu.wpi.first.wpilibj.livewindow">LiveWindowSendable</a></code></dd>
</dl>
</li>
</ul>
<a name="stopLiveWindowMode--">
<!-- -->
</a>
<ul class="blockListLast">
<li class="blockList">
<h4>stopLiveWindowMode</h4>
<pre>public void stopLiveWindowMode()</pre>
<div class="block">Analog Channels don't have to do anything special when exiting the LiveWindow. Stop having this sendable object automatically respond to value changes.</div>
<dl>
<dt><span class="overrideSpecifyLabel">Specified by:</span></dt>
<dd><code><a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html#stopLiveWindowMode--">stopLiveWindowMode</a></code> in interface <code><a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html" title="interface in edu.wpi.first.wpilibj.livewindow">LiveWindowSendable</a></code></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/ADXRS450_Gyro.html" title="class in edu.wpi.first.wpilibj"><span class="typeNameLink">Prev Class</span></a></li>
<li><a href="../../../../edu/wpi/first/wpilibj/AnalogGyro.html" title="class in edu.wpi.first.wpilibj"><span class="typeNameLink">Next Class</span></a></li>
</ul>
<ul class="navList">
<li><a href="../../../../index.html?edu/wpi/first/wpilibj/AnalogAccelerometer.html" target="_top">Frames</a></li>
<li><a href="AnalogAccelerometer.html" target="_top">No Frames</a></li>
</ul>
<ul class="navList" id="allclasses_navbar_bottom">
<li><a href="../../../../allclasses-noframe.html">All 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: </li>
<li>Nested | </li>
<li><a href="#field.summary">Field</a> | </li>
<li><a href="#constructor.summary">Constr</a> | </li>
<li><a href="#method.summary">Method</a></li>
</ul>
<ul class="subNavList">
<li>Detail: </li>
<li><a href="#field.detail">Field</a> | </li>
<li><a href="#constructor.detail">Constr</a> | </li>
<li><a href="#method.detail">Method</a></li>
</ul>
</div>
<a name="skip.navbar.bottom">
<!-- -->
</a></div>
<!-- ======== END OF BOTTOM NAVBAR ======= -->
</body>
</html>