testmav.cpp
Go to the documentation of this file.
1 // testmav.cpp : Defines the entry point for the console application.
2 //
3 
4 #include "stdafx.h"
5 #include "stdio.h"
6 #include "stdint.h"
7 #include "stddef.h"
8 #include "assert.h"
9 
10 
11 #define MAVLINK_USE_CONVENIENCE_FUNCTIONS
12 #define MAVLINK_COMM_NUM_BUFFERS 2
13 
14 #include <mavlink_types.h>
15 static mavlink_system_t mavlink_system = {42,11,};
16 
17 #define MAVLINK_ASSERT(x) assert(x)
18 static void comm_send_ch(mavlink_channel_t chan, uint8_t c);
19 
21 
22 #include <common/mavlink.h>
23 #include <common/testsuite.h>
24 
26 
27 static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
28 static unsigned error_count;
29 
31 
32 static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
33 {
34 #define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def)
35  switch (f->type) {
36  case MAVLINK_TYPE_CHAR:
37  printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1));
38  break;
40  printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1));
41  break;
43  printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1));
44  break;
46  printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2));
47  break;
49  printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2));
50  break;
52  printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4));
53  break;
55  printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4));
56  break;
58  printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8));
59  break;
61  printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8));
62  break;
63  case MAVLINK_TYPE_FLOAT:
64  printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4));
65  break;
67  printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8));
68  break;
69  }
70 }
71 
73 {
74  printf("%s: ", f->name);
75  if (f->array_length == 0) {
76  print_one_field(msg, f, 0);
77  printf(" ");
78  } else {
79  unsigned i;
80  /* print an array */
81  if (f->type == MAVLINK_TYPE_CHAR) {
82  printf("'%.*s'", f->array_length,
83  f->wire_offset+(const char *)_MAV_PAYLOAD(msg));
84 
85  } else {
86  printf("[ ");
87  for (i=0; i<f->array_length; i++) {
88  print_one_field(msg, f, i);
89  if (i < f->array_length) {
90  printf(", ");
91  }
92  }
93  printf("]");
94  }
95  }
96  printf(" ");
97 }
98 
100 {
101  const mavlink_message_info_t *m = &message_info[msg->msgid];
102  const mavlink_field_info_t *f = m->fields;
103  unsigned i;
104  printf("%s { ", m->name);
105  for (i=0; i<m->num_fields; i++) {
106  print_field(msg, &f[i]);
107  }
108  printf("}\n");
109 }
110 
111 static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
112 {
113  mavlink_status_t status;
114  if (mavlink_parse_char(chan, c, &last_msg, &status)) {
115  print_message(&last_msg);
116  chan_counts[chan]++;
117  /* channel 0 gets 3 messages per message, because of
118  the channel defaults for _pack() and _encode() */
119  if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) {
120  printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n",
121  chan_counts[chan], status.current_rx_seq);
122  error_count++;
123  } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) {
124  printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n",
125  (unsigned)chan, chan_counts[chan], status.current_rx_seq);
126  error_count++;
127  }
128  if (message_lengths[last_msg.msgid] != last_msg.len) {
129  printf("Incorrect message length %u for message %u - expected %u\n",
130  (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]);
131  error_count++;
132  }
133  }
134  if (status.packet_rx_drop_count != 0) {
135  printf("Parse error at packet %u\n", chan_counts[chan]);
136  error_count++;
137  }
138 }
139 
140 int _tmain(int argc, _TCHAR* argv[])
141 {
142  int chan;
143  mavlink_test_all(11, 10, &last_msg);
144  for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
145  printf("Received %u messages on channel %u OK\n",
146  chan_counts[chan], (unsigned)chan);
147  }
148  if (error_count != 0) {
149  printf("Error count %u\n", error_count);
150  return(1);
151  }
152  printf("No errors detected\n");
153  return 0;
154 }
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS]
Definition: testmav.cpp:25
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
#define MAVLINK_MESSAGE_LENGTHS
static unsigned error_count
Definition: testmav.cpp:28
static mavlink_system_t mavlink_system
Definition: testmav.cpp:15
static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
Definition: testmav.cpp:111
#define MAVLINK_COMM_NUM_BUFFERS
Definition: testmav.cpp:12
#define _MAV_RETURN_int8_t(msg, wire_offset)
#define _MAV_RETURN_char(msg, wire_offset)
static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
Definition: testmav.cpp:32
int _tmain(int argc, _TCHAR *argv[])
Definition: testmav.cpp:140
#define PRINT_FORMAT(f, def)
static const unsigned message_lengths[]
Definition: testmav.cpp:27
static const mavlink_message_info_t message_info[256]
Definition: testmav.cpp:30
static mavlink_message_t last_msg
Definition: testmav.cpp:20
static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f)
Definition: testmav.cpp:72
#define MAVLINK_MESSAGE_INFO
static void print_message(mavlink_message_t *msg)
Definition: testmav.cpp:99


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02