ardupilot/libraries/doc/html/_navigation_8h_source.html

114 lines
14 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: /home/jgoppert/Projects/ap/libraries/AP_Navigation/Navigation.h Source File</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css"/>
</head>
<body>
<!-- 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><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div class="tabs2">
<ul class="tablist">
<li><a href="files.html"><span>File&nbsp;List</span></a></li>
<li><a href="globals.html"><span>File&nbsp;Members</span></a></li>
</ul>
</div>
<div class="header">
<div class="headertitle">
<h1>/home/jgoppert/Projects/ap/libraries/AP_Navigation/Navigation.h</h1> </div>
</div>
<div class="contents">
<a href="_navigation_8h.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001
<a name="l00002"></a>00002 <span class="preprocessor">#ifndef AP_NAVIGATION_h</span>
<a name="l00003"></a>00003 <span class="preprocessor"></span><span class="preprocessor">#define AP_NAVIGATION_h</span>
<a name="l00004"></a>00004 <span class="preprocessor"></span>
<a name="l00005"></a><a class="code" href="_navigation_8h.html#a295b82827f88bc8115c34cfbb4650690">00005</a> <span class="preprocessor">#define XTRACK_GAIN 10 // Amount to compensate for crosstrack (degrees/100 per meter)</span>
<a name="l00006"></a><a class="code" href="_navigation_8h.html#adfd3d7f59e272b76b8a1038f512862f0">00006</a> <span class="preprocessor"></span><span class="preprocessor">#define XTRACK_ENTRY_ANGLE 3000 // Max angle used to correct for track following degrees*100</span>
<a name="l00007"></a>00007 <span class="preprocessor"></span><span class="preprocessor">#include &lt;<a class="code" href="_g_p_s_8h.html" title="Interface definition for the various GPS drivers.">GPS.h</a>&gt;</span> <span class="comment">// ArduPilot GPS Library</span>
<a name="l00008"></a>00008 <span class="preprocessor">#include &quot;<a class="code" href="_waypoints_8h.html">Waypoints.h</a>&quot;</span> <span class="comment">// ArduPilot Waypoints Library</span>
<a name="l00009"></a>00009 <span class="preprocessor">#include &quot;<a class="code" href="_w_program_8h.html">WProgram.h</a>&quot;</span>
<a name="l00010"></a>00010
<a name="l00011"></a><a class="code" href="_navigation_8h.html#a2ecc28a0523643551285b16c189518a0">00011</a> <span class="preprocessor">#define T7 10000000</span>
<a name="l00012"></a>00012 <span class="preprocessor"></span>
<a name="l00013"></a><a class="code" href="class_navigation.html">00013</a> <span class="keyword">class </span><a class="code" href="class_navigation.html">Navigation</a> {
<a name="l00014"></a>00014 <span class="keyword">public</span>:
<a name="l00015"></a>00015 <a class="code" href="class_navigation.html#a128f871ef138c360fb2c73ffec72729f">Navigation</a>(<a class="code" href="class_g_p_s.html" title="Abstract base class for GPS receiver drivers.">GPS</a> *withGPS, <a class="code" href="class_waypoints.html">Waypoints</a> *withWP);
<a name="l00016"></a>00016
<a name="l00017"></a>00017 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a9d2b3544acc5bf511da32c3e6888acd5">update_gps</a>(<span class="keywordtype">void</span>); <span class="comment">// called 50 Hz</span>
<a name="l00018"></a>00018 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a55010dc9ffe03ecba91bbfbb4e8f190c">set_home</a>(<a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a> loc);
<a name="l00019"></a>00019 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a222cd205c6709681875cbb4efa2657f0">set_next_wp</a>(<a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a> loc);
<a name="l00020"></a>00020 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a7d1a2aec8970bd7c4a6f26b4a31f69b1">load_first_wp</a>(<span class="keywordtype">void</span>);
<a name="l00021"></a>00021 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a307d267e9ce8cc9c73e52dde8f02a5ca">load_wp_with_index</a>(uint8_t i);
<a name="l00022"></a>00022 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#ac1eb3234566b231e44a2a5fbc6d25ca9">load_home</a>(<span class="keywordtype">void</span>);
<a name="l00023"></a>00023 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a3cb86f630e37f5d41467a23a7a8cf831">return_to_home_with_alt</a>(uint32_t alt);
<a name="l00024"></a>00024
<a name="l00025"></a>00025 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a99a4fd20cd5e7a0bf0fd8cfa5272e79f">reload_wp</a>(<span class="keywordtype">void</span>);
<a name="l00026"></a>00026 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a360a3f5097cf11ba28f12df55031d7b0">load_wp_index</a>(uint8_t i);
<a name="l00027"></a>00027 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#ae916ccef7d89b09a972ceda58d5ef9b6">hold_location</a>();
<a name="l00028"></a>00028 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#ad205d021d42786775c6b7d7e9d3c16f4">set_wp</a>(<a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a> loc);
<a name="l00029"></a>00029
<a name="l00030"></a>00030 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a260152de551277ff2a980e63bbb14fbc">set_hold_course</a>(int16_t b); <span class="comment">// -1 deisables, 0-36000 enables</span>
<a name="l00031"></a>00031 int16_t <a class="code" href="class_navigation.html#a60d4bee672c92c1e4cced76089836ebf">get_hold_course</a>(<span class="keywordtype">void</span>);
<a name="l00032"></a>00032
<a name="l00033"></a>00033 int32_t <a class="code" href="class_navigation.html#ac05da5065688d7ef70452bbc4b8f8556">get_distance</a>(<a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a> *loc1, <a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a> *loc2);
<a name="l00034"></a>00034 int32_t <a class="code" href="class_navigation.html#acf7075f5eedf8f47ae88b7ae04bccb39">get_bearing</a>(<a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a> *loc1, <a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a> *loc2);
<a name="l00035"></a>00035 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a3719b4db98a8fdc08599eff7e8e819af">set_bearing_error</a>(int32_t error);
<a name="l00036"></a>00036
<a name="l00037"></a>00037 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#a9aba08c1a7b668b80f2f3df8795095b6">set_loiter_vector</a>(int16_t v);
<a name="l00038"></a>00038 <span class="keywordtype">void</span> <a class="code" href="class_navigation.html#ab1178280258ea8502960ffb5b4fb2815">update_crosstrack</a>(<span class="keywordtype">void</span>);
<a name="l00039"></a>00039
<a name="l00040"></a>00040 int32_t <a class="code" href="class_navigation.html#abda1088bf8790dbcd31687ad4daf05b1">wrap_180</a>(int32_t error); <span class="comment">// utility</span>
<a name="l00041"></a>00041 int32_t <a class="code" href="class_navigation.html#a5ae7eb15b8aa81aeb2e2771fec018d5f">wrap_360</a>(int32_t angle); <span class="comment">// utility</span>
<a name="l00042"></a>00042
<a name="l00043"></a><a class="code" href="class_navigation.html#a327b5eb6bd65c8b1678b50d1002d95cb">00043</a> int32_t <a class="code" href="class_navigation.html#a327b5eb6bd65c8b1678b50d1002d95cb">bearing</a>; <span class="comment">// deg * 100 : 0 to 360 current desired bearing to navigate</span>
<a name="l00044"></a><a class="code" href="class_navigation.html#a5131b103f30de83744a07575680ae8ec">00044</a> int32_t <a class="code" href="class_navigation.html#a5131b103f30de83744a07575680ae8ec">distance</a>; <span class="comment">// meters : distance plane to next waypoint</span>
<a name="l00045"></a><a class="code" href="class_navigation.html#a5c655bff9637ea00a3dc3650cc1cf4f5">00045</a> int32_t <a class="code" href="class_navigation.html#a5c655bff9637ea00a3dc3650cc1cf4f5">altitude_above_home</a>; <span class="comment">// meters * 100 relative to home position</span>
<a name="l00046"></a><a class="code" href="class_navigation.html#a820f2e9d1a143419eb8e92d76c5702b7">00046</a> int32_t <a class="code" href="class_navigation.html#a820f2e9d1a143419eb8e92d76c5702b7">total_distance</a>; <span class="comment">// meters : distance between waypoints</span>
<a name="l00047"></a><a class="code" href="class_navigation.html#a82c620baabad8049cc58fbe95a34890c">00047</a> int32_t <a class="code" href="class_navigation.html#a82c620baabad8049cc58fbe95a34890c">bearing_error</a>; <span class="comment">// deg * 100 : 18000 to -18000 </span>
<a name="l00048"></a><a class="code" href="class_navigation.html#a63e21494db8c2022f5ff488295f2f1fe">00048</a> int32_t <a class="code" href="class_navigation.html#a63e21494db8c2022f5ff488295f2f1fe">altitude_error</a>; <span class="comment">// deg * 100 : 18000 to -18000 </span>
<a name="l00049"></a>00049
<a name="l00050"></a><a class="code" href="class_navigation.html#a2e0bfad230d48a39926571d5d455f139">00050</a> int16_t <a class="code" href="class_navigation.html#a2e0bfad230d48a39926571d5d455f139">loiter_sum</a>;
<a name="l00051"></a><a class="code" href="class_navigation.html#aa4cb8fedae77c0028012bf8284bb6217">00051</a> <a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a> <a class="code" href="class_navigation.html#acaa6eea8382dda9ba39e0dc3960d5d37">home</a>, <a class="code" href="class_navigation.html#a4f1060bf77cfc499ec5d3169c4494095">location</a>, <a class="code" href="class_navigation.html#aa4cb8fedae77c0028012bf8284bb6217">prev_wp</a>, <a class="code" href="class_navigation.html#afd1dec04a84096681bf951df5edf72e0">next_wp</a>;
<a name="l00052"></a>00052
<a name="l00053"></a>00053 <span class="keyword">private</span>:
<a name="l00054"></a>00054 <span class="keywordtype">void</span> calc_int32_t_scaling(int32_t lat);
<a name="l00055"></a>00055 <span class="keywordtype">void</span> calc_bearing_error(<span class="keywordtype">void</span>);
<a name="l00056"></a>00056 <span class="keywordtype">void</span> calc_altitude_error(<span class="keywordtype">void</span>);
<a name="l00057"></a>00057 <span class="keywordtype">void</span> calc_distance_error(<span class="keywordtype">void</span>);
<a name="l00058"></a>00058 <span class="keywordtype">void</span> calc_long_scaling(int32_t lat);
<a name="l00059"></a>00059 <span class="keywordtype">void</span> reset_crosstrack(<span class="keywordtype">void</span>);
<a name="l00060"></a>00060
<a name="l00061"></a>00061 int16_t _old_bearing; <span class="comment">// used to track delta on the bearing</span>
<a name="l00062"></a>00062 <a class="code" href="class_g_p_s.html" title="Abstract base class for GPS receiver drivers.">GPS</a> *_gps;
<a name="l00063"></a>00063 <a class="code" href="class_waypoints.html">Waypoints</a> *_wp;
<a name="l00064"></a>00064 int32_t _crosstrack_bearing; <span class="comment">// deg * 100 : 0 to 360 desired angle of plane to target</span>
<a name="l00065"></a>00065 <span class="keywordtype">float</span> _crosstrack_error; <span class="comment">// deg * 100 : 18000 to -18000 meters we are off trackline</span>
<a name="l00066"></a>00066 int16_t _hold_course; <span class="comment">// deg * 100 dir of plane</span>
<a name="l00067"></a>00067 int32_t _target_altitude; <span class="comment">// used for </span>
<a name="l00068"></a>00068 int32_t _offset_altitude; <span class="comment">// used for </span>
<a name="l00069"></a>00069 <span class="keywordtype">float</span> _altitude_estimate;
<a name="l00070"></a>00070 <span class="keywordtype">float</span> _scaleLongUp; <span class="comment">// used to reverse int32_ttitude scaling</span>
<a name="l00071"></a>00071 <span class="keywordtype">float</span> _scaleLongDown; <span class="comment">// used to reverse int32_ttitude scaling </span>
<a name="l00072"></a>00072 int16_t _loiter_delta;
<a name="l00073"></a>00073 };
<a name="l00074"></a>00074
<a name="l00075"></a>00075
<a name="l00076"></a>00076 <span class="preprocessor">#endif // AP_NAVIGATION_h</span>
</pre></div></div>
</div>
<hr class="footer"/><address class="footer"><small>Generated on Sun Dec 26 2010 19:58:33 for ArduPilot Libraries by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/></a> 1.7.1 </small></address>
</body>
</html>