mirror of https://github.com/ArduPilot/ardupilot
86 lines
7.3 KiB
HTML
86 lines
7.3 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.h 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 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><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 List</span></a></li>
|
|
<li><a href="globals.html"><span>File Members</span></a></li>
|
|
</ul>
|
|
</div>
|
|
<div class="header">
|
|
<div class="headertitle">
|
|
<h1>Waypoints.h</h1> </div>
|
|
</div>
|
|
<div class="contents">
|
|
<a href="_waypoints_8h.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="preprocessor">#ifndef Waypoints_h</span>
|
|
<a name="l00002"></a>00002 <span class="preprocessor"></span><span class="preprocessor">#define Waypoints_h</span>
|
|
<a name="l00003"></a>00003 <span class="preprocessor"></span>
|
|
<a name="l00004"></a>00004 <span class="preprocessor">#include <inttypes.h></span>
|
|
<a name="l00005"></a>00005 <span class="preprocessor">#include "<a class="code" href="_w_program_8h.html">WProgram.h</a>"</span>
|
|
<a name="l00006"></a>00006 <span class="preprocessor">#include <avr/eeprom.h></span>
|
|
<a name="l00007"></a>00007
|
|
<a name="l00008"></a><a class="code" href="class_waypoints.html">00008</a> <span class="keyword">class </span><a class="code" href="class_waypoints.html">Waypoints</a>
|
|
<a name="l00009"></a>00009 {
|
|
<a name="l00010"></a>00010 <span class="keyword">public</span>:
|
|
<a name="l00011"></a>00011 <a class="code" href="class_waypoints.html#acf16e7693e577540cd0be5b263acb047">Waypoints</a>();
|
|
<a name="l00012"></a>00012
|
|
<a name="l00013"></a><a class="code" href="struct_waypoints_1_1_w_p.html">00013</a> <span class="keyword">struct </span><a class="code" href="struct_waypoints_1_1_w_p.html">WP</a> {
|
|
<a name="l00014"></a><a class="code" href="struct_waypoints_1_1_w_p.html#af7aada2a4747d5b4329e07ab1f7fa8b8">00014</a> uint8_t <a class="code" href="struct_waypoints_1_1_w_p.html#af7aada2a4747d5b4329e07ab1f7fa8b8">id</a>; <span class="comment">// for commands</span>
|
|
<a name="l00015"></a><a class="code" href="struct_waypoints_1_1_w_p.html#a8052d8252ee2849af0060924ff943f89">00015</a> int8_t <a class="code" href="struct_waypoints_1_1_w_p.html#a8052d8252ee2849af0060924ff943f89">p1</a>; <span class="comment">// for commands</span>
|
|
<a name="l00016"></a><a class="code" href="struct_waypoints_1_1_w_p.html#aa2b3ddc9b275b4561da9ec0738b1b1bb">00016</a> int32_t <a class="code" href="struct_waypoints_1_1_w_p.html#aa2b3ddc9b275b4561da9ec0738b1b1bb">alt</a>; <span class="comment">// Altitude in centimeters (meters * 100)</span>
|
|
<a name="l00017"></a><a class="code" href="struct_waypoints_1_1_w_p.html#a9383b83df64aa44b2c9d7398fac40639">00017</a> int32_t <a class="code" href="struct_waypoints_1_1_w_p.html#a9383b83df64aa44b2c9d7398fac40639">lat</a>; <span class="comment">// Lattitude * 10**7</span>
|
|
<a name="l00018"></a><a class="code" href="struct_waypoints_1_1_w_p.html#aeaeb0aff010ed3057ff7fdfcac737054">00018</a> int32_t <a class="code" href="struct_waypoints_1_1_w_p.html#aeaeb0aff010ed3057ff7fdfcac737054">lng</a>; <span class="comment">// Longitude * 10**7</span>
|
|
<a name="l00019"></a>00019 };
|
|
<a name="l00020"></a>00020
|
|
<a name="l00021"></a>00021 <a class="code" href="struct_waypoints_1_1_w_p.html">WP</a> <a class="code" href="class_waypoints.html#ab942a563846af24d306e3eb19dfb4a2a">get_waypoint_with_index</a>(uint8_t i);
|
|
<a name="l00022"></a>00022 <a class="code" href="struct_waypoints_1_1_w_p.html">WP</a> <a class="code" href="class_waypoints.html#a0a69eac7c5eadd99d7dcd3df7bb12364">get_current_waypoint</a>(<span class="keywordtype">void</span>);
|
|
<a name="l00023"></a>00023
|
|
<a name="l00024"></a>00024 <span class="keywordtype">void</span> <a class="code" href="class_waypoints.html#a78f8f60817720baed33b8081e0ae5a82">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="l00025"></a>00025
|
|
<a name="l00026"></a>00026 <span class="keywordtype">void</span> <a class="code" href="class_waypoints.html#a41b0874bc4bffb40988d3112a24d0cb2">set_start_byte</a>(uint16_t start_byte);
|
|
<a name="l00027"></a>00027 <span class="keywordtype">void</span> <a class="code" href="class_waypoints.html#a3087951b9c0727ba23d553e6c56333b8">set_wp_size</a>(uint8_t wp_size);
|
|
<a name="l00028"></a>00028
|
|
<a name="l00029"></a>00029 <span class="keywordtype">void</span> <a class="code" href="class_waypoints.html#a5a1212d730716e107c76a80f38f72488">next_index</a>(<span class="keywordtype">void</span>);
|
|
<a name="l00030"></a>00030 uint8_t <a class="code" href="class_waypoints.html#a14fe22b108921ce62233d215c60528e3">get_index</a>(<span class="keywordtype">void</span>);
|
|
<a name="l00031"></a>00031 <span class="keywordtype">void</span> <a class="code" href="class_waypoints.html#a12ee61e5fdd8c7e5943d4beaee20eac0">set_index</a>(uint8_t i);
|
|
<a name="l00032"></a>00032
|
|
<a name="l00033"></a>00033 uint8_t <a class="code" href="class_waypoints.html#ad5b1eaf444c24ab141e7c4b34eece456">get_total</a>(<span class="keywordtype">void</span>);
|
|
<a name="l00034"></a>00034 <span class="keywordtype">void</span> <a class="code" href="class_waypoints.html#a93835eb97d9725bacec945e7deccc7f4">set_total</a>(uint8_t total);
|
|
<a name="l00035"></a>00035
|
|
<a name="l00036"></a>00036
|
|
<a name="l00037"></a>00037
|
|
<a name="l00038"></a>00038 <span class="keyword">private</span>:
|
|
<a name="l00039"></a>00039 uint16_t _start_byte;
|
|
<a name="l00040"></a>00040 uint8_t _wp_size;
|
|
<a name="l00041"></a>00041 uint8_t _index;
|
|
<a name="l00042"></a>00042 uint8_t _total;
|
|
<a name="l00043"></a>00043 };
|
|
<a name="l00044"></a>00044
|
|
<a name="l00045"></a>00045 <span class="preprocessor">#endif</span>
|
|
<a name="l00046"></a>00046 <span class="preprocessor"></span>
|
|
</pre></div></div>
|
|
</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>
|