ardupilot/libraries/doc/html/_waypoints_8cpp_source.html

160 lines
11 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: Waypoints.cpp Source File</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="pages.html"><span>Related&nbsp;Pages</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>Waypoints.cpp</h1> </div>
</div>
<div class="contents">
<a href="_waypoints_8cpp.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/*</span>
<a name="l00002"></a>00002 <span class="comment"> AP_Radio.cpp - Radio library for Arduino</span>
<a name="l00003"></a>00003 <span class="comment"> Code by Jason Short. DIYDrones.com</span>
<a name="l00004"></a>00004 <span class="comment"> </span>
<a name="l00005"></a>00005 <span class="comment"> This library is free software; you can redistribute it and / or</span>
<a name="l00006"></a>00006 <span class="comment"> modify it under the terms of the GNU Lesser General Public</span>
<a name="l00007"></a>00007 <span class="comment"> License as published by the Free Software Foundation; either</span>
<a name="l00008"></a>00008 <span class="comment"> version 2.1 of the License, or (at your option) any later version.</span>
<a name="l00009"></a>00009 <span class="comment"></span>
<a name="l00010"></a>00010 <span class="comment">*/</span>
<a name="l00011"></a>00011
<a name="l00012"></a>00012 <span class="preprocessor">#include &quot;<a class="code" href="_waypoints_8h.html">Waypoints.h</a>&quot;</span>
<a name="l00013"></a>00013
<a name="l00014"></a><a class="code" href="class_waypoints.html#acf16e7693e577540cd0be5b263acb047">00014</a> <a class="code" href="class_waypoints.html#acf16e7693e577540cd0be5b263acb047">Waypoints::Waypoints</a>()
<a name="l00015"></a>00015 {
<a name="l00016"></a>00016 }
<a name="l00017"></a>00017
<a name="l00018"></a>00018 <span class="keywordtype">void</span>
<a name="l00019"></a><a class="code" href="class_waypoints.html#a78f8f60817720baed33b8081e0ae5a82">00019</a> <a class="code" href="class_waypoints.html#a78f8f60817720baed33b8081e0ae5a82">Waypoints::set_waypoint_with_index</a>(<a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a> wp, uint8_t i)
<a name="l00020"></a>00020 {
<a name="l00021"></a>00021 i = constrain(i, 0, _total);
<a name="l00022"></a>00022 uint32_t mem = _start_byte + (i * _wp_size);
<a name="l00023"></a>00023
<a name="l00024"></a>00024 eeprom_busy_wait();
<a name="l00025"></a>00025 eeprom_write_byte((uint8_t *) mem, wp.<a class="code" href="struct_waypoints_1_1_w_p.html#af7aada2a4747d5b4329e07ab1f7fa8b8">id</a>);
<a name="l00026"></a>00026
<a name="l00027"></a>00027 mem++;
<a name="l00028"></a>00028 eeprom_busy_wait();
<a name="l00029"></a>00029 eeprom_write_byte((uint8_t *) mem, wp.<a class="code" href="struct_waypoints_1_1_w_p.html#a8052d8252ee2849af0060924ff943f89">p1</a>);
<a name="l00030"></a>00030
<a name="l00031"></a>00031 mem++;
<a name="l00032"></a>00032 eeprom_busy_wait();
<a name="l00033"></a>00033 eeprom_write_dword((uint32_t *) mem, wp.<a class="code" href="struct_waypoints_1_1_w_p.html#aa2b3ddc9b275b4561da9ec0738b1b1bb">alt</a>);
<a name="l00034"></a>00034
<a name="l00035"></a>00035 mem += 4;
<a name="l00036"></a>00036 eeprom_busy_wait();
<a name="l00037"></a>00037 eeprom_write_dword((uint32_t *) mem, wp.<a class="code" href="struct_waypoints_1_1_w_p.html#a9383b83df64aa44b2c9d7398fac40639">lat</a>);
<a name="l00038"></a>00038
<a name="l00039"></a>00039 mem += 4;
<a name="l00040"></a>00040 eeprom_busy_wait();
<a name="l00041"></a>00041 eeprom_write_dword((uint32_t *) mem, wp.<a class="code" href="struct_waypoints_1_1_w_p.html#aeaeb0aff010ed3057ff7fdfcac737054">lng</a>);
<a name="l00042"></a>00042 }
<a name="l00043"></a>00043
<a name="l00044"></a>00044 <a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a>
<a name="l00045"></a><a class="code" href="class_waypoints.html#ab942a563846af24d306e3eb19dfb4a2a">00045</a> <a class="code" href="class_waypoints.html#ab942a563846af24d306e3eb19dfb4a2a">Waypoints::get_waypoint_with_index</a>(uint8_t i)
<a name="l00046"></a>00046 {
<a name="l00047"></a>00047 <a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a> wp;
<a name="l00048"></a>00048
<a name="l00049"></a>00049 i = constrain(i, 0, _total);
<a name="l00050"></a>00050 uint32_t mem = _start_byte + (i * _wp_size);
<a name="l00051"></a>00051
<a name="l00052"></a>00052 eeprom_busy_wait();
<a name="l00053"></a>00053 wp.<a class="code" href="struct_waypoints_1_1_w_p.html#af7aada2a4747d5b4329e07ab1f7fa8b8">id</a> = eeprom_read_byte((uint8_t *)mem);
<a name="l00054"></a>00054
<a name="l00055"></a>00055 mem++;
<a name="l00056"></a>00056 eeprom_busy_wait();
<a name="l00057"></a>00057 wp.<a class="code" href="struct_waypoints_1_1_w_p.html#a8052d8252ee2849af0060924ff943f89">p1</a> = eeprom_read_byte((uint8_t *)mem);
<a name="l00058"></a>00058
<a name="l00059"></a>00059 mem++;
<a name="l00060"></a>00060 eeprom_busy_wait();
<a name="l00061"></a>00061 wp.<a class="code" href="struct_waypoints_1_1_w_p.html#aa2b3ddc9b275b4561da9ec0738b1b1bb">alt</a> = (long)eeprom_read_dword((uint32_t *)mem);
<a name="l00062"></a>00062
<a name="l00063"></a>00063 mem += 4;
<a name="l00064"></a>00064 eeprom_busy_wait();
<a name="l00065"></a>00065 wp.<a class="code" href="struct_waypoints_1_1_w_p.html#a9383b83df64aa44b2c9d7398fac40639">lat</a> = (long)eeprom_read_dword((uint32_t *)mem);
<a name="l00066"></a>00066
<a name="l00067"></a>00067 mem += 4;
<a name="l00068"></a>00068 eeprom_busy_wait();
<a name="l00069"></a>00069 wp.<a class="code" href="struct_waypoints_1_1_w_p.html#aeaeb0aff010ed3057ff7fdfcac737054">lng</a> = (long)eeprom_read_dword((uint32_t *)mem);
<a name="l00070"></a>00070 }
<a name="l00071"></a>00071
<a name="l00072"></a>00072
<a name="l00073"></a>00073 <a class="code" href="struct_waypoints_1_1_w_p.html">Waypoints::WP</a>
<a name="l00074"></a><a class="code" href="class_waypoints.html#a0a69eac7c5eadd99d7dcd3df7bb12364">00074</a> <a class="code" href="class_waypoints.html#a0a69eac7c5eadd99d7dcd3df7bb12364">Waypoints::get_current_waypoint</a>(<span class="keywordtype">void</span>)
<a name="l00075"></a>00075 {
<a name="l00076"></a>00076 <span class="keywordflow">return</span> <a class="code" href="class_waypoints.html#ab942a563846af24d306e3eb19dfb4a2a">get_waypoint_with_index</a>(_index);
<a name="l00077"></a>00077 }
<a name="l00078"></a>00078
<a name="l00079"></a>00079 uint8_t
<a name="l00080"></a><a class="code" href="class_waypoints.html#a14fe22b108921ce62233d215c60528e3">00080</a> <a class="code" href="class_waypoints.html#a14fe22b108921ce62233d215c60528e3">Waypoints::get_index</a>(<span class="keywordtype">void</span>)
<a name="l00081"></a>00081 {
<a name="l00082"></a>00082 <span class="keywordflow">return</span> _index;
<a name="l00083"></a>00083 }
<a name="l00084"></a>00084
<a name="l00085"></a>00085 <span class="keywordtype">void</span>
<a name="l00086"></a><a class="code" href="class_waypoints.html#a5a1212d730716e107c76a80f38f72488">00086</a> <a class="code" href="class_waypoints.html#a5a1212d730716e107c76a80f38f72488">Waypoints::next_index</a>(<span class="keywordtype">void</span>)
<a name="l00087"></a>00087 {
<a name="l00088"></a>00088 _index++;
<a name="l00089"></a>00089 <span class="keywordflow">if</span> (_index &gt;= _total)
<a name="l00090"></a>00090 _index == 0;
<a name="l00091"></a>00091 }
<a name="l00092"></a>00092
<a name="l00093"></a>00093 <span class="keywordtype">void</span>
<a name="l00094"></a><a class="code" href="class_waypoints.html#a12ee61e5fdd8c7e5943d4beaee20eac0">00094</a> <a class="code" href="class_waypoints.html#a12ee61e5fdd8c7e5943d4beaee20eac0">Waypoints::set_index</a>(uint8_t i)
<a name="l00095"></a>00095 {
<a name="l00096"></a>00096 i = constrain(i, 0, _total);
<a name="l00097"></a>00097 }
<a name="l00098"></a>00098
<a name="l00099"></a>00099 uint8_t
<a name="l00100"></a><a class="code" href="class_waypoints.html#ad5b1eaf444c24ab141e7c4b34eece456">00100</a> <a class="code" href="class_waypoints.html#ad5b1eaf444c24ab141e7c4b34eece456">Waypoints::get_total</a>(<span class="keywordtype">void</span>)
<a name="l00101"></a>00101 {
<a name="l00102"></a>00102 <span class="keywordflow">return</span> _total;
<a name="l00103"></a>00103 }
<a name="l00104"></a>00104 <span class="keywordtype">void</span>
<a name="l00105"></a><a class="code" href="class_waypoints.html#a93835eb97d9725bacec945e7deccc7f4">00105</a> <a class="code" href="class_waypoints.html#a93835eb97d9725bacec945e7deccc7f4">Waypoints::set_total</a>(uint8_t total)
<a name="l00106"></a>00106 {
<a name="l00107"></a>00107 _total = total;
<a name="l00108"></a>00108 }
<a name="l00109"></a>00109
<a name="l00110"></a>00110 <span class="keywordtype">void</span>
<a name="l00111"></a><a class="code" href="class_waypoints.html#a41b0874bc4bffb40988d3112a24d0cb2">00111</a> <a class="code" href="class_waypoints.html#a41b0874bc4bffb40988d3112a24d0cb2">Waypoints::set_start_byte</a>(uint16_t start_byte)
<a name="l00112"></a>00112 {
<a name="l00113"></a>00113 _start_byte = start_byte;
<a name="l00114"></a>00114 }
<a name="l00115"></a>00115
<a name="l00116"></a>00116 <span class="keywordtype">void</span>
<a name="l00117"></a><a class="code" href="class_waypoints.html#a3087951b9c0727ba23d553e6c56333b8">00117</a> <a class="code" href="class_waypoints.html#a3087951b9c0727ba23d553e6c56333b8">Waypoints::set_wp_size</a>(uint8_t wp_size)
<a name="l00118"></a>00118 {
<a name="l00119"></a>00119 _wp_size = wp_size;
<a name="l00120"></a>00120 }
</pre></div></div>
</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>