wh1ter0se/PowerUp-2018

View on GitHub
wpilib18/java/current/javadoc/edu/wpi/first/wpilibj/command/PIDCommand.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:54 EDT 2017 -->
<title>PIDCommand (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="PIDCommand (Documentation - Release API)";
        }
    }
    catch(err) {
    }
//-->
var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10,"i5":6,"i6":10,"i7":10,"i8":10,"i9":6};
var tabs = {65535:["t0","All Methods"],2:["t2","Instance Methods"],4:["t3","Abstract 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/command/InstantCommand.html" title="class in edu.wpi.first.wpilibj.command"><span class="typeNameLink">Prev&nbsp;Class</span></a></li>
<li><a href="../../../../../edu/wpi/first/wpilibj/command/PIDSubsystem.html" title="class in edu.wpi.first.wpilibj.command"><span class="typeNameLink">Next&nbsp;Class</span></a></li>
</ul>
<ul class="navList">
<li><a href="../../../../../index.html?edu/wpi/first/wpilibj/command/PIDCommand.html" target="_top">Frames</a></li>
<li><a href="PIDCommand.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>Field&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.command</div>
<h2 title="Class PIDCommand" class="title">Class PIDCommand</h2>
</div>
<div class="contentContainer">
<ul class="inheritance">
<li>java.lang.Object</li>
<li>
<ul class="inheritance">
<li><a href="../../../../../edu/wpi/first/wpilibj/command/Command.html" title="class in edu.wpi.first.wpilibj.command">edu.wpi.first.wpilibj.command.Command</a></li>
<li>
<ul class="inheritance">
<li>edu.wpi.first.wpilibj.command.PIDCommand</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/NamedSendable.html" title="interface in edu.wpi.first.wpilibj">NamedSendable</a>, <a href="../../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj">Sendable</a></dd>
</dl>
<hr>
<br>
<pre>public abstract class <span class="typeNameLabel">PIDCommand</span>
extends <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html" title="class in edu.wpi.first.wpilibj.command">Command</a>
implements <a href="../../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj">Sendable</a></pre>
<div class="block">This class defines a <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html" title="class in edu.wpi.first.wpilibj.command"><code>Command</code></a> which interacts heavily with a PID loop.

 <p> It provides some convenience methods to run an internal <a href="../../../../../edu/wpi/first/wpilibj/PIDController.html" title="class in edu.wpi.first.wpilibj"><code>PIDController</code></a> . It will also
 start and stop said <a href="../../../../../edu/wpi/first/wpilibj/PIDController.html" title="class in edu.wpi.first.wpilibj"><code>PIDController</code></a> when the <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> is first initialized and
 ended/interrupted. </p></div>
</li>
</ul>
</div>
<div class="summary">
<ul class="blockList">
<li class="blockList">
<!-- ======== 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/command/PIDCommand.html#PIDCommand-double-double-double-">PIDCommand</a></span>(double&nbsp;p,
          double&nbsp;i,
          double&nbsp;d)</code>
<div class="block">Instantiates a <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> that will use the given p, i and d values.</div>
</td>
</tr>
<tr class="rowColor">
<td class="colOne"><code><span class="memberNameLink"><a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#PIDCommand-double-double-double-double-">PIDCommand</a></span>(double&nbsp;p,
          double&nbsp;i,
          double&nbsp;d,
          double&nbsp;period)</code>
<div class="block">Instantiates a <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> that will use the given p, i and d values.</div>
</td>
</tr>
<tr class="altColor">
<td class="colOne"><code><span class="memberNameLink"><a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#PIDCommand-java.lang.String-double-double-double-">PIDCommand</a></span>(java.lang.String&nbsp;name,
          double&nbsp;p,
          double&nbsp;i,
          double&nbsp;d)</code>
<div class="block">Instantiates a <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> that will use the given p, i and d values.</div>
</td>
</tr>
<tr class="rowColor">
<td class="colOne"><code><span class="memberNameLink"><a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#PIDCommand-java.lang.String-double-double-double-double-">PIDCommand</a></span>(java.lang.String&nbsp;name,
          double&nbsp;p,
          double&nbsp;i,
          double&nbsp;d,
          double&nbsp;period)</code>
