mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-13 20:28:37 -04:00
8abc98be90
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1377 f9c3cf11-9bcb-44bc-f272-b75c42450872
391 lines
20 KiB
HTML
391 lines
20 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: IMU 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 Page</span></a></li>
|
|
<li><a href="pages.html"><span>Related Pages</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 List</span></a></li>
|
|
<li><a href="classes.html"><span>Class Index</span></a></li>
|
|
<li><a href="hierarchy.html"><span>Class Hierarchy</span></a></li>
|
|
<li><a href="functions.html"><span>Class Members</span></a></li>
|
|
</ul>
|
|
</div>
|
|
</div>
|
|
<div class="header">
|
|
<div class="summary">
|
|
<a href="#pub-types">Public Types</a> |
|
|
<a href="#pub-methods">Public Member Functions</a> |
|
|
<a href="#pub-attribs">Public Attributes</a> |
|
|
<a href="#pro-attribs">Protected Attributes</a> </div>
|
|
<div class="headertitle">
|
|
<h1>IMU Class Reference</h1> </div>
|
|
</div>
|
|
<div class="contents">
|
|
<!-- doxytag: class="IMU" -->
|
|
<p><code>#include <<a class="el" href="_i_m_u_8h_source.html">IMU.h</a>></code></p>
|
|
|
|
<p>Inherited by <a class="el" href="class_a_p___i_m_u___oilpan.html">AP_IMU_Oilpan</a>, and <a class="el" href="class_a_p___i_m_u___shim.html">AP_IMU_Shim</a>.</p>
|
|
<div class="dynheader">
|
|
Collaboration diagram for IMU:</div>
|
|
<div class="dyncontent">
|
|
<div class="center"><img src="class_i_m_u__coll__graph.png" border="0" usemap="#_i_m_u_coll__map" alt="Collaboration graph"/></div>
|
|
<map name="_i_m_u_coll__map" id="_i_m_u_coll__map">
|
|
<area shape="rect" id="node2" href="class_vector3.html" title="Vector3\< float \>" alt="" coords="5,5,133,35"/></map>
|
|
<center><span class="legend">[<a target="top" href="graph_legend.html">legend</a>]</span></center></div>
|
|
|
|
<p><a href="class_i_m_u-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 </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#aa0586fbba61e2a982c8607171a03f5c7">Start_style</a> { <a class="el" href="class_i_m_u.html#aa0586fbba61e2a982c8607171a03f5c7a424b5aaa81a970a788b293e6ae431d8a">COLD_START</a> = 0,
|
|
<a class="el" href="class_i_m_u.html#aa0586fbba61e2a982c8607171a03f5c7a966ab2a7917892dd74154eae066f6838">WARM_START</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"> </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#a5d36c5fa0688efe1a013679dbdcef4cc">IMU</a> ()</td></tr>
|
|
<tr><td class="mdescLeft"> </td><td class="mdescRight">Constructor. <a href="#a5d36c5fa0688efe1a013679dbdcef4cc"></a><br/></td></tr>
|
|
<tr><td class="memItemLeft" align="right" valign="top">virtual void </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#aeb47a3e26d28ac71abe05a61ce8b183a">init</a> (<a class="el" href="class_i_m_u.html#aa0586fbba61e2a982c8607171a03f5c7">Start_style</a> style)=0</td></tr>
|
|
<tr><td class="memItemLeft" align="right" valign="top">virtual void </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#aa966100a68326351a7aa91447c0cc609">init_accel</a> (<a class="el" href="class_i_m_u.html#aa0586fbba61e2a982c8607171a03f5c7">Start_style</a> style)=0</td></tr>
|
|
<tr><td class="memItemLeft" align="right" valign="top">virtual void </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#a445a56ed7d14574abcb877bef36e74ab">init_gyro</a> (<a class="el" href="class_i_m_u.html#aa0586fbba61e2a982c8607171a03f5c7">Start_style</a> style)=0</td></tr>
|
|
<tr><td class="memItemLeft" align="right" valign="top">virtual bool </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#a7867764689bc40d5561811b14a42edbd">update</a> (void)=0</td></tr>
|
|
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="class_vector3.html">Vector3f</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#aae81f4e2b32ec27d7c3fb1f6b74a177a">get_gyro</a> (void)</td></tr>
|
|
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="class_vector3.html">Vector3f</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#a8736c63185c19a8fadc86623fd4cd0c7">get_accel</a> (void)</td></tr>
|
|
<tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#a02cfc38e047c2f89032be7819014ff17">load_gyro_eeprom</a> (void)</td></tr>
|
|
<tr><td class="mdescLeft"> </td><td class="mdescRight">XXX backwards compat hack. <a href="#a02cfc38e047c2f89032be7819014ff17"></a><br/></td></tr>
|
|
<tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#ae3c6a3e904fb0490c79dd37495e4526a">load_accel_eeprom</a> (void)</td></tr>
|
|
<tr><td class="mdescLeft"> </td><td class="mdescRight">XXX backwards compat hack. <a href="#ae3c6a3e904fb0490c79dd37495e4526a"></a><br/></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">uint8_t </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#a1239aaa3224c964504f5ff1945950770">adc_constraints</a></td></tr>
|
|
<tr><td colspan="2"><h2><a name="pro-attribs"></a>
|
|
Protected Attributes</h2></td></tr>
|
|
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="class_vector3.html">Vector3f</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#aea1f8061c62fc5212895925157b06c74">_accel</a></td></tr>
|
|
<tr><td class="mdescLeft"> </td><td class="mdescRight">Most recent accelerometer reading obtained by update. <a href="#aea1f8061c62fc5212895925157b06c74"></a><br/></td></tr>
|
|
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="class_vector3.html">Vector3f</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="class_i_m_u.html#a33f0574d229be1b24acb99334e174709">_gyro</a></td></tr>
|
|
<tr><td class="mdescLeft"> </td><td class="mdescRight">Most recent gyro reading obtained by update. <a href="#a33f0574d229be1b24acb99334e174709"></a><br/></td></tr>
|
|
</table>
|
|
<hr/><a name="_details"></a><h2>Detailed Description</h2>
|
|
|
|
<p>Definition at line <a class="el" href="_i_m_u_8h_source.html#l00013">13</a> of file <a class="el" href="_i_m_u_8h_source.html">IMU.h</a>.</p>
|
|
<hr/><h2>Member Enumeration Documentation</h2>
|
|
<a class="anchor" id="aa0586fbba61e2a982c8607171a03f5c7"></a><!-- doxytag: member="IMU::Start_style" ref="aa0586fbba61e2a982c8607171a03f5c7" args="" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname">enum <a class="el" href="class_i_m_u.html#aa0586fbba61e2a982c8607171a03f5c7">IMU::Start_style</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="aa0586fbba61e2a982c8607171a03f5c7a424b5aaa81a970a788b293e6ae431d8a"></a><!-- doxytag: member="COLD_START" ref="aa0586fbba61e2a982c8607171a03f5c7a424b5aaa81a970a788b293e6ae431d8a" args="" -->COLD_START</em> </td><td>
|
|
</td></tr>
|
|
<tr><td valign="top"><em><a class="anchor" id="aa0586fbba61e2a982c8607171a03f5c7a966ab2a7917892dd74154eae066f6838"></a><!-- doxytag: member="WARM_START" ref="aa0586fbba61e2a982c8607171a03f5c7a966ab2a7917892dd74154eae066f6838" args="" -->WARM_START</em> </td><td>
|
|
</td></tr>
|
|
</table>
|
|
</dd>
|
|
</dl>
|
|
|
|
<p>Definition at line <a class="el" href="_i_m_u_8h_source.html#l00020">20</a> of file <a class="el" href="_i_m_u_8h_source.html">IMU.h</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<hr/><h2>Constructor & Destructor Documentation</h2>
|
|
<a class="anchor" id="a5d36c5fa0688efe1a013679dbdcef4cc"></a><!-- doxytag: member="IMU::IMU" ref="a5d36c5fa0688efe1a013679dbdcef4cc" args="()" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname">IMU::IMU </td>
|
|
<td>(</td>
|
|
<td class="paramname"></td>
|
|
<td> ) </td>
|
|
<td><code> [inline]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
|
|
<p>Constructor. </p>
|
|
|
|
<p>Definition at line <a class="el" href="_i_m_u_8h_source.html#l00018">18</a> of file <a class="el" href="_i_m_u_8h_source.html">IMU.h</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<hr/><h2>Member Function Documentation</h2>
|
|
<a class="anchor" id="a8736c63185c19a8fadc86623fd4cd0c7"></a><!-- doxytag: member="IMU::get_accel" ref="a8736c63185c19a8fadc86623fd4cd0c7" args="(void)" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname"><a class="el" href="class_vector3.html">Vector3f</a> IMU::get_accel </td>
|
|
<td>(</td>
|
|
<td class="paramtype">void </td>
|
|
<td class="paramname"></td>
|
|
<td> ) </td>
|
|
<td><code> [inline]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
<p>Fetch the current accelerometer values</p>
|
|
<dl class="return"><dt><b>Returns:</b></dt><dd>vector of current accelerations in m/s/s </dd></dl>
|
|
|
|
<p>Definition at line <a class="el" href="_i_m_u_8h_source.html#l00075">75</a> of file <a class="el" href="_i_m_u_8h_source.html">IMU.h</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<a class="anchor" id="aae81f4e2b32ec27d7c3fb1f6b74a177a"></a><!-- doxytag: member="IMU::get_gyro" ref="aae81f4e2b32ec27d7c3fb1f6b74a177a" args="(void)" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname"><a class="el" href="class_vector3.html">Vector3f</a> IMU::get_gyro </td>
|
|
<td>(</td>
|
|
<td class="paramtype">void </td>
|
|
<td class="paramname"></td>
|
|
<td> ) </td>
|
|
<td><code> [inline]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
<p>Fetch the current gyro values</p>
|
|
<dl class="return"><dt><b>Returns:</b></dt><dd>vector of rotational rates in radians/sec </dd></dl>
|
|
|
|
<p>Definition at line <a class="el" href="_i_m_u_8h_source.html#l00069">69</a> of file <a class="el" href="_i_m_u_8h_source.html">IMU.h</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<a class="anchor" id="aeb47a3e26d28ac71abe05a61ce8b183a"></a><!-- doxytag: member="IMU::init" ref="aeb47a3e26d28ac71abe05a61ce8b183a" args="(Start_style style)=0" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname">virtual void IMU::init </td>
|
|
<td>(</td>
|
|
<td class="paramtype"><a class="el" href="class_i_m_u.html#aa0586fbba61e2a982c8607171a03f5c7">Start_style</a> </td>
|
|
<td class="paramname"> <em>style</em></td>
|
|
<td> ) </td>
|
|
<td><code> [pure virtual]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
<p>Perform startup initialisation.</p>
|
|
<p>Called to initialise the state of the <a class="el" href="class_i_m_u.html">IMU</a>.</p>
|
|
<p>For COLD_START, implementations using real sensors can assume that the airframe is stationary and nominally oriented.</p>
|
|
<p>For WARM_START, no assumptions should be made about the orientation or motion of the airframe. Calibration should be as for the previous COLD_START call.</p>
|
|
<dl><dt><b>Parameters:</b></dt><dd>
|
|
<table border="0" cellspacing="2" cellpadding="0">
|
|
<tr><td valign="top"></td><td valign="top"><em>style</em> </td><td>The initialisation startup style. </td></tr>
|
|
</table>
|
|
</dd>
|
|
</dl>
|
|
|
|
<p>Implemented in <a class="el" href="class_a_p___i_m_u___oilpan.html#abc3ac9bdd9c8fb93e9dda339ae66ea71">AP_IMU_Oilpan</a>, and <a class="el" href="class_a_p___i_m_u___shim.html#aeb4c1f84b7e00ba6112e75dd5c8a346b">AP_IMU_Shim</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<a class="anchor" id="aa966100a68326351a7aa91447c0cc609"></a><!-- doxytag: member="IMU::init_accel" ref="aa966100a68326351a7aa91447c0cc609" args="(Start_style style)=0" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname">virtual void IMU::init_accel </td>
|
|
<td>(</td>
|
|
<td class="paramtype"><a class="el" href="class_i_m_u.html#aa0586fbba61e2a982c8607171a03f5c7">Start_style</a> </td>
|
|
<td class="paramname"> <em>style</em></td>
|
|
<td> ) </td>
|
|
<td><code> [pure virtual]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
<p>Perform startup initialisation for just the accelerometers.</p>
|
|
<dl class="note"><dt><b>Note:</b></dt><dd>This should not be called unless init has previously been called, as init may perform other work.</dd></dl>
|
|
<dl><dt><b>Parameters:</b></dt><dd>
|
|
<table border="0" cellspacing="2" cellpadding="0">
|
|
<tr><td valign="top"></td><td valign="top"><em>style</em> </td><td>The initialisation startup style. </td></tr>
|
|
</table>
|
|
</dd>
|
|
</dl>
|
|
|
|
<p>Implemented in <a class="el" href="class_a_p___i_m_u___oilpan.html#a8f258421660cdd01fbf945108514d657">AP_IMU_Oilpan</a>, and <a class="el" href="class_a_p___i_m_u___shim.html#ae49dccaf4fc2b3aa304a3769295f748e">AP_IMU_Shim</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<a class="anchor" id="a445a56ed7d14574abcb877bef36e74ab"></a><!-- doxytag: member="IMU::init_gyro" ref="a445a56ed7d14574abcb877bef36e74ab" args="(Start_style style)=0" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname">virtual void IMU::init_gyro </td>
|
|
<td>(</td>
|
|
<td class="paramtype"><a class="el" href="class_i_m_u.html#aa0586fbba61e2a982c8607171a03f5c7">Start_style</a> </td>
|
|
<td class="paramname"> <em>style</em></td>
|
|
<td> ) </td>
|
|
<td><code> [pure virtual]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
<p>Perform cold-start initialisation for just the gyros.</p>
|
|
<dl class="note"><dt><b>Note:</b></dt><dd>This should not be called unless init has previously been called, as init may perform other work</dd></dl>
|
|
<dl><dt><b>Parameters:</b></dt><dd>
|
|
<table border="0" cellspacing="2" cellpadding="0">
|
|
<tr><td valign="top"></td><td valign="top"><em>style</em> </td><td>The initialisation startup style. </td></tr>
|
|
</table>
|
|
</dd>
|
|
</dl>
|
|
|
|
<p>Implemented in <a class="el" href="class_a_p___i_m_u___oilpan.html#a21fdbf920ac0697dfe97b8f2d138bda0">AP_IMU_Oilpan</a>, and <a class="el" href="class_a_p___i_m_u___shim.html#a4e300b540ee13b6c62c996510a8c3ce2">AP_IMU_Shim</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<a class="anchor" id="ae3c6a3e904fb0490c79dd37495e4526a"></a><!-- doxytag: member="IMU::load_accel_eeprom" ref="ae3c6a3e904fb0490c79dd37495e4526a" args="(void)" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname">void IMU::load_accel_eeprom </td>
|
|
<td>(</td>
|
|
<td class="paramtype">void </td>
|
|
<td class="paramname"></td>
|
|
<td> ) </td>
|
|
<td><code> [inline]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
|
|
<p>XXX backwards compat hack. </p>
|
|
|
|
<p>Definition at line <a class="el" href="_i_m_u_8h_source.html#l00086">86</a> of file <a class="el" href="_i_m_u_8h_source.html">IMU.h</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<a class="anchor" id="a02cfc38e047c2f89032be7819014ff17"></a><!-- doxytag: member="IMU::load_gyro_eeprom" ref="a02cfc38e047c2f89032be7819014ff17" args="(void)" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname">void IMU::load_gyro_eeprom </td>
|
|
<td>(</td>
|
|
<td class="paramtype">void </td>
|
|
<td class="paramname"></td>
|
|
<td> ) </td>
|
|
<td><code> [inline]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
|
|
<p>XXX backwards compat hack. </p>
|
|
|
|
<p>Definition at line <a class="el" href="_i_m_u_8h_source.html#l00085">85</a> of file <a class="el" href="_i_m_u_8h_source.html">IMU.h</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<a class="anchor" id="a7867764689bc40d5561811b14a42edbd"></a><!-- doxytag: member="IMU::update" ref="a7867764689bc40d5561811b14a42edbd" args="(void)=0" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname">virtual bool IMU::update </td>
|
|
<td>(</td>
|
|
<td class="paramtype">void </td>
|
|
<td class="paramname"></td>
|
|
<td> ) </td>
|
|
<td><code> [pure virtual]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
<p>Give the <a class="el" href="class_i_m_u.html">IMU</a> some cycles to perform/fetch an update from its sensors.</p>
|
|
<dl class="return"><dt><b>Returns:</b></dt><dd>True if some state was updated. </dd></dl>
|
|
|
|
<p>Implemented in <a class="el" href="class_a_p___i_m_u___oilpan.html#a766a65169e94a095c6194e511558717d">AP_IMU_Oilpan</a>, and <a class="el" href="class_a_p___i_m_u___shim.html#a548d3f60980363ada611cf0cb4da382a">AP_IMU_Shim</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<hr/><h2>Member Data Documentation</h2>
|
|
<a class="anchor" id="aea1f8061c62fc5212895925157b06c74"></a><!-- doxytag: member="IMU::_accel" ref="aea1f8061c62fc5212895925157b06c74" args="" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname"><a class="el" href="class_vector3.html">Vector3f</a> <a class="el" href="class_i_m_u.html#aea1f8061c62fc5212895925157b06c74">IMU::_accel</a><code> [protected]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
|
|
<p>Most recent accelerometer reading obtained by update. </p>
|
|
|
|
<p>Definition at line <a class="el" href="_i_m_u_8h_source.html#l00090">90</a> of file <a class="el" href="_i_m_u_8h_source.html">IMU.h</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<a class="anchor" id="a33f0574d229be1b24acb99334e174709"></a><!-- doxytag: member="IMU::_gyro" ref="a33f0574d229be1b24acb99334e174709" args="" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname"><a class="el" href="class_vector3.html">Vector3f</a> <a class="el" href="class_i_m_u.html#a33f0574d229be1b24acb99334e174709">IMU::_gyro</a><code> [protected]</code></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
|
|
<p>Most recent gyro reading obtained by update. </p>
|
|
|
|
<p>Definition at line <a class="el" href="_i_m_u_8h_source.html#l00093">93</a> of file <a class="el" href="_i_m_u_8h_source.html">IMU.h</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<a class="anchor" id="a1239aaa3224c964504f5ff1945950770"></a><!-- doxytag: member="IMU::adc_constraints" ref="a1239aaa3224c964504f5ff1945950770" args="" -->
|
|
<div class="memitem">
|
|
<div class="memproto">
|
|
<table class="memname">
|
|
<tr>
|
|
<td class="memname">uint8_t <a class="el" href="class_i_m_u.html#a1239aaa3224c964504f5ff1945950770">IMU::adc_constraints</a></td>
|
|
</tr>
|
|
</table>
|
|
</div>
|
|
<div class="memdoc">
|
|
<p>A count of bad sensor readings</p>
|
|
<dl class="todo"><dt><b><a class="el" href="todo.html#_todo000001">Todo:</a></b></dt><dd>This should be renamed, as there's no guarantee that sensors are using ADCs, etc. </dd></dl>
|
|
|
|
<p>Definition at line <a class="el" href="_i_m_u_8h_source.html#l00082">82</a> of file <a class="el" href="_i_m_u_8h_source.html">IMU.h</a>.</p>
|
|
|
|
</div>
|
|
</div>
|
|
<hr/>The documentation for this class was generated from the following file:<ul>
|
|
<li><a class="el" href="_i_m_u_8h_source.html">IMU.h</a></li>
|
|
</ul>
|
|
</div>
|
|
<hr class="footer"/><address class="footer"><small>
|
|
Generated for ArduPilot Libraries by <a href="http://www.doxygen.org/index.html"><img class="footer" src="doxygen.png" alt="doxygen"/></a></small></address>
|
|
</body>
|
|
</html>
|