Sophie

Sophie

distrib > Fedora > 15 > i386 > by-pkgid > 2f6559b7006594cad03af173263c219e > files > 10343

mrpt-doc-0.9.4-0.1.20110110svn2383.fc15.i686.rpm

<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=iso-8859-1">
<title>The MRPT project: mrpt::bayes::TKF_options Struct Reference</title>
<link href="doxygen.css" rel="stylesheet" type="text/css">
<link href="tabs.css" rel="stylesheet" type="text/css">
</head><body>
<div align="left"><a href="http://www.mrpt.org/">Main MRPT website</a> &gt; <b>C++ reference</b> </div>
<div align="right">
<a href="index.html"><img border="0" src="mrpt_logo.png" alt="MRPT logo"></a>
</div>
<!-- Generated by Doxygen 1.7.2 -->
<script type="text/javascript"><!--
var searchBox = new SearchBox("searchBox", "search",false,'Search');
--></script>
<div class="navigation" id="top">
  <div class="tabs">
    <ul class="tablist">
      <li><a href="index.html"><span>Main&#160;Page</span></a></li>
      <li><a href="pages.html"><span>Related&#160;Pages</span></a></li>
      <li><a href="modules.html"><span>Modules</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>
      <li id="searchli">
        <div id="MSearchBox" class="MSearchBoxInactive">
          <span class="left">
            <form id="FSearchBox" action="search.php" method="get">
              <img id="MSearchSelect" src="search/mag.png" alt=""/>
              <input type="text" id="MSearchField" name="query" value="Search" size="20" accesskey="S" 
                     onfocus="searchBox.OnSearchFieldFocus(true)" 
                     onblur="searchBox.OnSearchFieldFocus(false)"/>
            </form>
          </span><span class="right"></span>
        </div>
      </li>
    </ul>
  </div>
  <div class="tabs2">
    <ul class="tablist">
      <li><a href="annotated.html"><span>Class&#160;List</span></a></li>
      <li><a href="classes.html"><span>Class&#160;Index</span></a></li>
      <li><a href="hierarchy.html"><span>Class&#160;Hierarchy</span></a></li>
      <li><a href="functions.html"><span>Class&#160;Members</span></a></li>
    </ul>
  </div>
  <div class="navpath">
    <ul>
      <li><a class="el" href="namespacemrpt.html">mrpt</a>      </li>
      <li><a class="el" href="namespacemrpt_1_1bayes.html">bayes</a>      </li>
      <li><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html">TKF_options</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#pub-methods">Public Member Functions</a> &#124;
<a href="#pub-attribs">Public Attributes</a>  </div>
  <div class="headertitle">
<h1>mrpt::bayes::TKF_options Struct Reference</h1>  </div>
</div>
<div class="contents">
<!-- doxytag: class="mrpt::bayes::TKF_options" --><!-- doxytag: inherits="mrpt::utils::CLoadableOptions" --><hr/><a name="_details"></a><h2>Detailed Description</h2>
<p>Generic options for the Kalman Filter algorithm in itself. </p>

<p>Definition at line <a class="el" href="_c_kalman_filter_capable_8h_source.html#l00071">71</a> of file <a class="el" href="_c_kalman_filter_capable_8h_source.html">CKalmanFilterCapable.h</a>.</p>

<p><code>#include &lt;<a class="el" href="_c_kalman_filter_capable_8h_source.html">mrpt/bayes/CKalmanFilterCapable.h</a>&gt;</code></p>
<!-- startSectionHeader --><div class="dynheader">
Inheritance diagram for mrpt::bayes::TKF_options:<!-- endSectionHeader --></div>
<!-- startSectionSummary --><!-- endSectionSummary --><!-- startSectionContent --><div class="dyncontent">
<div class="center"><img src="structmrpt_1_1bayes_1_1_t_k_f__options__inherit__graph.png" border="0" usemap="#mrpt_1_1bayes_1_1_t_k_f__options_inherit__map" alt="Inheritance graph"/></div>
<map name="mrpt_1_1bayes_1_1_t_k_f__options_inherit__map" id="mrpt_1_1bayes_1_1_t_k_f__options_inherit__map">
</map>
<center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center><!-- endSectionContent --></div>