<div class="block">Instantiates a <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> that will use the given p, i and d values.</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="t3" class="tableTab"><span><a href="javascript:show(4);">Abstract 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>protected <a href="../../../../../edu/wpi/first/wpilibj/PIDController.html" title="class in edu.wpi.first.wpilibj">PIDController</a></code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#getPIDController--">getPIDController</a></span>()</code>
<div class="block">Returns the <a href="../../../../../edu/wpi/first/wpilibj/PIDController.html" title="class in edu.wpi.first.wpilibj"><code>PIDController</code></a> used by this <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a>.</div>
</td>
</tr>
<tr id="i1" class="rowColor">
<td class="colFirst"><code>protected double</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#getPosition--">getPosition</a></span>()</code>
<div class="block">Returns the current position.</div>
</td>
</tr>
<tr id="i2" class="altColor">
<td class="colFirst"><code>protected double</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#getSetpoint--">getSetpoint</a></span>()</code>
<div class="block">Returns the setpoint.</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/command/PIDCommand.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/command/PIDCommand.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>&nbsp;table)</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>protected abstract double</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#returnPIDInput--">returnPIDInput</a></span>()</code>
<div class="block">Returns the input for the pid loop.</div>
</td>
</tr>
<tr id="i6" class="altColor">
<td class="colFirst"><code>protected void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#setInputRange-double-double-">setInputRange</a></span>(double&nbsp;minimumInput,
             double&nbsp;maximumInput)</code>
<div class="block">Sets the maximum and minimum values expected from the input and setpoint.</div>
</td>
</tr>
<tr id="i7" class="rowColor">
<td class="colFirst"><code>protected void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#setSetpoint-double-">setSetpoint</a></span>(double&nbsp;setpoint)</code>
<div class="block">Sets the setpoint to the given value.</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/command/PIDCommand.html#setSetpointRelative-double-">setSetpointRelative</a></span>(double&nbsp;deltaSetpoint)</code>
<div class="block">Adds the given value to the setpoint.</div>
</td>
</tr>
<tr id="i9" class="rowColor">
<td class="colFirst"><code>protected abstract void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#usePIDOutput-double-">usePIDOutput</a></span>(double&nbsp;output)</code>
<div class="block">Uses the value that the pid loop calculated.</div>
</td>
</tr>
</table>
<ul class="blockList">
<li class="blockList"><a name="methods.inherited.from.class.edu.wpi.first.wpilibj.command.Command">
<!--   -->
</a>
<h3>Methods inherited from class&nbsp;edu.wpi.first.wpilibj.command.<a href="../../../../../edu/wpi/first/wpilibj/command/Command.html" title="class in edu.wpi.first.wpilibj.command">Command</a></h3>
<code><a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#cancel--">cancel</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#clearRequirements--">clearRequirements</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#doesRequire-edu.wpi.first.wpilibj.command.Subsystem-">doesRequire</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#end--">end</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#execute--">execute</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#getGroup--">getGroup</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#getName--">getName</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#initialize--">initialize</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#interrupted--">interrupted</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#isCanceled--">isCanceled</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#isFinished--">isFinished</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#isInterruptible--">isInterruptible</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#isRunning--">isRunning</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#isTimedOut--">isTimedOut</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#requires-edu.wpi.first.wpilibj.command.Subsystem-">requires</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#setInterruptible-boolean-">setInterruptible</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#setRunWhenDisabled-boolean-">setRunWhenDisabled</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#setTimeout-double-">setTimeout</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#start--">start</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#timeSinceInitialized--">timeSinceInitialized</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#toString--">toString</a>, <a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#willRunWhenDisabled--">willRunWhenDisabled</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, wait, wait, wait</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="PIDCommand-java.lang.String-double-double-double-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>PIDCommand</h4>
<pre>public&nbsp;PIDCommand(java.lang.String&nbsp;name,
                  double&nbsp;p,
                  double&nbsp;i,
                  double&nbsp;d)</pre>
