📄 classmems_1_1_m_a_g___extended_kalman.html
字号:
<table class="memname"> <tr> <td class="memname">void mems::MAG_ExtendedKalman::setMeasurementNoise </td> <td>(</td> <td class="paramtype">MEMS_STD_VECTOR & </td> <td class="paramname"> <em>noise</em> </td> <td> ) </td> <td></td> </tr> </table></div><div class="memdoc"><p>Set the measurement noise for gyro, accelerometer and magnetometer. These values are generally empirically determined and <b>must be specified as a variance, not standard deviation.</b> Order of parameters is <gx, gy, gz, ax, ay, az, mx, my, mz> where g = gyro, a = accelerometer and m = magnetometer.<br> NOTE: the measurement noise covariance matrix is updated after each sample is processed. A call to setMeasurementNoise will completely reset the covariance matrix such that the specified noise values are along the diagonal, and the remaining values are zero.<p><dl compact><dt><b>Parameters:</b></dt><dd> <table border="0" cellspacing="2" cellpadding="0"> <tr><td valign="top"></td><td valign="top"><em>noise</em> </td><td>vector of measurement variances for each sensor</td></tr> </table></dl><dl class="see" compact><dt><b>See also:</b></dt><dd><a class="el" href="classmems_1_1_m_a_g___extended_kalman.html#e0222fd8a4bd0ecff4ba0fa656a9cef7">setProcessNoise()</a> <p><a class="el" href="_config_s_t_l_8h.html#a72efbfed31ceba6e18e11c0b742bb94">MEMS_STD_VECTOR</a> </dd></dl></div></div><p><a class="anchor" name="9f47d249f62fdba6ed9efda0fe54fed3"></a><!-- doxytag: member="mems::MAG_ExtendedKalman::getMeasurementNoiseCovariance" ref="9f47d249f62fdba6ed9efda0fe54fed3" args="()" --><div class="memitem"><div class="memproto"> <table class="memname"> <tr> <td class="memname">MEMS_STD_MATRIX mems::MAG_ExtendedKalman::getMeasurementNoiseCovariance </td> <td>(</td> <td class="paramname"> </td> <td> ) </td> <td></td> </tr> </table></div><div class="memdoc"><p>Returns the current measurement noise covariance matrix.<p><dl class="return" compact><dt><b>Returns:</b></dt><dd>The measurement noise covariance matrix</dd></dl><dl class="see" compact><dt><b>See also:</b></dt><dd><a class="el" href="_config_s_t_l_8h.html#4ccecb7b220e54be1d9e7ab09113a15f">MEMS_STD_MATRIX</a> </dd></dl></div></div><p><a class="anchor" name="cb1896a97c0888efa1183a3a154e9088"></a><!-- doxytag: member="mems::MAG_ExtendedKalman::processSample" ref="cb1896a97c0888efa1183a3a154e9088" args="(double delta, MEMS_STD_VECTOR &sample)" --><div class="memitem"><div class="memproto"> <table class="memname"> <tr> <td class="memname">MEMS_STD_VECTOR mems::MAG_ExtendedKalman::processSample </td> <td>(</td> <td class="paramtype">double </td> <td class="paramname"> <em>delta</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">MEMS_STD_VECTOR & </td> <td class="paramname"> <em>sample</em></td><td> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td><td></td> </tr> </table></div><div class="memdoc"><p>Process a sample of data and return the position data in quaterion format. The data sample is expected to be ordered as follows: <gx, gy, gz, ax, ay, az, mx, my, mz>. The resolution of the sample delta is the relative time between the current sample and the previous sample in seconds. The sample must be in the following units:<ul><li>Gyro: rad/s</li><li>Accelerometer: G's</li><li>Magnetometer: Gauss</li></ul><p><dl compact><dt><b>Parameters:</b></dt><dd> <table border="0" cellspacing="2" cellpadding="0"> <tr><td valign="top"></td><td valign="top"><em>delta</em> </td><td>time, in seconds, between the previous sample and the current sample </td></tr> <tr><td valign="top"></td><td valign="top"><em>sample</em> </td><td>data sample in units ordered as: <gx, gy, gz, ax, ay, az, mx, my, mz> </td></tr> </table></dl><dl class="return" compact><dt><b>Returns:</b></dt><dd>vector ordered as follows: <gx, gy, gz, qw, qx, qy, qz, bx, by, bz> where g = gyro in rad/s, q = normalized quaternion, b = gyro bias in rad.</dd></dl><dl class="see" compact><dt><b>See also:</b></dt><dd><a class="el" href="_config_s_t_l_8h.html#a72efbfed31ceba6e18e11c0b742bb94">MEMS_STD_VECTOR</a> </dd></dl></div></div><p><a class="anchor" name="aa5f5755aa5f249cab5e60bffcae7d9e"></a><!-- doxytag: member="mems::MAG_ExtendedKalman::processSample" ref="aa5f5755aa5f249cab5e60bffcae7d9e" args="(double delta, double gx, double gy, double gz, double ax, double ay, double az, double mx, double my, double mz)" --><div class="memitem"><div class="memproto"> <table class="memname"> <tr> <td class="memname">MEMS_STD_VECTOR mems::MAG_ExtendedKalman::processSample </td> <td>(</td> <td class="paramtype">double </td> <td class="paramname"> <em>delta</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>gx</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>gy</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>gz</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>ax</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>ay</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>az</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>mx</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>my</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>mz</em></td><td> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td><td></td> </tr> </table></div><div class="memdoc"><p>Process a sample of data and return the position data in quaterion format. The resolution of the sample delta is the relative time between the current sample and the previous sample in seconds. The sample must be in the following units:<ul><li>Gyro: rad/s</li><li>Accelerometer: G's</li><li>Magnetometer: Gauss</li></ul><p><dl compact><dt><b>Parameters:</b></dt><dd> <table border="0" cellspacing="2" cellpadding="0"> <tr><td valign="top"></td><td valign="top"><em>delta</em> </td><td>time, in seconds, between the previous sample and the current sample </td></tr> <tr><td valign="top"></td><td valign="top"><em>gx</em> </td><td>x-gyro angular rate (rad/s) </td></tr> <tr><td valign="top"></td><td valign="top"><em>gy</em> </td><td>y-gyro angular rate (rad/s) </td></tr> <tr><td valign="top"></td><td valign="top"><em>gz</em> </td><td>z-gyro angular rate (rad/s) </td></tr> <tr><td valign="top"></td><td valign="top"><em>ax</em> </td><td>x-accelerometer (G) </td></tr> <tr><td valign="top"></td><td valign="top"><em>ay</em> </td><td>y-accelerometer (G) </td></tr> <tr><td valign="top"></td><td valign="top"><em>az</em> </td><td>z-accelerometer (G) </td></tr> <tr><td valign="top"></td><td valign="top"><em>mx</em> </td><td>x-magnetometer (Gauss) </td></tr> <tr><td valign="top"></td><td valign="top"><em>my</em> </td><td>y-magnetometer (Gauss) </td></tr> <tr><td valign="top"></td><td valign="top"><em>mz</em> </td><td>z-magnetometer (Gauss)</td></tr> </table></dl><dl class="return" compact><dt><b>Returns:</b></dt><dd>vector ordered as follows: <gx, gy, gz, qw, qx, qy, qz, bx, by, bz> where g = gyro in rad/s, q = normalized quaternion, b = gyro bias in rad.</dd></dl><dl class="see" compact><dt><b>See also:</b></dt><dd><a class="el" href="_config_s_t_l_8h.html#a72efbfed31ceba6e18e11c0b742bb94">MEMS_STD_VECTOR</a> </dd></dl></div></div><p><a class="anchor" name="9ae86aed59bcb4be28436f14bbe82f2b"></a><!-- doxytag: member="mems::MAG_ExtendedKalman::getResidual" ref="9ae86aed59bcb4be28436f14bbe82f2b" args="()" --><div class="memitem"><div class="memproto"> <table class="memname"> <tr> <td class="memname">MEMS_STD_VECTOR mems::MAG_ExtendedKalman::getResidual </td> <td>(</td> <td class="paramname"> </td> <td> ) </td> <td></td> </tr> </table></div><div class="memdoc"><p>Returns the residual, or measurement innovation, which is defined as the discrepancy between the predicted measurement (x_hat_minus) and the actual measurement (z). A residual of zero means that the two are in complete agreement (see Welch/Bishop - Introduction to Kalman Filter). A 'zero' residual means the filter is predicting perfectly the next step in the state transition and that the filter is performing at its peak.<p><dl class="return" compact><dt><b>Returns:</b></dt><dd>The residual which is as follows: <gx, gy, gz, qw, qx, qy, qz> where g = gyro in rad/s, q = normalized quaternion.</dd></dl><dl class="see" compact><dt><b>See also:</b></dt><dd><a class="el" href="_config_s_t_l_8h.html#a72efbfed31ceba6e18e11c0b742bb94">MEMS_STD_VECTOR</a> </dd></dl></div></div><p><a class="anchor" name="360d4a7b1d98ac339fdd4dd2d4b4a15e"></a><!-- doxytag: member="mems::MAG_ExtendedKalman::quat2Euler" ref="360d4a7b1d98ac339fdd4dd2d4b4a15e" args="(double w, double x, double y, double z)" --><div class="memitem"><div class="memproto"> <table class="memname"> <tr> <td class="memname">MEMS_STD_VECTOR mems::MAG_ExtendedKalman::quat2Euler </td> <td>(</td> <td class="paramtype">double </td> <td class="paramname"> <em>w</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>x</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>y</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">double </td> <td class="paramname"> <em>z</em></td><td> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td><td></td> </tr> </table></div><div class="memdoc"><p>Normalized quaternion to Euler angle conversion. The euler angles are in the order in which they are to be applied: yaw(z-axis), pitch(y-axis), roll(x-axis) in the LOCAL coordinate system (CS). In the local CS the CS rotates with the device, and each new rotation is perfomed relative to new orientation of the coordinate system - not the earth-based coordinate system. An example would be: starting in the canonical position where device x/y/z matches with earth x/y/z, a +90 degree z-axis (yaw) rotation followed by a +90 degree rotation around the x-axis (roll) produces a device orientation such that the longitudinal axis (device x-axis) will be oriented east-west, or along the earth y axis, and on its side. If this same sequence was perfomed using a earth-based/global CS, the device will be oriented such that the device x-axis is aligned with the earth z-axis (north-south).<br> NOTE: The quaternion <b>must</b> be normalized.<p><dl compact><dt><b>Parameters:</b></dt><dd> <table border="0" cellspacing="2" cellpadding="0"> <tr><td valign="top"></td><td valign="top"><em>w</em> </td><td>quaternion w </td></tr> <tr><td valign="top"></td><td valign="top"><em>x</em> </td><td>quaternion x </td></tr> <tr><td valign="top"></td><td valign="top"><em>y</em> </td><td>quaternion y </td></tr> <tr><td valign="top"></td><td valign="top"><em>z</em> </td><td>quaternion z</td></tr> </table></dl><dl class="return" compact><dt><b>Returns:</b></dt><dd>3-element vector of euler angles, in radians, in the order in which they are to be applied (yaw, pitch, roll).</dd></dl><dl class="see" compact><dt><b>See also:</b></dt><dd><a class="el" href="_config_s_t_l_8h.html#a72efbfed31ceba6e18e11c0b742bb94">MEMS_STD_VECTOR</a> </dd></dl></div></div><p><hr>The documentation for this class was generated from the following file:<ul><li>C:/memsense/dev/C/Kalman/src/<a class="el" href="_m_a_g___extended_kalman_8h-source.html">MAG_ExtendedKalman.h</a></ul></div><hr size="1"><address style="text-align: right;"><small>Generated on Mon Mar 2 16:28:23 2009 for ExtendedKalman by <a href="http://www.doxygen.org/index.html"><img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address></body></html>
⌨️ 快捷键说明
复制代码
Ctrl + C
搜索代码
Ctrl + F
全屏模式
F11
切换主题
Ctrl + Shift + D
显示快捷键
?
增大字号
Ctrl + =
减小字号
Ctrl + -