11 #define MAVLINK_USE_CONVENIENCE_FUNCTIONS 12 #define MAVLINK_COMM_NUM_BUFFERS 2 14 #include <mavlink_types.h> 17 #define MAVLINK_ASSERT(x) assert(x) 22 #include <common/mavlink.h> 23 #include <common/testsuite.h> 34 #define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def) 74 printf(
"%s: ", f->
name);
89 if (i < f->array_length) {
104 printf(
"%s { ", m->
name);
120 printf(
"Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n",
124 printf(
"Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n",
129 printf(
"Incorrect message length %u for message %u - expected %u\n",
135 printf(
"Parse error at packet %u\n",
chan_counts[chan]);
145 printf(
"Received %u messages on channel %u OK\n",
152 printf(
"No errors detected\n");
unsigned int array_length
#define _MAV_RETURN_uint8_t(msg, wire_offset)
uint8_t msgid
ID of message in payload.
static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS]
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
#define MAVLINK_MESSAGE_LENGTHS
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]
static unsigned error_count
mavlink_message_type_t type
static mavlink_system_t mavlink_system
static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
#define MAVLINK_COMM_NUM_BUFFERS
#define _MAV_RETURN_int8_t(msg, wire_offset)
#define _MAV_RETURN_char(msg, wire_offset)
uint16_t packet_rx_drop_count
Number of packet drops.
static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
int _tmain(int argc, _TCHAR *argv[])
#define PRINT_FORMAT(f, def)
#define _MAV_PAYLOAD(msg)
uint8_t len
Length of payload.
uint8_t current_rx_seq
Sequence number of last packet received.
static const unsigned message_lengths[]
static const mavlink_message_info_t message_info[256]
static mavlink_message_t last_msg
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t *r_message, mavlink_status_t *r_mavlink_status)
static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f)
#define MAVLINK_MESSAGE_INFO
static void print_message(mavlink_message_t *msg)