mirror of https://github.com/ArduPilot/ardupilot
150 lines
16 KiB
HTML
150 lines
16 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/APM_BinComm/test/test.cpp 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 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 List</span></a></li>
|
|
<li><a href="globals.html"><span>File Members</span></a></li>
|
|
</ul>
|
|
</div>
|
|
<div class="header">
|
|
<div class="headertitle">
|
|
<h1>/home/jgoppert/Projects/ap/libraries/APM_BinComm/test/test.cpp</h1> </div>
|
|
</div>
|
|
<div class="contents">
|
|
<a href="test_8cpp.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*-</span>
|
|
<a name="l00002"></a>00002
|
|
<a name="l00003"></a>00003 <span class="comment">// test harness for the APM_BinComm bits</span>
|
|
<a name="l00004"></a>00004
|
|
<a name="l00005"></a>00005 <span class="preprocessor">#include <stdint.h></span>
|
|
<a name="l00006"></a>00006 <span class="preprocessor">#include <err.h></span>
|
|
<a name="l00007"></a>00007 <span class="preprocessor">#include <unistd.h></span>
|
|
<a name="l00008"></a>00008 <span class="preprocessor">#include <fcntl.h></span>
|
|
<a name="l00009"></a>00009 <span class="preprocessor">#include <termios.h></span>
|
|
<a name="l00010"></a>00010 <span class="preprocessor">#include <stdio.h></span>
|
|
<a name="l00011"></a>00011 <span class="preprocessor">#include <string.h></span>
|
|
<a name="l00012"></a>00012
|
|
<a name="l00013"></a>00013 <span class="preprocessor">#include "<a class="code" href="_w_program_8h.html">WProgram.h</a>"</span>
|
|
<a name="l00014"></a>00014
|
|
<a name="l00015"></a>00015 <span class="preprocessor">#include "../APM_BinComm.h"</span>
|
|
<a name="l00016"></a>00016
|
|
<a name="l00017"></a>00017 <span class="keyword">static</span> <span class="keywordtype">void</span> handler(<span class="keywordtype">void</span> *arg, uint8_t messageId, uint8_t messageVersion, <span class="keywordtype">void</span> *messageData);
|
|
<a name="l00018"></a>00018
|
|
<a name="l00019"></a><a class="code" href="test_8cpp.html#ac3f04f306dac1700cd98ab7b03c0fe48">00019</a> <a class="code" href="struct_bin_comm_1_1_message_handler.html">BinComm::MessageHandler</a> <a class="code" href="test_8cpp.html#ac3f04f306dac1700cd98ab7b03c0fe48">handlers</a>[] = {
|
|
<a name="l00020"></a>00020 {BinComm::MSG_ANY, handler, NULL},
|
|
<a name="l00021"></a>00021 {BinComm::MSG_NULL, 0, 0}
|
|
<a name="l00022"></a>00022 };
|
|
<a name="l00023"></a>00023
|
|
<a name="l00024"></a><a class="code" href="test_8cpp.html#aa9d3949e4023e37adada0665a885faef">00024</a> <a class="code" href="class_stream.html">Stream</a> <a class="code" href="test_8cpp.html#aa9d3949e4023e37adada0665a885faef">port</a>;
|
|
<a name="l00025"></a>00025 <a class="code" href="class_bin_comm.html" title="Class providing protocol en/decoding services for the ArduPilot Mega binary telemetry protocol...">BinComm</a> <a class="code" href="test_8cpp.html#a42b50075184374b8c8753d61b50c8563">comm</a>(handlers, &port);
|
|
<a name="l00026"></a>00026
|
|
<a name="l00027"></a><a class="code" href="test_8cpp.html#aeb74ae68ddf027f2d083efbf58e69882">00027</a> <span class="keywordtype">int</span> <a class="code" href="test_8cpp.html#aeb74ae68ddf027f2d083efbf58e69882">port_fd</a>;
|
|
<a name="l00028"></a>00028
|
|
<a name="l00029"></a>00029 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span>
|
|
<a name="l00030"></a><a class="code" href="_w_program_8h.html#a941a22cb7e0f6429fe40f91e83ead3d9">00030</a> <a class="code" href="test_8cpp.html#a941a22cb7e0f6429fe40f91e83ead3d9">millis</a>(<span class="keywordtype">void</span>)
|
|
<a name="l00031"></a>00031 {
|
|
<a name="l00032"></a>00032 <span class="keywordflow">return</span> 0;
|
|
<a name="l00033"></a>00033 }
|
|
<a name="l00034"></a>00034
|
|
<a name="l00035"></a>00035 <span class="keywordtype">void</span>
|
|
<a name="l00036"></a><a class="code" href="class_stream.html#a46cd2d80c276134f30300d619416d5c8">00036</a> <a class="code" href="class_stream.html#a46cd2d80c276134f30300d619416d5c8">Stream::write</a>(uint8_t val)
|
|
<a name="l00037"></a>00037 {<a class="code" href="class_stream.html#a46cd2d80c276134f30300d619416d5c8"></a>
|
|
<a name="l00038"></a>00038 <a class="code" href="class_stream.html#a46cd2d80c276134f30300d619416d5c8"> ::write</a>(<a class="code" href="test_8cpp.html#aeb74ae68ddf027f2d083efbf58e69882">port_fd</a>, &val, 1);
|
|
<a name="l00039"></a>00039 }
|
|
<a name="l00040"></a>00040
|
|
<a name="l00041"></a>00041 <span class="keywordtype">int</span>
|
|
<a name="l00042"></a><a class="code" href="class_stream.html#adb912146b71c46ce62d22412b819adcb">00042</a> <a class="code" href="class_stream.html#adb912146b71c46ce62d22412b819adcb">Stream::available</a>(<span class="keywordtype">void</span>)
|
|
<a name="l00043"></a>00043 {
|
|
<a name="l00044"></a>00044 <span class="keywordflow">return</span>(1);
|
|
<a name="l00045"></a>00045 }
|
|
<a name="l00046"></a>00046
|
|
<a name="l00047"></a>00047 <span class="keywordtype">int</span>
|
|
<a name="l00048"></a><a class="code" href="class_stream.html#a4de9545ea7065d408c3efdb97f55dc2b">00048</a> <a class="code" href="class_stream.html#a4de9545ea7065d408c3efdb97f55dc2b">Stream::read</a>(<span class="keywordtype">void</span>)
|
|
<a name="l00049"></a>00049 {
|
|
<a name="l00050"></a>00050 <span class="keywordtype">int</span> ret;
|
|
<a name="l00051"></a>00051 uint8_t c;
|
|
<a name="l00052"></a>00052
|
|
<a name="l00053"></a>00053 <span class="keywordflow">switch</span>(::<a class="code" href="class_stream.html#a4de9545ea7065d408c3efdb97f55dc2b">read</a>(<a class="code" href="test_8cpp.html#aeb74ae68ddf027f2d083efbf58e69882">port_fd</a>, &c, 1)) {
|
|
<a name="l00054"></a>00054 <span class="keywordflow">case</span> 1:
|
|
<a name="l00055"></a>00055 printf(<span class="stringliteral">"0x%02x\n"</span>, c);
|
|
<a name="l00056"></a>00056 <span class="keywordflow">return</span> c;
|
|
<a name="l00057"></a>00057 <span class="keywordflow">case</span> 0:
|
|
<a name="l00058"></a>00058 errx(1, <span class="stringliteral">"device disappeared"</span>);
|
|
<a name="l00059"></a>00059
|
|
<a name="l00060"></a>00060 <span class="keywordflow">default</span>:
|
|
<a name="l00061"></a>00061 <span class="comment">// almost certainly EWOULDBLOCK</span>
|
|
<a name="l00062"></a>00062 <span class="keywordflow">return</span> -1;
|
|
<a name="l00063"></a>00063 }
|
|
<a name="l00064"></a>00064 }
|
|
<a name="l00065"></a>00065
|
|
<a name="l00066"></a>00066 <span class="keywordtype">void</span>
|
|
<a name="l00067"></a>00067 handler(<span class="keywordtype">void</span> *arg, uint8_t messageId, uint8_t messageVersion, <span class="keywordtype">void</span> *messageData)
|
|
<a name="l00068"></a>00068 {
|
|
<a name="l00069"></a>00069
|
|
<a name="l00070"></a>00070 <span class="keywordflow">if</span> (messageId == <a class="code" href="class_bin_comm.html#a75c89aa6af30f2f2916a71405a461fb0a184e68a06d7603879fe28ab716065d86">BinComm::MSG_HEARTBEAT</a>) {
|
|
<a name="l00071"></a>00071 <span class="keyword">struct </span><a class="code" href="struct_bin_comm_1_1msg__heartbeat.html" title="Structure describing the payload section of the MSG_HEARTBEAT message.">BinComm::msg_heartbeat</a> *m = (<span class="keyword">struct </span><a class="code" href="struct_bin_comm_1_1msg__heartbeat.html" title="Structure describing the payload section of the MSG_HEARTBEAT message.">BinComm::msg_heartbeat</a> *)messageData;
|
|
<a name="l00072"></a>00072 printf(<span class="stringliteral">"Heartbeat: mode %u time %u voltage %u command %u\n"</span>,
|
|
<a name="l00073"></a>00073 m-><a class="code" href="struct_bin_comm_1_1msg__heartbeat.html#ab6c0301d6ca0fdf86e4a9ab513a750eb">flightMode</a>, m-><a class="code" href="struct_bin_comm_1_1msg__heartbeat.html#af6764d31aa29a75875f12f4e6aecb83f">timeStamp</a>, m-><a class="code" href="struct_bin_comm_1_1msg__heartbeat.html#ab0150305c94e7672db4e13901c1eaa43">batteryVoltage</a>, m-><a class="code" href="struct_bin_comm_1_1msg__heartbeat.html#ab3f2f26630902ad5735be9fe4c6aab2b">commandIndex</a>);
|
|
<a name="l00074"></a>00074 } <span class="keywordflow">else</span>
|
|
<a name="l00075"></a>00075 <span class="keywordflow">if</span> (messageId == <a class="code" href="class_bin_comm.html#a75c89aa6af30f2f2916a71405a461fb0af792fb86670678acaf6ea875cfa868e3">BinComm::MSG_ATTITUDE</a>) {
|
|
<a name="l00076"></a>00076 <span class="keyword">struct </span><a class="code" href="struct_bin_comm_1_1msg__attitude.html" title="Structure describing the payload section of the MSG_ATTITUDE message.">BinComm::msg_attitude</a> *m = (<span class="keyword">struct </span><a class="code" href="struct_bin_comm_1_1msg__attitude.html" title="Structure describing the payload section of the MSG_ATTITUDE message.">BinComm::msg_attitude</a> *)messageData;
|
|
<a name="l00077"></a>00077 printf(<span class="stringliteral">"Attitude: pitch %d roll %d yaw %d\n"</span>,
|
|
<a name="l00078"></a>00078 m-><a class="code" href="struct_bin_comm_1_1msg__attitude.html#ae94f9d2b1562576b84582d329c41f2a9">pitch</a>, m-><a class="code" href="struct_bin_comm_1_1msg__attitude.html#ace5d7b0dc8726d39ae79e1f44ab2b44e">roll</a>, m-><a class="code" href="struct_bin_comm_1_1msg__attitude.html#ab075904a0236e90e98c9de1b42f07215">yaw</a>);
|
|
<a name="l00079"></a>00079 } <span class="keywordflow">else</span>
|
|
<a name="l00080"></a>00080 <span class="keywordflow">if</span> (messageId == <a class="code" href="class_bin_comm.html#a75c89aa6af30f2f2916a71405a461fb0a4c7725ddd2cd18546491bb52a3a34536">BinComm::MSG_LOCATION</a>) {
|
|
<a name="l00081"></a>00081 <span class="keyword">struct </span><a class="code" href="struct_bin_comm_1_1msg__location.html" title="Structure describing the payload section of the MSG_LOCATION message.">BinComm::msg_location</a> *m = (<span class="keyword">struct </span><a class="code" href="struct_bin_comm_1_1msg__location.html" title="Structure describing the payload section of the MSG_LOCATION message.">BinComm::msg_location</a> *)messageData;
|
|
<a name="l00082"></a>00082 printf(<span class="stringliteral">"Location: lat %d long %d altitude %d groundspeed %d groundcourse %d time %u\n"</span>,
|
|
<a name="l00083"></a>00083 m-><a class="code" href="struct_bin_comm_1_1msg__location.html#a42ba2f86fc28107d8177371a067de142">latitude</a>, m-><a class="code" href="struct_bin_comm_1_1msg__location.html#a53477a78964d8f414c8c61bd609b545d">longitude</a>, m-><a class="code" href="struct_bin_comm_1_1msg__location.html#a7c2e3c04d8842ebadee41415e1bf3f42">altitude</a>, m-><a class="code" href="struct_bin_comm_1_1msg__location.html#a1b726523f0f11421f5c25d9649e12f99">groundSpeed</a>, m-><a class="code" href="struct_bin_comm_1_1msg__location.html#a9854d1d73555ef90f6cc576229b3255f">groundCourse</a>, m-><a class="code" href="struct_bin_comm_1_1msg__location.html#a8edd5f36a9ecb7d88199873a93592ef4">timeOfWeek</a>);
|
|
<a name="l00084"></a>00084 } <span class="keywordflow">else</span>
|
|
<a name="l00085"></a>00085 <span class="keywordflow">if</span> (messageId == <a class="code" href="class_bin_comm.html#a75c89aa6af30f2f2916a71405a461fb0a32cd8f978006350a5e4fcf8ef8f57f20">BinComm::MSG_STATUS_TEXT</a>) {
|
|
<a name="l00086"></a>00086 <span class="keyword">struct </span><a class="code" href="struct_bin_comm_1_1msg__status__text.html" title="Structure describing the payload section of the MSG_STATUS_TEXT message.">BinComm::msg_status_text</a> *m = (<span class="keyword">struct </span><a class="code" href="struct_bin_comm_1_1msg__status__text.html" title="Structure describing the payload section of the MSG_STATUS_TEXT message.">BinComm::msg_status_text</a> *)messageData;
|
|
<a name="l00087"></a>00087 printf(<span class="stringliteral">"Message %d: %-50s\n"</span>, m-><a class="code" href="struct_bin_comm_1_1msg__status__text.html#a257a9a58e1c9f921e69fdf3b0c4c55c4">severity</a>, m-><a class="code" href="struct_bin_comm_1_1msg__status__text.html#a922e5cb0e166e35812c560afd8765f77">text</a>);
|
|
<a name="l00088"></a>00088 } <span class="keywordflow">else</span> {
|
|
<a name="l00089"></a>00089 warnx(<span class="stringliteral">"received message %d,%d"</span>, messageId, messageVersion);
|
|
<a name="l00090"></a>00090 }
|
|
<a name="l00091"></a>00091 }
|
|
<a name="l00092"></a>00092
|
|
<a name="l00093"></a>00093 <span class="keywordtype">int</span>
|
|
<a name="l00094"></a><a class="code" href="test_8cpp.html#a0ddf1224851353fc92bfbff6f499fa97">00094</a> <a class="code" href="test_8cpp.html#a0ddf1224851353fc92bfbff6f499fa97">main</a>(<span class="keywordtype">int</span> argc, <span class="keywordtype">char</span> *argv[])
|
|
<a name="l00095"></a>00095 {
|
|
<a name="l00096"></a>00096 <span class="keyword">struct </span>termios t;
|
|
<a name="l00097"></a>00097
|
|
<a name="l00098"></a>00098 <span class="keywordflow">if</span> (2 > argc)
|
|
<a name="l00099"></a>00099 errx(1, <span class="stringliteral">"BinCommTest <port>"</span>);
|
|
<a name="l00100"></a>00100 <span class="keywordflow">if</span> (0 >= (<a class="code" href="test_8cpp.html#aeb74ae68ddf027f2d083efbf58e69882">port_fd</a> = open(argv[1], O_RDWR | O_NONBLOCK)))
|
|
<a name="l00101"></a>00101 err(1, <span class="stringliteral">"could not open port %s"</span>, argv[1]);
|
|
<a name="l00102"></a>00102 <span class="keywordflow">if</span> (tcgetattr(<a class="code" href="test_8cpp.html#aeb74ae68ddf027f2d083efbf58e69882">port_fd</a>, &t))
|
|
<a name="l00103"></a>00103 err(1, <span class="stringliteral">"tcgetattr"</span>);
|
|
<a name="l00104"></a>00104 cfsetspeed(&t, 115200);
|
|
<a name="l00105"></a>00105 <span class="keywordflow">if</span> (tcsetattr(<a class="code" href="test_8cpp.html#aeb74ae68ddf027f2d083efbf58e69882">port_fd</a>, TCSANOW, &t))
|
|
<a name="l00106"></a>00106 err(1, <span class="stringliteral">"tcsetattr"</span>);
|
|
<a name="l00107"></a>00107
|
|
<a name="l00108"></a>00108 <span class="comment">// spin listening</span>
|
|
<a name="l00109"></a>00109 <span class="keywordflow">for</span> (;;) {
|
|
<a name="l00110"></a>00110 <a class="code" href="test_8cpp.html#a42b50075184374b8c8753d61b50c8563">comm</a>.<a class="code" href="class_bin_comm.html#a3275f04afbe2f74f03a3933dcdfc435a">update</a>();
|
|
<a name="l00111"></a>00111 }
|
|
<a name="l00112"></a>00112 }
|
|
</pre></div></div>
|
|
</div>
|
|
<hr class="footer"/><address class="footer"><small>Generated on Sun Dec 26 2010 21:58:34 for ArduPilot Libraries by
|
|
<a href="http://www.doxygen.org/index.html">
|
|
<img class="footer" src="doxygen.png" alt="doxygen"/></a> 1.7.1 </small></address>
|
|
</body>
|
|
</html>
|