3 #define MAVLINK_MSG_ID_MISSION_REQUEST 40 12 #define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 13 #define MAVLINK_MSG_ID_40_LEN 4 15 #define MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230 16 #define MAVLINK_MSG_ID_40_CRC 230 20 #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ 23 { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ 24 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ 25 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ 44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 80 mavlink_message_t* msg,
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 100 #if MAVLINK_CRC_EXTRA 142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 152 #if MAVLINK_CRC_EXTRA 163 #if MAVLINK_CRC_EXTRA 171 #if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN 181 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 182 char *buf = (
char *)msgbuf;
187 #if MAVLINK_CRC_EXTRA 198 #if MAVLINK_CRC_EXTRA 239 return _MAV_RETURN_uint16_t(msg, 0);
250 #if MAVLINK_NEED_BYTE_SWAP static uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t *msg)
Send a mission_request message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN
static uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_mission_request_t *mission_request)
Encode a mission_request struct.
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.
#define _mav_put_uint8_t(buf, wire_offset, b)
static uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint16_t seq)
Pack a mission_request message.
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t *msg)
Get field seq from mission_request message.
#define _MAV_PAYLOAD(msg)
struct __mavlink_mission_request_t mavlink_mission_request_t
#define MAVLINK_MSG_ID_MISSION_REQUEST
static void mavlink_msg_mission_request_decode(const mavlink_message_t *msg, mavlink_mission_request_t *mission_request)
Decode a mission_request message into a struct.
static uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t *msg)
Get field target_component from mission_request message.
#define MAVLINK_MSG_ID_MISSION_REQUEST_CRC
static uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_mission_request_t *mission_request)
Encode a mission_request struct on a channel.
#define _mav_put_uint16_t(buf, wire_offset, b)
static uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint16_t seq)
Pack a mission_request message on a channel.
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.