3 #define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37
13 #define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6
14 #define MAVLINK_MSG_ID_37_LEN 6
16 #define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212
17 #define MAVLINK_MSG_ID_37_CRC 212
21 #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \
22 "MISSION_REQUEST_PARTIAL_LIST", \
24 { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \
25 { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \
26 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \
27 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \
44 static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45 uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
85 static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
86 mavlink_message_t* msg,
87 uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index)
89 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108 #if MAVLINK_CRC_EXTRA
123 static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_mission_request_partial_list_t* mission_request_partial_list)
125 return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->
target_system, mission_request_partial_list->
target_component, mission_request_partial_list->
start_index, mission_request_partial_list->
end_index);
137 static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_mission_request_partial_list_t* mission_request_partial_list)
139 return mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, chan, msg, mission_request_partial_list->
target_system, mission_request_partial_list->
target_component, mission_request_partial_list->
start_index, mission_request_partial_list->
end_index);
151 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
153 static inline void mavlink_msg_mission_request_partial_list_send(
mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
155 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
162 #if MAVLINK_CRC_EXTRA
174 #if MAVLINK_CRC_EXTRA
182 #if MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
190 static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
192 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193 char *buf = (
char *)msgbuf;
199 #if MAVLINK_CRC_EXTRA
211 #if MAVLINK_CRC_EXTRA
230 static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(
const mavlink_message_t* msg)
240 static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(
const mavlink_message_t* msg)
250 static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(
const mavlink_message_t* msg)
252 return _MAV_RETURN_int16_t(msg, 0);
260 static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(
const mavlink_message_t* msg)
262 return _MAV_RETURN_int16_t(msg, 2);
273 #if MAVLINK_NEED_BYTE_SWAP
274 mission_request_partial_list->
start_index = mavlink_msg_mission_request_partial_list_get_start_index(msg);
275 mission_request_partial_list->
end_index = mavlink_msg_mission_request_partial_list_get_end_index(msg);
276 mission_request_partial_list->
target_system = mavlink_msg_mission_request_partial_list_get_target_system(msg);
277 mission_request_partial_list->
target_component = mavlink_msg_mission_request_partial_list_get_target_component(msg);
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN
Definition: mavlink_msg_mission_request_partial_list.h:13
uint8_t target_system
System ID.
Definition: mavlink_msg_mission_request_partial_list.h:9
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
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
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
int16_t start_index
Start index, 0 by default.
Definition: mavlink_msg_mission_request_partial_list.h:7
Definition: mavlink_msg_mission_request_partial_list.h:5
uint8_t target_component
Component ID.
Definition: mavlink_msg_mission_request_partial_list.h:10
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST
Definition: mavlink_msg_mission_request_partial_list.h:3
struct __mavlink_mission_request_partial_list_t mavlink_mission_request_partial_list_t
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
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:140
int16_t end_index
End index, -1 by default (-1: send list to end). Else a valid index of the list.
Definition: mavlink_msg_mission_request_partial_list.h:8
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC
Definition: mavlink_msg_mission_request_partial_list.h:16