include_v0.9/test/testsuite.h
Go to the documentation of this file.
1 
5 #ifndef TEST_TESTSUITE_H
6 #define TEST_TESTSUITE_H
7 
8 #ifdef __cplusplus
9 extern "C" {
10 #endif
11 
12 #ifndef MAVLINK_TEST_ALL
13 #define MAVLINK_TEST_ALL
14 
15 static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg);
16 
17 static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
18 {
19 
20  mavlink_test_test(system_id, component_id, last_msg);
21 }
22 #endif
23 
24 
25 
26 
27 static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
28 {
30  uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
31  uint16_t i;
32  mavlink_test_types_t packet_in = {
33  'A',
34  "BCDEFGHIJ",
35  230,
36  17859,
37  963498192,
38  93372036854776941ULL,
39  211,
40  18639,
41  963498972,
42  93372036854777886LL,
43  304.0,
44  438.0,
45  { 228, 229, 230 },
46  { 20147, 20148, 20149 },
47  { 963500688, 963500689, 963500690 },
48  { 93372036854780469, 93372036854780470, 93372036854780471 },
49  { 171, 172, 173 },
50  { 22487, 22488, 22489 },
51  { 963503028, 963503029, 963503030 },
52  { 93372036854783304, 93372036854783305, 93372036854783306 },
53  { 1018.0, 1019.0, 1020.0 },
54  { 1208.0, 1209.0, 1210.0 },
55  };
56  mavlink_test_types_t packet1, packet2;
57  memset(&packet1, 0, sizeof(packet1));
58  packet1.c = packet_in.c;
59  packet1.u8 = packet_in.u8;
60  packet1.u16 = packet_in.u16;
61  packet1.u32 = packet_in.u32;
62  packet1.u64 = packet_in.u64;
63  packet1.s8 = packet_in.s8;
64  packet1.s16 = packet_in.s16;
65  packet1.s32 = packet_in.s32;
66  packet1.s64 = packet_in.s64;
67  packet1.f = packet_in.f;
68  packet1.d = packet_in.d;
69 
70  mav_array_memcpy(packet1.s, packet_in.s, sizeof(char)*10);
71  mav_array_memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3);
72  mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3);
73  mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3);
74  mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3);
75  mav_array_memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3);
76  mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3);
77  mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3);
78  mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3);
79  mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3);
80  mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3);
81 
82 
83  memset(&packet2, 0, sizeof(packet2));
84  mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1);
85  mavlink_msg_test_types_decode(&msg, &packet2);
86  MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
87 
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 );
90  mavlink_msg_test_types_decode(&msg, &packet2);
91  MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
92 
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 );
95  mavlink_msg_test_types_decode(&msg, &packet2);
96  MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
97 
98  memset(&packet2, 0, sizeof(packet2));
99  mavlink_msg_to_send_buffer(buffer, &msg);
100  for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
101  comm_send_ch(MAVLINK_COMM_0, buffer[i]);
102  }
103  mavlink_msg_test_types_decode(last_msg, &packet2);
104  MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
105 
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 );
108  mavlink_msg_test_types_decode(last_msg, &packet2);
109  MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
110 }
111 
112 static void mavlink_test_test(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
113 {
114  mavlink_test_test_types(system_id, component_id, last_msg);
115 }
116 
117 #ifdef __cplusplus
118 }
119 #endif // __cplusplus
120 #endif // TEST_TESTSUITE_H
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)
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg)
static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
Definition: testmav.c:135
static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static mavlink_message_t last_msg
Definition: testmav.c:26


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