<div class="block">Instantiates a <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> that will use the given p, i and d values.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>name</code> - the name of the command</dd>
<dd><code>p</code> - the proportional value</dd>
<dd><code>i</code> - the integral value</dd>
<dd><code>d</code> - the derivative value</dd>
</dl>
</li>
</ul>
<a name="PIDCommand-java.lang.String-double-double-double-double-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>PIDCommand</h4>
<pre>public&nbsp;PIDCommand(java.lang.String&nbsp;name,
                  double&nbsp;p,
                  double&nbsp;i,
                  double&nbsp;d,
                  double&nbsp;period)</pre>
<div class="block">Instantiates a <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> that will use the given p, i and d values. It will also space
 the time between PID loop calculations to be equal to the given period.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>name</code> - the name</dd>
<dd><code>p</code> - the proportional value</dd>
<dd><code>i</code> - the integral value</dd>
<dd><code>d</code> - the derivative value</dd>
<dd><code>period</code> - the time (in seconds) between calculations</dd>
</dl>
</li>
</ul>
<a name="PIDCommand-double-double-double-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>PIDCommand</h4>
<pre>public&nbsp;PIDCommand(double&nbsp;p,
                  double&nbsp;i,
                  double&nbsp;d)</pre>
<div class="block">Instantiates a <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> that will use the given p, i and d values. It will use the
 class name as its name.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>p</code> - the proportional value</dd>
<dd><code>i</code> - the integral value</dd>
<dd><code>d</code> - the derivative value</dd>
</dl>
</li>
</ul>
<a name="PIDCommand-double-double-double-double-">
<!--   -->
</a>
<ul class="blockListLast">
<li class="blockList">
<h4>PIDCommand</h4>
<pre>public&nbsp;PIDCommand(double&nbsp;p,
                  double&nbsp;i,
                  double&nbsp;d,
                  double&nbsp;period)</pre>
<div class="block">Instantiates a <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> that will use the given p, i and d values. It will use the
 class name as its name.. It will also space the time between PID loop calculations to be equal
 to the given period.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>p</code> - the proportional value</dd>
<dd><code>i</code> - the integral value</dd>
<dd><code>d</code> - the derivative value</dd>
<dd><code>period</code> - the time (in seconds) between calculations</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="getPIDController--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getPIDController</h4>
<pre>protected&nbsp;<a href="../../../../../edu/wpi/first/wpilibj/PIDController.html" title="class in edu.wpi.first.wpilibj">PIDController</a>&nbsp;getPIDController()</pre>
<div class="block">Returns the <a href="../../../../../edu/wpi/first/wpilibj/PIDController.html" title="class in edu.wpi.first.wpilibj"><code>PIDController</code></a> used by this <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a>. Use this if you would like
 to fine tune the pid loop.</div>
<dl>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>the <a href="../../../../../edu/wpi/first/wpilibj/PIDController.html" title="class in edu.wpi.first.wpilibj"><code>PIDController</code></a> used by this <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a></dd>
</dl>
</li>
</ul>
<a name="setSetpointRelative-double-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setSetpointRelative</h4>
<pre>public&nbsp;void&nbsp;setSetpointRelative(double&nbsp;deltaSetpoint)</pre>
<div class="block">Adds the given value to the setpoint. If <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#setInputRange-double-double-"><code>setInputRange(...)</code></a> was used, then the bounds will still be honored by this method.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>deltaSetpoint</code> - the change in the setpoint</dd>
</dl>
</li>
</ul>
<a name="setSetpoint-double-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setSetpoint</h4>
<pre>protected&nbsp;void&nbsp;setSetpoint(double&nbsp;setpoint)</pre>
<div class="block">Sets the setpoint to the given value. If <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html#setInputRange-double-double-"><code>setInputRange(...)</code></a> was called, then the given setpoint will be trimmed to fit within the
 range.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>setpoint</code> - the new setpoint</dd>
</dl>
</li>
</ul>
<a name="getSetpoint--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getSetpoint</h4>
<pre>protected&nbsp;double&nbsp;getSetpoint()</pre>
<div class="block">Returns the setpoint.</div>
<dl>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>the setpoint</dd>
</dl>
</li>
</ul>
<a name="getPosition--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getPosition</h4>
<pre>protected&nbsp;double&nbsp;getPosition()</pre>
<div class="block">Returns the current position.</div>
<dl>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>the current position</dd>
</dl>
</li>
</ul>
<a name="setInputRange-double-double-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setInputRange</h4>
<pre>protected&nbsp;void&nbsp;setInputRange(double&nbsp;minimumInput,
                             double&nbsp;maximumInput)</pre>
