testmav.c
Go to the documentation of this file.
1 /*
2  simple MAVLink testsuite for C
3  */
4 #include <stdio.h>
5 #include <stdlib.h>
6 #include <stdint.h>
7 #include <assert.h>
8 #include <stddef.h>
9 #include <stdbool.h>
10 
11 #define MAVLINK_USE_CONVENIENCE_FUNCTIONS
12 #define MAVLINK_USE_MESSAGE_INFO
13 #define MAVLINK_COMM_NUM_BUFFERS 2
14 
15 // this trick allows us to make mavlink_message_t as small as possible
16 // for this dialect, which saves some memory
17 #include <version.h>
18 #define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE
19 
20 #include <mavlink_types.h>
21 static mavlink_system_t mavlink_system = {42,11,};
22 
23 #define MAVLINK_ASSERT(x) assert(x)
24 static void comm_send_ch(mavlink_channel_t chan, uint8_t c);
25 
27 
28 #include <mavlink.h>
29 #include <testsuite.h>
30 
32 
33 #ifndef MAVLINK_HAVE_MIN_MESSAGE_LENGTH
34 static const uint8_t message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
35 #define mavlink_min_message_length(msg) message_lengths[(msg)->msgid]
36 #endif
37 
38 #ifndef MAVLINK_HAVE_GET_MESSAGE_INFO
40 #define mavlink_get_message_info(msg) &message_info[(msg)->msgid]
41 #endif
42 
43 static unsigned error_count;
44 
45 
46 static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
47 {
48 #define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def)
49  switch (f->type) {
50  case MAVLINK_TYPE_CHAR:
51  printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1));
52  break;
54  printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1));
55  break;
57  printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1));
58  break;
60  printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2));
61  break;
63  printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2));
64  break;
66  printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4));
67  break;
69  printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4));
70  break;
72  printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8));
73  break;
75  printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8));
76  break;
77  case MAVLINK_TYPE_FLOAT:
78  printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4));
79  break;
81  printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8));
82  break;
83  }
84 }
85 
87 {
88  printf("%s: ", f->name);
89  if (f->array_length == 0) {
90  print_one_field(msg, f, 0);
91  printf(" ");
92  } else {
93  unsigned i;
94  /* print an array */
95  if (f->type == MAVLINK_TYPE_CHAR) {
96  printf("'%.*s'", f->array_length,
97  f->wire_offset+(const char *)_MAV_PAYLOAD(msg));
98 
99  } else {
100  printf("[ ");
101  for (i=0; i<f->array_length; i++) {
102  print_one_field(msg, f, i);
103  if (i < f->array_length) {
104  printf(", ");
105  }
106  }
107  printf("]");
108  }
109  }
110  printf(" ");
111 }
112 
114 {
116  if (m == NULL) {
117  printf("ERROR: no message info for %u\n", msg->msgid);
118  error_count++;
119  return;
120  }
121  const mavlink_field_info_t *f = m->fields;
122  unsigned i;
123  printf("%s { ", m->name);
124  for (i=0; i<m->num_fields; i++) {
125  print_field(msg, &f[i]);
126  }
127  printf("}\n");
128 }
129 
130 #ifdef MAVLINK_SIGNING_FLAG_SIGN_OUTGOING
132 static mavlink_signing_streams_t signing_streams_in;
133 #endif
134 
135 static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
136 {
137  mavlink_status_t status;
138  memset(&status, 0, sizeof(status));
139 #ifdef MAVLINK_SIGNING_FLAG_SIGN_OUTGOING
140  status.signing = &signing_in[chan];
141  status.signing_streams = &signing_streams_in;
142 #endif
143  if (mavlink_parse_char(chan, c, &last_msg, &status)) {
144  print_message(&last_msg);
145  chan_counts[chan]++;
146  /* channel 0 gets 3 messages per message, because of
147  the channel defaults for _pack() and _encode() */
148  if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) {
149  printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n",
150  chan_counts[chan], status.current_rx_seq);
151  error_count++;
152  } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) {
153  printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n",
154  (unsigned)chan, chan_counts[chan], status.current_rx_seq);
155  error_count++;
156  }
157  // we only check the lengtth for MAVLink1. In MAVLink2 packets are zero trimmed
158  if (mavlink_min_message_length(&last_msg) > last_msg.len && last_msg.magic == 254) {
159  printf("Incorrect message length %u for message %u - expected %u\n",
160  (unsigned)last_msg.len, (unsigned)last_msg.msgid,
161  mavlink_min_message_length(&last_msg));
162  error_count++;
163  }
164  }
165  if (status.packet_rx_drop_count != 0) {
166  printf("Parse error at packet %u\n", chan_counts[chan]);
167  error_count++;
168  }
169 }
170 
171 int main(void)
172 {
173  mavlink_channel_t chan;
174 
175  mavlink_test_all(11, 10, &last_msg);
176  for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
177  printf("Received %u messages on channel %u OK\n",
178  chan_counts[chan], (unsigned)chan);
179  }
180  if (error_count != 0) {
181  printf("Error count %u\n", error_count);
182  exit(1);
183  }
184  printf("No errors detected\n");
185 
186 #ifdef MAVLINK_SIGNING_FLAG_SIGN_OUTGOING
187  mavlink_status_t *status;
188 
189  printf("Testing signing\n");
190  mavlink_signing_t signing;
191  mavlink_signing_streams_t signing_streams;
192  memset(&signing, 0, sizeof(signing));
193  memset(&signing_streams, 0, sizeof(signing_streams));
195  signing.link_id = 0;
196  signing.timestamp = 1;
197  memset(signing.secret_key, 42, sizeof(signing.secret_key));
198 
200  status->signing = &signing;
201  status->signing_streams = &signing_streams;
202 
203  mavlink_test_all(11, 10, &last_msg);
204  for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
205  printf("Received %u messages on channel %u OK\n",
206  chan_counts[chan], (unsigned)chan);
207  }
208  if (error_count != 0) {
209  printf("Error count %u\n", error_count);
210  exit(1);
211  }
212  printf("No errors detected\n");
213 #endif
214 
215 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
218  status->signing = NULL;
221  status->signing = NULL;
222  printf("Testing sending as MAVLink1\n");
223 
224  mavlink_test_all(11, 10, &last_msg);
225  for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
226  printf("Received %u messages on channel %u OK\n",
227  chan_counts[chan], (unsigned)chan);
228  }
229  if (error_count != 0) {
230  printf("Error count %u\n", error_count);
231  exit(1);
232  }
233  printf("No errors detected\n");
234 #endif
235 
236 
237  return 0;
238 }
239 
#define _MAV_RETURN_uint8_t(msg, wire_offset)
#define mavlink_min_message_length(msg)
Definition: testmav.c:35
static const uint8_t message_lengths[]
Definition: testmav.c:34
#define mavlink_get_message_info(msg)
Definition: testmav.c:40
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f)
Definition: testmav.c:86
#define MAVLINK_MESSAGE_LENGTHS
static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
Definition: testmav.c:135
#define _MAV_RETURN_int8_t(msg, wire_offset)
#define PRINT_FORMAT(f, def)
#define _MAV_RETURN_char(msg, wire_offset)
#define MAVLINK_COMM_NUM_BUFFERS
Definition: testmav.c:13
static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
Definition: testmav.c:46
static mavlink_message_t last_msg
Definition: testmav.c:26
static unsigned error_count
Definition: testmav.c:43
static mavlink_system_t mavlink_system
Definition: testmav.c:21
int main(void)
Definition: testmav.c:171
static const mavlink_message_info_t message_info[]
Definition: testmav.c:39
static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS]
Definition: testmav.c:31
#define MAVLINK_MESSAGE_INFO
static void print_message(mavlink_message_t *msg)
Definition: testmav.c:113


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Jul 7 2019 03:22:07