wh1ter0se/PowerUp-2018

View on GitHub
wpilib18/java/current/javadoc/edu/wpi/first/wpilibj/PWM.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:53 EDT 2017 -->
<title>PWM (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="PWM (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,"i12":10,"i13":10,"i14":10,"i15":10,"i16":10,"i17":10,"i18":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/Preferences.html" title="class in edu.wpi.first.wpilibj"><span class="typeNameLink">Prev&nbsp;Class</span></a></li>
<li><a href="../../../../edu/wpi/first/wpilibj/PWM.PeriodMultiplier.html" title="enum 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/PWM.html" target="_top">Frames</a></li>
<li><a href="PWM.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><a href="#nested.class.summary">Nested</a>&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 PWM" class="title">Class PWM</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.PWM</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/Sendable.html" title="interface in edu.wpi.first.wpilibj">Sendable</a></dd>
</dl>
<dl>
<dt>Direct Known Subclasses:</dt>
<dd><a href="../../../../edu/wpi/first/wpilibj/SafePWM.html" title="class in edu.wpi.first.wpilibj">SafePWM</a>, <a href="../../../../edu/wpi/first/wpilibj/Servo.html" title="class in edu.wpi.first.wpilibj">Servo</a></dd>
</dl>
<hr>
<br>
<pre>public class <span class="typeNameLabel">PWM</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/livewindow/LiveWindowSendable.html" title="interface in edu.wpi.first.wpilibj.livewindow">LiveWindowSendable</a></pre>
<div class="block">Class implements the PWM generation in the FPGA.

 <p>The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They are mapped to
 the hardware dependent values, in this case 0-2000 for the FPGA. Changes are immediately sent to
 the FPGA, and the update occurs at the next FPGA cycle (5.005ms). There is no delay.

 <p>As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-2000 values as follows: - 2000 =
 maximum pulse width - 1999 to 1001 = linear scaling from "full forward" to "center" - 1000 =
 center value - 999 to 2 = linear scaling from "center" to "full reverse" - 1 = minimum pulse
 width (currently .5ms) - 0 = disabled (i.e. PWM output is held low)</div>
</li>
</ul>
</div>
<div class="summary">
<ul class="blockList">
<li class="blockList">
<!-- ======== NESTED CLASS SUMMARY ======== -->
<ul class="blockList">
<li class="blockList"><a name="nested.class.summary">
<!--   -->
</a>
<h3>Nested Class Summary</h3>
<table class="memberSummary" border="0" cellpadding="3" cellspacing="0" summary="Nested Class Summary table, listing nested classes, and an explanation">
<caption><span>Nested Classes</span><span class="tabEnd">&nbsp;</span></caption>
<tr>
<th class="colFirst" scope="col">Modifier and Type</th>
<th class="colLast" scope="col">Class and Description</th>
</tr>
<tr class="altColor">
<td class="colFirst"><code>static class&nbsp;</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.PeriodMultiplier.html" title="enum in edu.wpi.first.wpilibj">PWM.PeriodMultiplier</a></span></code>
<div class="block">Represents the amount to multiply the minimum servo-pulse pwm period by.</div>
</td>
</tr>
</table>
</li>
</ul>
<!-- =========== 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/PWM.html#PWM-int-">PWM</a></span>(int&nbsp;channel)</code>
<div class="block">Allocate a PWM given a channel.</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/PWM.html#enableDeadbandElimination-boolean-">enableDeadbandElimination</a></span>(boolean&nbsp;eliminateDeadband)</code>
<div class="block">Optionally eliminate the deadband from a speed controller.</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/PWM.html#free--">free</a></span>()</code>
<div class="block">Free the PWM channel.</div>
</td>
</tr>
<tr id="i2" class="altColor">
<td class="colFirst"><code>int</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#getChannel--">getChannel</a></span>()</code>
<div class="block">Gets the channel number associated with the PWM Object.</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/PWM.html#getPosition--">getPosition</a></span>()</code>
<div class="block">Get the PWM value in terms of a position.</div>
</td>
</tr>
<tr id="i4" class="altColor">
<td class="colFirst"><code>int</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#getRaw--">getRaw</a></span>()</code>
<div class="block">Get the PWM value directly from the hardware.</div>
</td>
</tr>
<tr id="i5" class="rowColor">
<td class="colFirst"><code><a href="../../../../edu/wpi/first/wpilibj/PWMConfigDataResult.html" title="class in edu.wpi.first.wpilibj">PWMConfigDataResult</a></code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#getRawBounds--">getRawBounds</a></span>()</code>
<div class="block">Gets the bounds on the PWM pulse widths.</div>
</td>
</tr>
<tr id="i6" class="altColor">
<td class="colFirst"><code>java.lang.String</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.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="i7" class="rowColor">
<td class="colFirst"><code>double</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#getSpeed--">getSpeed</a></span>()</code>
<div class="block">Get the PWM value in terms of speed.</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/PWM.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;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="i9" class="rowColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#setBounds-double-double-double-double-double-">setBounds</a></span>(double&nbsp;max,
         double&nbsp;deadbandMax,
         double&nbsp;center,
         double&nbsp;deadbandMin,
         double&nbsp;min)</code>
<div class="block">Set the bounds on the PWM pulse widths.</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/PWM.html#setDisabled--">setDisabled</a></span>()</code>
<div class="block">Temporarily disables the PWM output.</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/PWM.html#setPeriodMultiplier-edu.wpi.first.wpilibj.PWM.PeriodMultiplier-">setPeriodMultiplier</a></span>(<a href="../../../../edu/wpi/first/wpilibj/PWM.PeriodMultiplier.html" title="enum in edu.wpi.first.wpilibj">PWM.PeriodMultiplier</a>&nbsp;mult)</code>
<div class="block">Slow down the PWM signal for old devices.</div>
</td>
</tr>
<tr id="i12" class="altColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#setPosition-double-">setPosition</a></span>(double&nbsp;pos)</code>
<div class="block">Set the PWM value based on a position.</div>
</td>
</tr>
<tr id="i13" class="rowColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#setRaw-int-">setRaw</a></span>(int&nbsp;value)</code>
<div class="block">Set the PWM value directly to the hardware.</div>
</td>
</tr>
<tr id="i14" class="altColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#setSpeed-double-">setSpeed</a></span>(double&nbsp;speed)</code>
<div class="block">Set the PWM value based on a speed.</div>
</td>
</tr>
<tr id="i15" class="rowColor">
<td class="colFirst"><code>protected void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#setZeroLatch--">setZeroLatch</a></span>()</code>&nbsp;</td>
</tr>
<tr id="i16" class="altColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#startLiveWindowMode--">startLiveWindowMode</a></span>()</code>
<div class="block">Start having this sendable object automatically respond to value changes reflect the value on
 the table.</div>
</td>
</tr>
<tr id="i17" class="rowColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.html#stopLiveWindowMode--">stopLiveWindowMode</a></span>()</code>
<div class="block">Stop having this sendable object automatically respond to value changes.</div>
</td>
</tr>
<tr id="i18" class="altColor">
<td class="colFirst"><code>void</code></td>
<td class="colLast"><code><span class="memberNameLink"><a href="../../../../edu/wpi/first/wpilibj/PWM.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&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>
</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="PWM-int-">
<!--   -->
</a>
<ul class="blockListLast">
<li class="blockList">
<h4>PWM</h4>
<pre>public&nbsp;PWM(int&nbsp;channel)</pre>
<div class="block">Allocate a PWM given a channel.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>channel</code> - The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port</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&nbsp;void&nbsp;free()</pre>
<div class="block">Free the PWM channel.

 <p>Free the resource associated with the PWM channel and set the value to 0.</div>
<dl>
<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="enableDeadbandElimination-boolean-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>enableDeadbandElimination</h4>
<pre>public&nbsp;void&nbsp;enableDeadbandElimination(boolean&nbsp;eliminateDeadband)</pre>
<div class="block">Optionally eliminate the deadband from a speed controller.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>eliminateDeadband</code> - If true, set the motor curve on the Jaguar to eliminate the deadband
                          in the middle of the range. Otherwise, keep the full range without
                          modifying any values.</dd>
</dl>
</li>
</ul>
<a name="setBounds-double-double-double-double-double-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setBounds</h4>
<pre>public&nbsp;void&nbsp;setBounds(double&nbsp;max,
                      double&nbsp;deadbandMax,
                      double&nbsp;center,
                      double&nbsp;deadbandMin,
                      double&nbsp;min)</pre>
<div class="block">Set the bounds on the PWM pulse widths. This sets the bounds on the PWM values for a particular
 type of controller. The values determine the upper and lower speeds as well as the deadband
 bracket.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>max</code> - The max PWM pulse width in ms</dd>
<dd><code>deadbandMax</code> - The high end of the deadband range pulse width in ms</dd>
<dd><code>center</code> - The center (off) pulse width in ms</dd>
<dd><code>deadbandMin</code> - The low end of the deadband pulse width in ms</dd>
<dd><code>min</code> - The minimum pulse width in ms</dd>
</dl>
</li>
</ul>
<a name="getRawBounds--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getRawBounds</h4>
<pre>public&nbsp;<a href="../../../../edu/wpi/first/wpilibj/PWMConfigDataResult.html" title="class in edu.wpi.first.wpilibj">PWMConfigDataResult</a>&nbsp;getRawBounds()</pre>
<div class="block">Gets the bounds on the PWM pulse widths. This Gets the bounds on the PWM values for a
 particular type of controller. The values determine the upper and lower speeds as well
 as the deadband bracket.</div>
</li>
</ul>
<a name="getChannel--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getChannel</h4>
<pre>public&nbsp;int&nbsp;getChannel()</pre>
<div class="block">Gets the channel number associated with the PWM Object.</div>
<dl>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>The channel number.</dd>
</dl>
</li>
</ul>
<a name="setPosition-double-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setPosition</h4>
<pre>public&nbsp;void&nbsp;setPosition(double&nbsp;pos)</pre>
<div class="block">Set the PWM value based on a position.

 <p>This is intended to be used by servos.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>pos</code> - The position to set the servo between 0.0 and 1.0.</dd>
<dt><span class="simpleTagLabel">Pre-Condition</span></dt>
<dd>SetMaxPositivePwm() called., SetMinNegativePwm() called.</dd>
</dl>
</li>
</ul>
<a name="getPosition--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getPosition</h4>
<pre>public&nbsp;double&nbsp;getPosition()</pre>
<div class="block">Get the PWM value in terms of a position.

 <p>This is intended to be used by servos.</div>
<dl>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>The position the servo is set to between 0.0 and 1.0.</dd>
<dt><span class="simpleTagLabel">Pre-Condition</span></dt>
<dd>SetMaxPositivePwm() called., SetMinNegativePwm() called.</dd>
</dl>
</li>
</ul>
<a name="setSpeed-double-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setSpeed</h4>
<pre>public&nbsp;void&nbsp;setSpeed(double&nbsp;speed)</pre>
<div class="block">Set the PWM value based on a speed.

 <p>This is intended to be used by speed controllers.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>speed</code> - The speed to set the speed controller between -1.0 and 1.0.</dd>
<dt><span class="simpleTagLabel">Pre-Condition</span></dt>
<dd>SetMaxPositivePwm() called., SetMinPositivePwm() called., SetCenterPwm() called., SetMaxNegativePwm() called., SetMinNegativePwm() called.</dd>
</dl>
</li>
</ul>
<a name="getSpeed--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getSpeed</h4>
<pre>public&nbsp;double&nbsp;getSpeed()</pre>
<div class="block">Get the PWM value in terms of speed.

 <p>This is intended to be used by speed controllers.</div>
<dl>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>The most recently set speed between -1.0 and 1.0.</dd>
<dt><span class="simpleTagLabel">Pre-Condition</span></dt>
<dd>SetMaxPositivePwm() called., SetMinPositivePwm() called., SetMaxNegativePwm() called., SetMinNegativePwm() called.</dd>
</dl>
</li>
</ul>
<a name="setRaw-int-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setRaw</h4>
<pre>public&nbsp;void&nbsp;setRaw(int&nbsp;value)</pre>
<div class="block">Set the PWM value directly to the hardware.

 <p>Write a raw value to a PWM channel.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>value</code> - Raw PWM value. Range 0 - 255.</dd>
</dl>
</li>
</ul>
<a name="getRaw--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>getRaw</h4>
<pre>public&nbsp;int&nbsp;getRaw()</pre>
<div class="block">Get the PWM value directly from the hardware.

 <p>Read a raw value from a PWM channel.</div>
<dl>
<dt><span class="returnLabel">Returns:</span></dt>
<dd>Raw PWM control value. Range: 0 - 255.</dd>
</dl>
</li>
</ul>
<a name="setDisabled--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setDisabled</h4>
<pre>public&nbsp;void&nbsp;setDisabled()</pre>
<div class="block">Temporarily disables the PWM output. The next set call will reenable
 the output.</div>
</li>
</ul>
<a name="setPeriodMultiplier-edu.wpi.first.wpilibj.PWM.PeriodMultiplier-">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setPeriodMultiplier</h4>
<pre>public&nbsp;void&nbsp;setPeriodMultiplier(<a href="../../../../edu/wpi/first/wpilibj/PWM.PeriodMultiplier.html" title="enum in edu.wpi.first.wpilibj">PWM.PeriodMultiplier</a>&nbsp;mult)</pre>
<div class="block">Slow down the PWM signal for old devices.</div>
<dl>
<dt><span class="paramLabel">Parameters:</span></dt>
<dd><code>mult</code> - The period multiplier to apply to this channel</dd>
</dl>
</li>
</ul>
<a name="setZeroLatch--">
<!--   -->
</a>
<ul class="blockList">
<li class="blockList">
<h4>setZeroLatch</h4>
<pre>protected&nbsp;void&nbsp;setZeroLatch()</pre>
</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="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&nbsp;void&nbsp;initTable(<a href="../../../../edu/wpi/first/networktables/NetworkTable.html" title="class in edu.wpi.first.networktables">NetworkTable</a>&nbsp;subtable)</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="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&nbsp;void&nbsp;updateTable()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface:&nbsp;<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>&nbsp;in interface&nbsp;<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&nbsp;void&nbsp;startLiveWindowMode()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface:&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html#startLiveWindowMode--">LiveWindowSendable</a></code></span></div>
<div class="block">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>&nbsp;in interface&nbsp;<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&nbsp;void&nbsp;stopLiveWindowMode()</pre>
<div class="block"><span class="descfrmTypeLabel">Description copied from interface:&nbsp;<code><a href="../../../../edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.html#stopLiveWindowMode--">LiveWindowSendable</a></code></span></div>
<div class="block">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>&nbsp;in interface&nbsp;<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/Preferences.html" title="class in edu.wpi.first.wpilibj"><span class="typeNameLink">Prev&nbsp;Class</span></a></li>
<li><a href="../../../../edu/wpi/first/wpilibj/PWM.PeriodMultiplier.html" title="enum 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/PWM.html" target="_top">Frames</a></li>
<li><a href="PWM.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><a href="#nested.class.summary">Nested</a>&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>