2 * @brief MAVLink comm protocol testsuite generated from minimal.xml
3 * @see http://qgroundcontrol.org/mavlink/
6 #ifndef MINIMAL_TESTSUITE_H
7 #define MINIMAL_TESTSUITE_H
13 #ifndef MAVLINK_TEST_ALL
14 #define MAVLINK_TEST_ALL
16 static void mavlink_test_minimal(uint8_t, uint8_t, mavlink_message_t
*last_msg
);
18 static void mavlink_test_all(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*last_msg
)
21 mavlink_test_minimal(system_id
, component_id
, last_msg
);
28 static void mavlink_test_heartbeat(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*last_msg
)
30 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
31 mavlink_status_t
*status
= mavlink_get_channel_status(MAVLINK_COMM_0
);
32 if ((status
->flags
& MAVLINK_STATUS_FLAG_OUT_MAVLINK1
) && MAVLINK_MSG_ID_HEARTBEAT
>= 256) {
36 mavlink_message_t msg
;
37 uint8_t buffer
[MAVLINK_MAX_PACKET_LEN
];
39 mavlink_heartbeat_t packet_in
= {
40 963497464,17,84,151,218,3
42 mavlink_heartbeat_t packet1
, packet2
;
43 memset(&packet1
, 0, sizeof(packet1
));
44 packet1
.custom_mode
= packet_in
.custom_mode
;
45 packet1
.type
= packet_in
.type
;
46 packet1
.autopilot
= packet_in
.autopilot
;
47 packet1
.base_mode
= packet_in
.base_mode
;
48 packet1
.system_status
= packet_in
.system_status
;
49 packet1
.mavlink_version
= packet_in
.mavlink_version
;
52 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
53 if (status
->flags
& MAVLINK_STATUS_FLAG_OUT_MAVLINK1
) {
54 // cope with extensions
55 memset(MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN
+ (char *)&packet1
, 0, sizeof(packet1
)-MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN
);
58 memset(&packet2
, 0, sizeof(packet2
));
59 mavlink_msg_heartbeat_encode(system_id
, component_id
, &msg
, &packet1
);
60 mavlink_msg_heartbeat_decode(&msg
, &packet2
);
61 MAVLINK_ASSERT(memcmp(&packet1
, &packet2
, sizeof(packet1
)) == 0);
63 memset(&packet2
, 0, sizeof(packet2
));
64 mavlink_msg_heartbeat_pack(system_id
, component_id
, &msg
, packet1
.type
, packet1
.autopilot
, packet1
.base_mode
, packet1
.custom_mode
, packet1
.system_status
);
65 mavlink_msg_heartbeat_decode(&msg
, &packet2
);
66 MAVLINK_ASSERT(memcmp(&packet1
, &packet2
, sizeof(packet1
)) == 0);
68 memset(&packet2
, 0, sizeof(packet2
));
69 mavlink_msg_heartbeat_pack_chan(system_id
, component_id
, MAVLINK_COMM_0
, &msg
, packet1
.type
, packet1
.autopilot
, packet1
.base_mode
, packet1
.custom_mode
, packet1
.system_status
);
70 mavlink_msg_heartbeat_decode(&msg
, &packet2
);
71 MAVLINK_ASSERT(memcmp(&packet1
, &packet2
, sizeof(packet1
)) == 0);
73 memset(&packet2
, 0, sizeof(packet2
));
74 mavlink_msg_to_send_buffer(buffer
, &msg
);
75 for (i
=0; i
<mavlink_msg_get_send_buffer_length(&msg
); i
++) {
76 comm_send_ch(MAVLINK_COMM_0
, buffer
[i
]);
78 mavlink_msg_heartbeat_decode(last_msg
, &packet2
);
79 MAVLINK_ASSERT(memcmp(&packet1
, &packet2
, sizeof(packet1
)) == 0);
81 memset(&packet2
, 0, sizeof(packet2
));
82 mavlink_msg_heartbeat_send(MAVLINK_COMM_1
, packet1
.type
, packet1
.autopilot
, packet1
.base_mode
, packet1
.custom_mode
, packet1
.system_status
);
83 mavlink_msg_heartbeat_decode(last_msg
, &packet2
);
84 MAVLINK_ASSERT(memcmp(&packet1
, &packet2
, sizeof(packet1
)) == 0);
87 static void mavlink_test_protocol_version(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*last_msg
)
89 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
90 mavlink_status_t
*status
= mavlink_get_channel_status(MAVLINK_COMM_0
);
91 if ((status
->flags
& MAVLINK_STATUS_FLAG_OUT_MAVLINK1
) && MAVLINK_MSG_ID_PROTOCOL_VERSION
>= 256) {
95 mavlink_message_t msg
;
96 uint8_t buffer
[MAVLINK_MAX_PACKET_LEN
];
98 mavlink_protocol_version_t packet_in
= {
99 17235,17339,17443,{ 151, 152, 153, 154, 155, 156, 157, 158 },{ 175, 176, 177, 178, 179, 180, 181, 182 }
101 mavlink_protocol_version_t packet1
, packet2
;
102 memset(&packet1
, 0, sizeof(packet1
));
103 packet1
.version
= packet_in
.version
;
104 packet1
.min_version
= packet_in
.min_version
;
105 packet1
.max_version
= packet_in
.max_version
;
107 mav_array_memcpy(packet1
.spec_version_hash
, packet_in
.spec_version_hash
, sizeof(uint8_t)*8);
108 mav_array_memcpy(packet1
.library_version_hash
, packet_in
.library_version_hash
, sizeof(uint8_t)*8);
110 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
111 if (status
->flags
& MAVLINK_STATUS_FLAG_OUT_MAVLINK1
) {
112 // cope with extensions
113 memset(MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN
+ (char *)&packet1
, 0, sizeof(packet1
)-MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN
);
116 memset(&packet2
, 0, sizeof(packet2
));
117 mavlink_msg_protocol_version_encode(system_id
, component_id
, &msg
, &packet1
);
118 mavlink_msg_protocol_version_decode(&msg
, &packet2
);
119 MAVLINK_ASSERT(memcmp(&packet1
, &packet2
, sizeof(packet1
)) == 0);
121 memset(&packet2
, 0, sizeof(packet2
));
122 mavlink_msg_protocol_version_pack(system_id
, component_id
, &msg
, packet1
.version
, packet1
.min_version
, packet1
.max_version
, packet1
.spec_version_hash
, packet1
.library_version_hash
);
123 mavlink_msg_protocol_version_decode(&msg
, &packet2
);
124 MAVLINK_ASSERT(memcmp(&packet1
, &packet2
, sizeof(packet1
)) == 0);
126 memset(&packet2
, 0, sizeof(packet2
));
127 mavlink_msg_protocol_version_pack_chan(system_id
, component_id
, MAVLINK_COMM_0
, &msg
, packet1
.version
, packet1
.min_version
, packet1
.max_version
, packet1
.spec_version_hash
, packet1
.library_version_hash
);
128 mavlink_msg_protocol_version_decode(&msg
, &packet2
);
129 MAVLINK_ASSERT(memcmp(&packet1
, &packet2
, sizeof(packet1
)) == 0);
131 memset(&packet2
, 0, sizeof(packet2
));
132 mavlink_msg_to_send_buffer(buffer
, &msg
);
133 for (i
=0; i
<mavlink_msg_get_send_buffer_length(&msg
); i
++) {
134 comm_send_ch(MAVLINK_COMM_0
, buffer
[i
]);
136 mavlink_msg_protocol_version_decode(last_msg
, &packet2
);
137 MAVLINK_ASSERT(memcmp(&packet1
, &packet2
, sizeof(packet1
)) == 0);
139 memset(&packet2
, 0, sizeof(packet2
));
140 mavlink_msg_protocol_version_send(MAVLINK_COMM_1
, packet1
.version
, packet1
.min_version
, packet1
.max_version
, packet1
.spec_version_hash
, packet1
.library_version_hash
);
141 mavlink_msg_protocol_version_decode(last_msg
, &packet2
);
142 MAVLINK_ASSERT(memcmp(&packet1
, &packet2
, sizeof(packet1
)) == 0);
145 static void mavlink_test_minimal(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*last_msg
)
147 mavlink_test_heartbeat(system_id
, component_id
, last_msg
);
148 mavlink_test_protocol_version(system_id
, component_id
, last_msg
);
153 #endif // __cplusplus
154 #endif // MINIMAL_TESTSUITE_H