<p><a href="structmrpt_1_1bayes_1_1_t_k_f__options-members.html">List of all members.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="pub-methods"></a>
Public Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a8f671abffa15c6b886f857e080d21ef8">TKF_options</a> ()</td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a77aca2947531c1be8389ea2824032beb">loadFromConfigFile</a> (const <a class="el" href="classmrpt_1_1utils_1_1_c_config_file_base.html">mrpt::utils::CConfigFileBase</a> &amp;source, const std::string &amp;section)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">This method load the options from a ".ini"-like file or memory-stored string list.  <a href="#a77aca2947531c1be8389ea2824032beb"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a796e800336b75baf4ec29dd1b583372c">dumpToTextStream</a> (<a class="el" href="classmrpt_1_1utils_1_1_c_stream.html">CStream</a> &amp;out) const </td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">This method must display clearly all the contents of the structure in textual form, sending it to a CStream.  <a href="#a796e800336b75baf4ec29dd1b583372c"></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"><a class="el" href="namespacemrpt_1_1bayes.html#a93ff73c3a01619f01d97fd80dff40d14">TKFMethod</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a136e211bf1136d8437ad907782c2967d">method</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The method to employ (default: kfEKFNaive)  <a href="#a136e211bf1136d8437ad907782c2967d"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a79d277e2e9ac720106e7665883aeb81d">verbose</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">If set to true timing and other information will be dumped during the execution (default=false)  <a href="#a79d277e2e9ac720106e7665883aeb81d"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">int&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a512bf4ff5350affab3d5e94c03b7da1a">IKF_iterations</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Number of refinement iterations, only for the IKF method.  <a href="#a512bf4ff5350affab3d5e94c03b7da1a"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a57b4a351be8de935f8c2c2357b3d8b5c">enable_profiler</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">If enabled (default=false), detailed timing information will be dumped to the console thru a CTimerLog at the end of the execution.  <a href="#a57b4a351be8de935f8c2c2357b3d8b5c"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#aa628121a80c83a8e7a75363df9536048">use_analytic_transition_jacobian</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">(default=true) If true, OnTransitionJacobian will be called; otherwise, the Jacobian will be estimated from a numeric approximation by calling several times to OnTransitionModel.  <a href="#aa628121a80c83a8e7a75363df9536048"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#abe0d010c6e68f8270175362293fbcc17">use_analytic_observation_jacobian</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">(default=true) If true, OnObservationJacobians will be called; otherwise, the Jacobian will be estimated from a numeric approximation by calling several times to OnObservationModel.  <a href="#abe0d010c6e68f8270175362293fbcc17"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">bool&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a00d30cee24c38bfc6ec470a573646675">debug_verify_analytic_jacobians</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">(default=false) If true, will compute all the Jacobians numerically and compare them to the analytical ones, throwing an exception on mismatch.  <a href="#a00d30cee24c38bfc6ec470a573646675"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">double&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a5239885ee4c9ed75c1c3d6966226cae2">debug_verify_analytic_jacobians_threshold</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">(default-1e-2) Sets the threshold for the difference between the analytic and the numerical jacobians  <a href="#a5239885ee4c9ed75c1c3d6966226cae2"></a><br/></td></tr>
</table>
<hr/><h2>Constructor &amp; Destructor Documentation</h2>
<a class="anchor" id="a8f671abffa15c6b886f857e080d21ef8"></a><!-- doxytag: member="mrpt::bayes::TKF_options::TKF_options" ref="a8f671abffa15c6b886f857e080d21ef8" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">mrpt::bayes::TKF_options::TKF_options </td>
          <td>(</td>
          <td class="paramname">&#160;)</td>
          <td></td>
        </tr>
      </table>
</div>
<div class="memdoc">

</div>
</div>
<hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="a796e800336b75baf4ec29dd1b583372c"></a><!-- doxytag: member="mrpt::bayes::TKF_options::dumpToTextStream" ref="a796e800336b75baf4ec29dd1b583372c" args="(CStream &amp;out) const " -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void mrpt::bayes::TKF_options::dumpToTextStream </td>
          <td>(</td>
          <td class="paramtype"><a class="el" href="classmrpt_1_1utils_1_1_c_stream.html">CStream</a> &amp;&#160;</td>
          <td class="paramname"> <em>out</em>&#160;)</td>
          <td> const<code> [virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>This method must display clearly all the contents of the structure in textual form, sending it to a CStream. </p>

<p>Implements <a class="el" href="classmrpt_1_1utils_1_1_c_loadable_options.html#adbe314b74deedfe953290ebf48750883">mrpt::utils::CLoadableOptions</a>.</p>

</div>
</div>
<a class="anchor" id="a77aca2947531c1be8389ea2824032beb"></a><!-- doxytag: member="mrpt::bayes::TKF_options::loadFromConfigFile" ref="a77aca2947531c1be8389ea2824032beb" args="(const mrpt::utils::CConfigFileBase &amp;source, const std::string &amp;section)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">void mrpt::bayes::TKF_options::loadFromConfigFile </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1utils_1_1_c_config_file_base.html">mrpt::utils::CConfigFileBase</a> &amp;&#160;</td>
          <td class="paramname"> <em>source</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const std::string &amp;&#160;</td>
          <td class="paramname"> <em>section</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>This method load the options from a ".ini"-like file or memory-stored string list. </p>
<p>Only those parameters found in the given "section" and having the same name that the variable are loaded. Those not found in the file will stay with their previous values (usually the default values loaded at initialization). An example of an ".ini" <a href="file:">file:</a> </p>
<div class="fragment"><pre class="fragment">  [section]
        resolution=0.10         ; blah blah...
        modeSelection=1         ; 0=blah, 1=blah,...
</pre></div><dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1utils_1_1_c_loadable_options.html#a1ce8e0f241fe85f78095e23d37b2b635" title="Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile ob...">loadFromConfigFileName</a>, <a class="el" href="classmrpt_1_1utils_1_1_c_loadable_options.html#a913c3433af4564cedeb25e24ace1cf28" title="This method saves the options to a &quot;.ini&quot;-like file or memory-stored string list...">saveToConfigFile</a> </dd></dl>

<p>Implements <a class="el" href="classmrpt_1_1utils_1_1_c_loadable_options.html#ae2373fce5f2c8d3f0bdad21433becad2">mrpt::utils::CLoadableOptions</a>.</p>

</div>
</div>
<hr/><h2>Member Data Documentation</h2>
<a class="anchor" id="a00d30cee24c38bfc6ec470a573646675"></a><!-- doxytag: member="mrpt::bayes::TKF_options::debug_verify_analytic_jacobians" ref="a00d30cee24c38bfc6ec470a573646675" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">bool <a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a00d30cee24c38bfc6ec470a573646675">mrpt::bayes::TKF_options::debug_verify_analytic_jacobians</a></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>(default=false) If true, will compute all the Jacobians numerically and compare them to the analytical ones, throwing an exception on mismatch. </p>

<p>Definition at line <a class="el" href="_c_kalman_filter_capable_8h_source.html#l00088">88</a> of file <a class="el" href="_c_kalman_filter_capable_8h_source.html">CKalmanFilterCapable.h</a>.</p>

</div>
</div>
<a class="anchor" id="a5239885ee4c9ed75c1c3d6966226cae2"></a><!-- doxytag: member="mrpt::bayes::TKF_options::debug_verify_analytic_jacobians_threshold" ref="a5239885ee4c9ed75c1c3d6966226cae2" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">double <a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a5239885ee4c9ed75c1c3d6966226cae2">mrpt::bayes::TKF_options::debug_verify_analytic_jacobians_threshold</a></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>(default-1e-2) Sets the threshold for the difference between the analytic and the numerical jacobians </p>

<p>Definition at line <a class="el" href="_c_kalman_filter_capable_8h_source.html#l00089">89</a> of file <a class="el" href="_c_kalman_filter_capable_8h_source.html">CKalmanFilterCapable.h</a>.</p>

</div>
</div>
<a class="anchor" id="a57b4a351be8de935f8c2c2357b3d8b5c"></a><!-- doxytag: member="mrpt::bayes::TKF_options::enable_profiler" ref="a57b4a351be8de935f8c2c2357b3d8b5c" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">bool <a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a57b4a351be8de935f8c2c2357b3d8b5c">mrpt::bayes::TKF_options::enable_profiler</a></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>If enabled (default=false), detailed timing information will be dumped to the console thru a CTimerLog at the end of the execution. </p>

<p>Definition at line <a class="el" href="_c_kalman_filter_capable_8h_source.html#l00085">85</a> of file <a class="el" href="_c_kalman_filter_capable_8h_source.html">CKalmanFilterCapable.h</a>.</p>

</div>
</div>
<a class="anchor" id="a512bf4ff5350affab3d5e94c03b7da1a"></a><!-- doxytag: member="mrpt::bayes::TKF_options::IKF_iterations" ref="a512bf4ff5350affab3d5e94c03b7da1a" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">int <a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a512bf4ff5350affab3d5e94c03b7da1a">mrpt::bayes::TKF_options::IKF_iterations</a></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Number of refinement iterations, only for the IKF method. </p>

<p>Definition at line <a class="el" href="_c_kalman_filter_capable_8h_source.html#l00084">84</a> of file <a class="el" href="_c_kalman_filter_capable_8h_source.html">CKalmanFilterCapable.h</a>.</p>

</div>
</div>
<a class="anchor" id="a136e211bf1136d8437ad907782c2967d"></a><!-- doxytag: member="mrpt::bayes::TKF_options::method" ref="a136e211bf1136d8437ad907782c2967d" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="namespacemrpt_1_1bayes.html#a93ff73c3a01619f01d97fd80dff40d14">TKFMethod</a> <a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a136e211bf1136d8437ad907782c2967d">mrpt::bayes::TKF_options::method</a></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The method to employ (default: kfEKFNaive) </p>

<p>Definition at line <a class="el" href="_c_kalman_filter_capable_8h_source.html#l00082">82</a> of file <a class="el" href="_c_kalman_filter_capable_8h_source.html">CKalmanFilterCapable.h</a>.</p>

</div>
</div>
<a class="anchor" id="abe0d010c6e68f8270175362293fbcc17"></a><!-- doxytag: member="mrpt::bayes::TKF_options::use_analytic_observation_jacobian" ref="abe0d010c6e68f8270175362293fbcc17" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">bool <a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#abe0d010c6e68f8270175362293fbcc17">mrpt::bayes::TKF_options::use_analytic_observation_jacobian</a></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>(default=true) If true, OnObservationJacobians will be called; otherwise, the Jacobian will be estimated from a numeric approximation by calling several times to OnObservationModel. </p>

<p>Definition at line <a class="el" href="_c_kalman_filter_capable_8h_source.html#l00087">87</a> of file <a class="el" href="_c_kalman_filter_capable_8h_source.html">CKalmanFilterCapable.h</a>.</p>

</div>
</div>
<a class="anchor" id="aa628121a80c83a8e7a75363df9536048"></a><!-- doxytag: member="mrpt::bayes::TKF_options::use_analytic_transition_jacobian" ref="aa628121a80c83a8e7a75363df9536048" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">bool <a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#aa628121a80c83a8e7a75363df9536048">mrpt::bayes::TKF_options::use_analytic_transition_jacobian</a></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>(default=true) If true, OnTransitionJacobian will be called; otherwise, the Jacobian will be estimated from a numeric approximation by calling several times to OnTransitionModel. </p>

<p>Definition at line <a class="el" href="_c_kalman_filter_capable_8h_source.html#l00086">86</a> of file <a class="el" href="_c_kalman_filter_capable_8h_source.html">CKalmanFilterCapable.h</a>.</p>

</div>
</div>
<a class="anchor" id="a79d277e2e9ac720106e7665883aeb81d"></a><!-- doxytag: member="mrpt::bayes::TKF_options::verbose" ref="a79d277e2e9ac720106e7665883aeb81d" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">bool <a class="el" href="structmrpt_1_1bayes_1_1_t_k_f__options.html#a79d277e2e9ac720106e7665883aeb81d">mrpt::bayes::TKF_options::verbose</a></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>If set to true timing and other information will be dumped during the execution (default=false) </p>

<p>Definition at line <a class="el" href="_c_kalman_filter_capable_8h_source.html#l00083">83</a> of file <a class="el" href="_c_kalman_filter_capable_8h_source.html">CKalmanFilterCapable.h</a>.</p>

</div>
</div>
</div>
<br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.7.2</a> for MRPT 0.9.4 SVN: at Mon Jan 10 22:30:30 UTC 2011</td><td></td> <td width="100"> </td> <td width="150">  </td></tr> </table> </body></html>