<div class="block">Sets the maximum and minimum values expected from the input and setpoint.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>minimumInput</code> - the minimum value expected from the input and setpoint</dd>
<dd><code>maximumInput</code> - the maximum value expected from the input and setpoint</dd>
</dl>
</li>
</ul>
<a name="returnPIDInput--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>returnPIDInput</h4>
<pre>protected abstract&nbsp;double&nbsp;returnPIDInput()</pre>
<div class="block">Returns the input for the pid loop.

 <p>It returns the input for the pid loop, so if this command was based off of a gyro, then it
 should return the angle of the gyro.

 <p>All subclasses of <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> must override this method.

 <p>This method will be called in a different thread then the <a href="../../../../../edu/wpi/first/wpilibj/command/Scheduler.html" title="class in edu.wpi.first.wpilibj.command"><code>Scheduler</code></a> thread.</div>
<dl>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>the value the pid loop should use as input</dd>
</dl>
</li>
</ul>
<a name="usePIDOutput-double-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>usePIDOutput</h4>
<pre>protected abstract&nbsp;void&nbsp;usePIDOutput(double&nbsp;output)</pre>
<div class="block">Uses the value that the pid loop calculated. The calculated value is the "output" parameter.
 This method is a good time to set motor values, maybe something along the lines of
 <code>driveline.tankDrive(output, -output)</code>

 <p>All subclasses of <a href="../../../../../edu/wpi/first/wpilibj/command/PIDCommand.html" title="class in edu.wpi.first.wpilibj.command"><code>PIDCommand</code></a> must override this method.

 <p>This method will be called in a different thread then the <a href="../../../../../edu/wpi/first/wpilibj/command/Scheduler.html" title="class in edu.wpi.first.wpilibj.command"><code>Scheduler</code></a> thread.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>output</code> - the value the pid loop calculated</dd>
</dl>
</li>
</ul>
<a name="getSmartDashboardType--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getSmartDashboardType</h4>
<pre>public&nbsp;java.lang.String&nbsp;getSmartDashboardType()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface:&nbsp;<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>&nbsp;in interface&nbsp;<code><a href="../../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj">Sendable</a></code></dd>
<dt><span class="overrideSpecifyLabel">Overrides:</span></dt>
<dd><code><a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#getSmartDashboardType--">getSmartDashboardType</a></code>&nbsp;in class&nbsp;<code><a href="../../../../../edu/wpi/first/wpilibj/command/Command.html" title="class in edu.wpi.first.wpilibj.command">Command</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="blockListLast">
<li class="blockList">
<h4>initTable</h4>
<pre>public&nbsp;void&nbsp;initTable(<a href="../../../../../edu/wpi/first/networktables/NetworkTable.html" title="class in edu.wpi.first.networktables">NetworkTable</a>&nbsp;table)</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface:&nbsp;<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>&nbsp;in interface&nbsp;<code><a href="../../../../../edu/wpi/first/wpilibj/Sendable.html" title="interface in edu.wpi.first.wpilibj">Sendable</a></code></dd>
<dt><span class="overrideSpecifyLabel">Overrides:</span></dt>
<dd><code><a href="../../../../../edu/wpi/first/wpilibj/command/Command.html#initTable-edu.wpi.first.networktables.NetworkTable-">initTable</a></code>&nbsp;in class&nbsp;<code><a href="../../../../../edu/wpi/first/wpilibj/command/Command.html" title="class in edu.wpi.first.wpilibj.command">Command</a></code></dd>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>table</code> - The table to put the values in.</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/command/InstantCommand.html" title="class in edu.wpi.first.wpilibj.command"><span class="typeNameLink">Prev&nbsp;Class</span></a></li>
<li><a href="../../../../../edu/wpi/first/wpilibj/command/PIDSubsystem.html" title="class in edu.wpi.first.wpilibj.command"><span class="typeNameLink">Next&nbsp;Class</span></a></li>
</ul>
<ul class="navList">
<li><a href="../../../../../index.html?edu/wpi/first/wpilibj/command/PIDCommand.html" target="_top">Frames</a></li>
<li><a href="PIDCommand.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>Field&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>