00001
00002
00003
00004 #include <stdio.h>
00005 #include <stdlib.h>
00006 #include <stdint.h>
00007 #include <assert.h>
00008 #include <stddef.h>
00009
00010 #define MAVLINK_USE_CONVENIENCE_FUNCTIONS
00011 #define MAVLINK_COMM_NUM_BUFFERS 2
00012
00013
00014
00015 #include <version.h>
00016 #define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE
00017
00018 #include <mavlink_types.h>
00019 static mavlink_system_t mavlink_system = {42,11,};
00020
00021 #define MAVLINK_ASSERT(x) assert(x)
00022 static void comm_send_ch(mavlink_channel_t chan, uint8_t c);
00023
00024 static mavlink_message_t last_msg;
00025
00026 #include <mavlink.h>
00027 #include <testsuite.h>
00028
00029 static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS];
00030
00031 static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
00032 static unsigned error_count;
00033
00034 static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO;
00035
00036 static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
00037 {
00038 #define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def)
00039 switch (f->type) {
00040 case MAVLINK_TYPE_CHAR:
00041 printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1));
00042 break;
00043 case MAVLINK_TYPE_UINT8_T:
00044 printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1));
00045 break;
00046 case MAVLINK_TYPE_INT8_T:
00047 printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1));
00048 break;
00049 case MAVLINK_TYPE_UINT16_T:
00050 printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2));
00051 break;
00052 case MAVLINK_TYPE_INT16_T:
00053 printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2));
00054 break;
00055 case MAVLINK_TYPE_UINT32_T:
00056 printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4));
00057 break;
00058 case MAVLINK_TYPE_INT32_T:
00059 printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4));
00060 break;
00061 case MAVLINK_TYPE_UINT64_T:
00062 printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8));
00063 break;
00064 case MAVLINK_TYPE_INT64_T:
00065 printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8));
00066 break;
00067 case MAVLINK_TYPE_FLOAT:
00068 printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4));
00069 break;
00070 case MAVLINK_TYPE_DOUBLE:
00071 printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8));
00072 break;
00073 }
00074 }
00075
00076 static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f)
00077 {
00078 printf("%s: ", f->name);
00079 if (f->array_length == 0) {
00080 print_one_field(msg, f, 0);
00081 printf(" ");
00082 } else {
00083 unsigned i;
00084
00085 if (f->type == MAVLINK_TYPE_CHAR) {
00086 printf("'%.*s'", f->array_length,
00087 f->wire_offset+(const char *)_MAV_PAYLOAD(msg));
00088
00089 } else {
00090 printf("[ ");
00091 for (i=0; i<f->array_length; i++) {
00092 print_one_field(msg, f, i);
00093 if (i < f->array_length) {
00094 printf(", ");
00095 }
00096 }
00097 printf("]");
00098 }
00099 }
00100 printf(" ");
00101 }
00102
00103 static void print_message(mavlink_message_t *msg)
00104 {
00105 const mavlink_message_info_t *m = &message_info[msg->msgid];
00106 const mavlink_field_info_t *f = m->fields;
00107 unsigned i;
00108 printf("%s { ", m->name);
00109 for (i=0; i<m->num_fields; i++) {
00110 print_field(msg, &f[i]);
00111 }
00112 printf("}\n");
00113 }
00114
00115 static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
00116 {
00117 mavlink_status_t status;
00118 if (mavlink_parse_char(chan, c, &last_msg, &status)) {
00119 print_message(&last_msg);
00120 chan_counts[chan]++;
00121
00122
00123 if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) {
00124 printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n",
00125 chan_counts[chan], status.current_rx_seq);
00126 error_count++;
00127 } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) {
00128 printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n",
00129 (unsigned)chan, chan_counts[chan], status.current_rx_seq);
00130 error_count++;
00131 }
00132 if (message_lengths[last_msg.msgid] != last_msg.len) {
00133 printf("Incorrect message length %u for message %u - expected %u\n",
00134 (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]);
00135 error_count++;
00136 }
00137 }
00138 if (status.packet_rx_drop_count != 0) {
00139 printf("Parse error at packet %u\n", chan_counts[chan]);
00140 error_count++;
00141 }
00142 }
00143
00144 int main(void)
00145 {
00146 mavlink_channel_t chan;
00147 mavlink_test_all(11, 10, &last_msg);
00148 for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
00149 printf("Received %u messages on channel %u OK\n",
00150 chan_counts[chan], (unsigned)chan);
00151 }
00152 if (error_count != 0) {
00153 printf("Error count %u\n", error_count);
00154 exit(1);
00155 }
00156 printf("No errors detected\n");
00157 return 0;
00158 }
00159