5 #ifndef TEST_TESTSUITE_H 6 #define TEST_TESTSUITE_H 12 #ifndef MAVLINK_TEST_ALL 13 #define MAVLINK_TEST_ALL 36 { 93372036854777319, 93372036854777320, 93372036854777321 },
37 { 93372036854778831, 93372036854778832, 93372036854778833 },
38 { 627.0, 628.0, 629.0 },
42 { 963503080, 963503081, 963503082 },
43 { 963503704, 963503705, 963503706 },
44 { 941.0, 942.0, 943.0 },
47 { 24931, 24932, 24933 },
48 { 25243, 25244, 25245 },
57 memset(&packet1, 0,
sizeof(packet1));
58 packet1.
u64 = packet_in.
u64;
59 packet1.
s64 = packet_in.
s64;
60 packet1.
d = packet_in.
d;
61 packet1.
u32 = packet_in.
u32;
62 packet1.
s32 = packet_in.
s32;
63 packet1.
f = packet_in.
f;
64 packet1.
u16 = packet_in.
u16;
65 packet1.
s16 = packet_in.
s16;
66 packet1.
c = packet_in.
c;
67 packet1.
u8 = packet_in.
u8;
68 packet1.
s8 = packet_in.
s8;
83 memset(&packet2, 0,
sizeof(packet2));
88 memset(&packet2, 0,
sizeof(packet2));
89 mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.
c , packet1.
s , packet1.
u8 , packet1.
u16 , packet1.
u32 , packet1.
u64 , packet1.
s8 , packet1.
s16 , packet1.
s32 , packet1.
s64 , packet1.
f , packet1.
d , packet1.
u8_array , packet1.
u16_array , packet1.
u32_array , packet1.
u64_array , packet1.
s8_array , packet1.
s16_array , packet1.
s32_array , packet1.
s64_array , packet1.
f_array , packet1.
d_array );
93 memset(&packet2, 0,
sizeof(packet2));
94 mavlink_msg_test_types_pack_chan(system_id, component_id,
MAVLINK_COMM_0, &msg , packet1.
c , packet1.
s , packet1.
u8 , packet1.
u16 , packet1.
u32 , packet1.
u64 , packet1.
s8 , packet1.
s16 , packet1.
s32 , packet1.
s64 , packet1.
f , packet1.
d , packet1.
u8_array , packet1.
u16_array , packet1.
u32_array , packet1.
u64_array , packet1.
s8_array , packet1.
s16_array , packet1.
s32_array , packet1.
s64_array , packet1.
f_array , packet1.
d_array );
98 memset(&packet2, 0,
sizeof(packet2));
106 memset(&packet2, 0,
sizeof(packet2));
107 mavlink_msg_test_types_send(
MAVLINK_COMM_1 , packet1.
c , packet1.
s , packet1.
u8 , packet1.
u16 , packet1.
u32 , packet1.
u64 , packet1.
s8 , packet1.
s16 , packet1.
s32 , packet1.
s64 , packet1.
f , packet1.
d , packet1.
u8_array , packet1.
u16_array , packet1.
u32_array , packet1.
u64_array , packet1.
s8_array , packet1.
s16_array , packet1.
s32_array , packet1.
s64_array , packet1.
f_array , packet1.
d_array );
119 #endif // __cplusplus 120 #endif // TEST_TESTSUITE_H static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg)
static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
int8_t s8_array[3]
int8_t_array
#define MAVLINK_MAX_PACKET_LEN
Maximum packet length.
uint8_t u8_array[3]
uint8_t_array
static void mavlink_msg_test_types_decode(const mavlink_message_t *msg, mavlink_test_types_t *test_types)
Decode a test_types message into a struct.
static uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t *msg)
Get the required buffer size for this message.
#define MAVLINK_ASSERT(x)
int64_t s64_array[3]
int64_t_array
static uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array)
Pack a test_types message on a channel.
uint16_t u16_array[3]
uint16_t_array
static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
int16_t s16_array[3]
int16_t_array
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
static uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_test_types_t *test_types)
Encode a test_types struct into a message.
static uint16_t mavlink_msg_test_types_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array)
Pack a test_types message.
uint64_t u64_array[3]
uint64_t_array
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static mavlink_message_t last_msg
double d_array[3]
double_array
int32_t s32_array[3]
int32_t_array
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
Pack a message to send it over a serial byte stream.
float f_array[3]
float_array
uint32_t u32_array[3]
uint32_t_array