3 #define MAVLINK_MSG_ID_MISSION_COUNT 44
12 #define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4
13 #define MAVLINK_MSG_ID_44_LEN 4
15 #define MAVLINK_MSG_ID_MISSION_COUNT_CRC 221
16 #define MAVLINK_MSG_ID_44_CRC 221
20 #define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \
23 { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
24 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \
25 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \
41 static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42 uint8_t target_system, uint8_t target_component, uint16_t count)
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
79 static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
80 mavlink_message_t* msg,
81 uint8_t target_system,uint8_t target_component,uint16_t count)
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
100 #if MAVLINK_CRC_EXTRA
115 static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_mission_count_t* mission_count)
129 static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_mission_count_t* mission_count)
142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
144 static inline void mavlink_msg_mission_count_send(
mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count)
146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
152 #if MAVLINK_CRC_EXTRA
159 packet.
count = count;
163 #if MAVLINK_CRC_EXTRA
171 #if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
179 static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count)
181 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 char *buf = (
char *)msgbuf;
187 #if MAVLINK_CRC_EXTRA
194 packet->
count = count;
198 #if MAVLINK_CRC_EXTRA
217 static inline uint8_t mavlink_msg_mission_count_get_target_system(
const mavlink_message_t* msg)
227 static inline uint8_t mavlink_msg_mission_count_get_target_component(
const mavlink_message_t* msg)
237 static inline uint16_t mavlink_msg_mission_count_get_count(
const mavlink_message_t* msg)
239 return _MAV_RETURN_uint16_t(msg, 0);
248 static inline void mavlink_msg_mission_count_decode(
const mavlink_message_t* msg,
mavlink_mission_count_t* mission_count)
250 #if MAVLINK_NEED_BYTE_SWAP
251 mission_count->
count = mavlink_msg_mission_count_get_count(msg);
252 mission_count->
target_system = mavlink_msg_mission_count_get_target_system(msg);
253 mission_count->
target_component = mavlink_msg_mission_count_get_target_component(msg);
uint8_t target_system
System ID.
Definition: mavlink_msg_mission_count.h:8
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
uint16_t count
Number of mission items in the sequence.
Definition: mavlink_msg_mission_count.h:7
struct __mavlink_mission_count_t mavlink_mission_count_t
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
Definition: mavlink_msg_mission_count.h:5
mavlink_channel_t
Definition: mavlink_types.h:178
#define MAVLINK_MSG_ID_MISSION_COUNT_CRC
Definition: mavlink_msg_mission_count.h:15
uint8_t target_component
Component ID.
Definition: mavlink_msg_mission_count.h:9
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
#define MAVLINK_MSG_ID_MISSION_COUNT_LEN
Definition: mavlink_msg_mission_count.h:12
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
#define MAVLINK_MSG_ID_MISSION_COUNT
Definition: mavlink_msg_mission_count.h:3
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71