ardupilot/libraries/doc/html/class_p_i_d.html

529 lines
25 KiB
HTML

<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<title>ArduPilot Libraries: PID Class Reference</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="search/search.css" rel="stylesheet" type="text/css"/>
<script type="text/javaScript" src="search/search.js"></script>
<link href="doxygen.css" rel="stylesheet" type="text/css"/>
</head>
<body onload='searchBox.OnSelectItem(0);'>
<!-- Generated by Doxygen 1.7.1 -->
<div class="navigation" id="top">
<div class="tabs">
<ul class="tablist">
<li><a href="main.html"><span>Main&nbsp;Page</span></a></li>
<li><a href="namespaces.html"><span>Namespaces</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div class="tabs2">
<ul class="tablist">
<li><a href="annotated.html"><span>Class&nbsp;List</span></a></li>
<li><a href="classes.html"><span>Class&nbsp;Index</span></a></li>
<li><a href="hierarchy.html"><span>Class&nbsp;Hierarchy</span></a></li>
<li><a href="functions.html"><span>Class&nbsp;Members</span></a></li>
</ul>
</div>
</div>
<div class="header">
<div class="summary">
<a href="#pub-types">Public Types</a> &#124;
<a href="#pub-methods">Public Member Functions</a> &#124;
<a href="#pub-attribs">Public Attributes</a> </div>
<div class="headertitle">
<h1>PID Class Reference</h1> </div>
</div>
<div class="contents">
<!-- doxytag: class="PID" -->
<p>Object managing one <a class="el" href="class_p_i_d.html" title="Object managing one PID control.">PID</a> control.
<a href="#_details">More...</a></p>
<p><code>#include &lt;<a class="el" href="_p_i_d_8h_source.html">PID.h</a>&gt;</code></p>
<div class="dynheader">
Collaboration diagram for PID:</div>
<div class="dyncontent">
<div class="center"><img src="class_p_i_d__coll__graph.png" border="0" usemap="#_p_i_d_coll__map" alt="Collaboration graph"/></div>
<map name="_p_i_d_coll__map" id="_p_i_d_coll__map">
<area shape="rect" id="node2" href="class_a_p___e_e_p_r_o_m_b.html" title="Object for reading and writing to the EEPROM." alt="" coords="45,101,152,131"/></map>
<center><span class="legend">[<a target="top" href="graph_legend.html">legend</a>]</span></center></div>
<p><a href="class_p_i_d-members.html">List of all members.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="pub-types"></a>
Public Types</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">enum &nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#ab205c894ccd87f7f97c5d87c137df89e">storage_t</a> { <a class="el" href="class_p_i_d.html#ab205c894ccd87f7f97c5d87c137df89eaaf3ae4177b842acac49ae8340f62a915">STORE_OFF</a>,
<a class="el" href="class_p_i_d.html#ab205c894ccd87f7f97c5d87c137df89ea298eec9e3b8f13f44adbb491bcfb0d9a">STORE_EEPROM_FLOAT</a>,
<a class="el" href="class_p_i_d.html#ab205c894ccd87f7f97c5d87c137df89ea6f777cc5fe5af30de1ab385cd9354e12">STORE_EEPROM_UINT16</a>
}</td></tr>
<tr><td colspan="2"><h2><a name="pub-methods"></a>
Public Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a0311b6f7de348499ce24e53ba353514a">PID</a> ()</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a28a69de98b67fbf39417bee5dbe17db2">PID</a> (uint16_t address, <a class="el" href="class_p_i_d.html#ab205c894ccd87f7f97c5d87c137df89e">storage_t</a> storage=STORE_EEPROM_UINT16)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#af42f6af709ea5f484bcb92f43b041a1d">PID</a> (float *gain_array)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">long&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a485849289cc63b5e8c62f546912e461a">get_pid</a> (int32_t error, uint16_t dt, float scaler=1.0)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#ab5b56004fca57d7bd2a580a743775b74">reset_I</a> ()</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a3e8b0cc1984ac60db07cf55f45b71485">load_gains</a> ()</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a7fd5ea68386a5fdff983144decf552e6">save_gains</a> ()</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">float&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a10c0e53dc0b52ebb69bba0c8ac1db0aa">get_integrator</a> ()</td></tr>
<tr><td colspan="2"><div class="groupHeader">parameter accessors</div></td></tr>
<tr><td colspan="2"><div class="groupText"><p><a class="anchor" id="amgrp47f497b4757490ed399ca3240ec92a26"></a> </p>
</div></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">float&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a2dd3c39db6d37f4717bd0c492dc375fc">kP</a> ()</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">float&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a7f502cac90ea0dfcf82c15df85c8c2e2">kI</a> ()</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">float&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#ada7ca5447359196169af5141acdd767a">kD</a> ()</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">float&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#ae95642565b4b814ad8ef7f121168f749">imax</a> ()</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a6a455ccfa83bca050ee21a41e5d26604">kP</a> (const float v)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#aac61f98c9ae29d0321cfe004923ba793">kI</a> (const float v)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#aca5be548cd47219d246e9509bd606bd1">kD</a> (const float v)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a63b9060a9e086d5d1faecf53764cc579">imax</a> (const float v)</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#a1116e2ccdf958659f3575b8aaa2f1c36">address</a> (const uint16_t v)</td></tr>
<tr><td colspan="2"><h2><a name="pub-attribs"></a>
Public Attributes</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">enum <a class="el" href="class_p_i_d.html#ab205c894ccd87f7f97c5d87c137df89e">PID::storage_t</a>&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="class_p_i_d.html#af403c0149432f89b6f1f2117007b2f9f">_storage</a></td></tr>
</table>
<hr/><a name="_details"></a><h2>Detailed Description</h2>
<p>Object managing one <a class="el" href="class_p_i_d.html" title="Object managing one PID control.">PID</a> control. </p>
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00014">14</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
<hr/><h2>Member Enumeration Documentation</h2>
<a class="anchor" id="ab205c894ccd87f7f97c5d87c137df89e"></a><!-- doxytag: member="PID::storage_t" ref="ab205c894ccd87f7f97c5d87c137df89e" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">enum <a class="el" href="class_p_i_d.html#ab205c894ccd87f7f97c5d87c137df89e">PID::storage_t</a></td>
</tr>
</table>
</div>
<div class="memdoc">
<dl><dt><b>Enumerator: </b></dt><dd><table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><em><a class="anchor" id="ab205c894ccd87f7f97c5d87c137df89eaaf3ae4177b842acac49ae8340f62a915"></a><!-- doxytag: member="STORE_OFF" ref="ab205c894ccd87f7f97c5d87c137df89eaaf3ae4177b842acac49ae8340f62a915" args="" -->STORE_OFF</em>&nbsp;</td><td>
</td></tr>
<tr><td valign="top"><em><a class="anchor" id="ab205c894ccd87f7f97c5d87c137df89ea298eec9e3b8f13f44adbb491bcfb0d9a"></a><!-- doxytag: member="STORE_EEPROM_FLOAT" ref="ab205c894ccd87f7f97c5d87c137df89ea298eec9e3b8f13f44adbb491bcfb0d9a" args="" -->STORE_EEPROM_FLOAT</em>&nbsp;</td><td>
</td></tr>
<tr><td valign="top"><em><a class="anchor" id="ab205c894ccd87f7f97c5d87c137df89ea6f777cc5fe5af30de1ab385cd9354e12"></a><!-- doxytag: member="STORE_EEPROM_UINT16" ref="ab205c894ccd87f7f97c5d87c137df89ea6f777cc5fe5af30de1ab385cd9354e12" args="" -->STORE_EEPROM_UINT16</em>&nbsp;</td><td>
</td></tr>
</table>
</dd>
</dl>
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00018">18</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<hr/><h2>Constructor &amp; Destructor Documentation</h2>
<a class="anchor" id="a0311b6f7de348499ce24e53ba353514a"></a><!-- doxytag: member="PID::PID" ref="a0311b6f7de348499ce24e53ba353514a" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">PID::PID </td>
<td>(</td>
<td class="paramname"></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Constructor</p>
<p>A <a class="el" href="class_p_i_d.html" title="Object managing one PID control.">PID</a> constructed in this fashion does not support save/restore. Gains are managed internally, and must be read/written using the accessor functions. </p>
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00031">31</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="a28a69de98b67fbf39417bee5dbe17db2"></a><!-- doxytag: member="PID::PID" ref="a28a69de98b67fbf39417bee5dbe17db2" args="(uint16_t address, storage_t storage=STORE_EEPROM_UINT16)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">PID::PID </td>
<td>(</td>
<td class="paramtype">uint16_t&nbsp;</td>
<td class="paramname"> <em>address</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype"><a class="el" href="class_p_i_d.html#ab205c894ccd87f7f97c5d87c137df89e">storage_t</a>&nbsp;</td>
<td class="paramname"> <em>storage</em> = <code>STORE_EEPROM_UINT16</code></td><td>&nbsp;</td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td><td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Constructor</p>
<p>The <a class="el" href="class_p_i_d.html" title="Object managing one PID control.">PID</a> will manage gains internally, and the load/save functions will use 16 bytes of EEPROM storage to store gain values.</p>
<dl><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"></td><td valign="top"><em>address</em>&nbsp;</td><td>EEPROM base address at which <a class="el" href="class_p_i_d.html" title="Object managing one PID control.">PID</a> parameters are stored. </td></tr>
</table>
</dd>
</dl>
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00045">45</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="af42f6af709ea5f484bcb92f43b041a1d"></a><!-- doxytag: member="PID::PID" ref="af42f6af709ea5f484bcb92f43b041a1d" args="(float *gain_array)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">PID::PID </td>
<td>(</td>
<td class="paramtype">float *&nbsp;</td>
<td class="paramname"> <em>gain_array</em></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Constructor</p>
<p>Gain values for the <a class="el" href="class_p_i_d.html" title="Object managing one PID control.">PID</a> are managed externally; load/save are a NOP.</p>
<dl><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"></td><td valign="top"><em>gain_array</em>&nbsp;</td><td>Address of an array of float values. The array is used as kP, kI, kD and imax respectively. </td></tr>
</table>
</dd>
</dl>
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00062">62</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="a1116e2ccdf958659f3575b8aaa2f1c36"></a><!-- doxytag: member="PID::address" ref="a1116e2ccdf958659f3575b8aaa2f1c36" args="(const uint16_t v)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void PID::address </td>
<td>(</td>
<td class="paramtype">const uint16_t&nbsp;</td>
<td class="paramname"> <em>v</em></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00111">111</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="a10c0e53dc0b52ebb69bba0c8ac1db0aa"></a><!-- doxytag: member="PID::get_integrator" ref="a10c0e53dc0b52ebb69bba0c8ac1db0aa" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">float PID::get_integrator </td>
<td>(</td>
<td class="paramname"></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00118">118</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="a485849289cc63b5e8c62f546912e461a"></a><!-- doxytag: member="PID::get_pid" ref="a485849289cc63b5e8c62f546912e461a" args="(int32_t error, uint16_t dt, float scaler=1.0)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">long PID::get_pid </td>
<td>(</td>
<td class="paramtype">int32_t&nbsp;</td>
<td class="paramname"> <em>error</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">uint16_t&nbsp;</td>
<td class="paramname"> <em>dt</em>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">float&nbsp;</td>
<td class="paramname"> <em>scaler</em> = <code>1.0</code></td><td>&nbsp;</td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td><td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Iterate the <a class="el" href="class_p_i_d.html" title="Object managing one PID control.">PID</a>, return the new control value</p>
<p>Positive error produces positive output.</p>
<dl><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"></td><td valign="top"><em>error</em>&nbsp;</td><td>The measured error value </td></tr>
<tr><td valign="top"></td><td valign="top"><em>dt</em>&nbsp;</td><td>The time delta in milliseconds (note that update interval cannot be more than 65.535 seconds due to limited range of the data type). </td></tr>
<tr><td valign="top"></td><td valign="top"><em>scaler</em>&nbsp;</td><td>An arbitrary scale factor</td></tr>
</table>
</dd>
</dl>
<dl class="return"><dt><b>Returns:</b></dt><dd>The updated control output. </dd></dl>
<p>Definition at line <a class="el" href="_p_i_d_8cpp_source.html#l00018">18</a> of file <a class="el" href="_p_i_d_8cpp_source.html">PID.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ae95642565b4b814ad8ef7f121168f749"></a><!-- doxytag: member="PID::imax" ref="ae95642565b4b814ad8ef7f121168f749" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">float PID::imax </td>
<td>(</td>
<td class="paramname"></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00104">104</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="a63b9060a9e086d5d1faecf53764cc579"></a><!-- doxytag: member="PID::imax" ref="a63b9060a9e086d5d1faecf53764cc579" args="(const float v)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void PID::imax </td>
<td>(</td>
<td class="paramtype">const float&nbsp;</td>
<td class="paramname"> <em>v</em></td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_p_i_d_8cpp_source.html#l00061">61</a> of file <a class="el" href="_p_i_d_8cpp_source.html">PID.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="aca5be548cd47219d246e9509bd606bd1"></a><!-- doxytag: member="PID::kD" ref="aca5be548cd47219d246e9509bd606bd1" args="(const float v)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void PID::kD </td>
<td>(</td>
<td class="paramtype">const float&nbsp;</td>
<td class="paramname"> <em>v</em></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00108">108</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="ada7ca5447359196169af5141acdd767a"></a><!-- doxytag: member="PID::kD" ref="ada7ca5447359196169af5141acdd767a" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">float PID::kD </td>
<td>(</td>
<td class="paramname"></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00103">103</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="aac61f98c9ae29d0321cfe004923ba793"></a><!-- doxytag: member="PID::kI" ref="aac61f98c9ae29d0321cfe004923ba793" args="(const float v)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void PID::kI </td>
<td>(</td>
<td class="paramtype">const float&nbsp;</td>
<td class="paramname"> <em>v</em></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00107">107</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="a7f502cac90ea0dfcf82c15df85c8c2e2"></a><!-- doxytag: member="PID::kI" ref="a7f502cac90ea0dfcf82c15df85c8c2e2" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">float PID::kI </td>
<td>(</td>
<td class="paramname"></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00102">102</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="a2dd3c39db6d37f4717bd0c492dc375fc"></a><!-- doxytag: member="PID::kP" ref="a2dd3c39db6d37f4717bd0c492dc375fc" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">float PID::kP </td>
<td>(</td>
<td class="paramname"></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00101">101</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="a6a455ccfa83bca050ee21a41e5d26604"></a><!-- doxytag: member="PID::kP" ref="a6a455ccfa83bca050ee21a41e5d26604" args="(const float v)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void PID::kP </td>
<td>(</td>
<td class="paramtype">const float&nbsp;</td>
<td class="paramname"> <em>v</em></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00106">106</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="a3e8b0cc1984ac60db07cf55f45b71485"></a><!-- doxytag: member="PID::load_gains" ref="a3e8b0cc1984ac60db07cf55f45b71485" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void PID::load_gains </td>
<td>(</td>
<td class="paramname"></td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Load gain properties </p>
<p>Definition at line <a class="el" href="_p_i_d_8cpp_source.html#l00067">67</a> of file <a class="el" href="_p_i_d_8cpp_source.html">PID.cpp</a>.</p>
</div>
</div>
<a class="anchor" id="ab5b56004fca57d7bd2a580a743775b74"></a><!-- doxytag: member="PID::reset_I" ref="ab5b56004fca57d7bd2a580a743775b74" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void PID::reset_I </td>
<td>(</td>
<td class="paramname"></td>
<td>&nbsp;)&nbsp;</td>
<td><code> [inline]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Reset the <a class="el" href="class_p_i_d.html" title="Object managing one PID control.">PID</a> integrator </p>
<p>Definition at line <a class="el" href="_p_i_d_8h_source.html#l00085">85</a> of file <a class="el" href="_p_i_d_8h_source.html">PID.h</a>.</p>
</div>
</div>
<a class="anchor" id="a7fd5ea68386a5fdff983144decf552e6"></a><!-- doxytag: member="PID::save_gains" ref="a7fd5ea68386a5fdff983144decf552e6" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void PID::save_gains </td>
<td>(</td>
<td class="paramname"></td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>Save gain properties </p>
<p>Definition at line <a class="el" href="_p_i_d_8cpp_source.html#l00097">97</a> of file <a class="el" href="_p_i_d_8cpp_source.html">PID.cpp</a>.</p>
</div>
</div>
<hr/><h2>Member Data Documentation</h2>
<a class="anchor" id="af403c0149432f89b6f1f2117007b2f9f"></a><!-- doxytag: member="PID::_storage" ref="af403c0149432f89b6f1f2117007b2f9f" args="" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">enum <a class="el" href="class_p_i_d.html#ab205c894ccd87f7f97c5d87c137df89e">PID::storage_t</a> <a class="el" href="class_p_i_d.html#af403c0149432f89b6f1f2117007b2f9f">PID::_storage</a></td>
</tr>
</table>
</div>
<div class="memdoc">
</div>
</div>
<hr/>The documentation for this class was generated from the following files:<ul>
<li>/home/jgoppert/Projects/ap/libraries/PID/<a class="el" href="_p_i_d_8h_source.html">PID.h</a></li>
<li>/home/jgoppert/Projects/ap/libraries/PID/<a class="el" href="_p_i_d_8cpp_source.html">PID.cpp</a></li>
</ul>
</div>
<hr class="footer"/><address class="footer"><small>
Generated for ArduPilot Libraries by&nbsp;<a href="http://www.doxygen.org/index.html"><img class="footer" src="doxygen.png" alt="doxygen"/></a></small></address>
</body>
</html>