4#define MAVLINK_MSG_ID_MISSION_REQUEST_INT 51 
    7typedef struct __mavlink_mission_request_int_t {
 
   10 uint8_t target_component; 
 
   12}) mavlink_mission_request_int_t;
 
   14#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN 5 
   15#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN 4 
   16#define MAVLINK_MSG_ID_51_LEN 5 
   17#define MAVLINK_MSG_ID_51_MIN_LEN 4 
   19#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC 196 
   20#define MAVLINK_MSG_ID_51_CRC 196 
   24#if MAVLINK_COMMAND_24BIT 
   25#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ 
   27    "MISSION_REQUEST_INT", \ 
   29    {  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ 
   30         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ 
   31         { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ 
   32         { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_int_t, mission_type) }, \ 
   36#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ 
   37    "MISSION_REQUEST_INT", \ 
   39    {  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ 
   40         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ 
   41         { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ 
   42         { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_int_t, mission_type) }, \ 
   59static inline uint16_t mavlink_msg_mission_request_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
 
   60                               uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
 
   62#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
   63 char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN];
 
   64    _mav_put_uint16_t(buf, 0, seq);
 
   65    _mav_put_uint8_t(buf, 2, target_system);
 
   66    _mav_put_uint8_t(buf, 3, target_component);
 
   67    _mav_put_uint8_t(buf, 4, mission_type);
 
   69        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN);
 
   71    mavlink_mission_request_int_t packet;
 
   73    packet.target_system = target_system;
 
   74    packet.target_component = target_component;
 
   75    packet.mission_type = mission_type;
 
   77        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN);
 
   80    msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT;
 
   81 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
 
   96static inline uint16_t mavlink_msg_mission_request_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
 
   97                               mavlink_message_t* msg,
 
   98                                   uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t mission_type)
 
  100#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  101 char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN];
 
  102    _mav_put_uint16_t(buf, 0, seq);
 
  103    _mav_put_uint8_t(buf, 2, target_system);
 
  104    _mav_put_uint8_t(buf, 3, target_component);
 
  105    _mav_put_uint8_t(buf, 4, mission_type);
 
  107        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN);
 
  109    mavlink_mission_request_int_t packet;
 
  111    packet.target_system = target_system;
 
  112    packet.target_component = target_component;
 
  113    packet.mission_type = mission_type;
 
  115        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN);
 
  118    msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT;
 
  119 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
 
  130static inline uint16_t mavlink_msg_mission_request_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 
const mavlink_mission_request_int_t* mission_request_int)
 
  132 return mavlink_msg_mission_request_int_pack(system_id, component_id, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type);
 
  144static inline uint16_t mavlink_msg_mission_request_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, 
const mavlink_mission_request_int_t* mission_request_int)
 
  146 return mavlink_msg_mission_request_int_pack_chan(system_id, component_id, chan, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type);
 
  158#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 
  160static inline void mavlink_msg_mission_request_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
 
  162#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  163 char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN];
 
  164    _mav_put_uint16_t(buf, 0, seq);
 
  165    _mav_put_uint8_t(buf, 2, target_system);
 
  166    _mav_put_uint8_t(buf, 3, target_component);
 
  167    _mav_put_uint8_t(buf, 4, mission_type);
 
  169    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
 
  171    mavlink_mission_request_int_t packet;
 
  173    packet.target_system = target_system;
 
  174    packet.target_component = target_component;
 
  175    packet.mission_type = mission_type;
 
  177    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (
const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
 
  186static inline void mavlink_msg_mission_request_int_send_struct(mavlink_channel_t chan, 
const mavlink_mission_request_int_t* mission_request_int)
 
  188#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  189    mavlink_msg_mission_request_int_send(chan, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type);
 
  191    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (
const char *)mission_request_int, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
 
  195#if MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN 
  203static inline void mavlink_msg_mission_request_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
 
  205#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  206 char *buf = (
char *)msgbuf;
 
  207    _mav_put_uint16_t(buf, 0, seq);
 
  208    _mav_put_uint8_t(buf, 2, target_system);
 
  209    _mav_put_uint8_t(buf, 3, target_component);
 
  210    _mav_put_uint8_t(buf, 4, mission_type);
 
  212    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
 
  214    mavlink_mission_request_int_t *packet = (mavlink_mission_request_int_t *)msgbuf;
 
  216    packet->target_system = target_system;
 
  217    packet->target_component = target_component;
 
  218    packet->mission_type = mission_type;
 
  220    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (
const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
 
  235static inline uint8_t mavlink_msg_mission_request_int_get_target_system(
const mavlink_message_t* msg)
 
  237 return _MAV_RETURN_uint8_t(msg,  2);
 
  245static inline uint8_t mavlink_msg_mission_request_int_get_target_component(
const mavlink_message_t* msg)
 
  247 return _MAV_RETURN_uint8_t(msg,  3);
 
  255static inline uint16_t mavlink_msg_mission_request_int_get_seq(
const mavlink_message_t* msg)
 
  257 return _MAV_RETURN_uint16_t(msg,  0);
 
  265static inline uint8_t mavlink_msg_mission_request_int_get_mission_type(
const mavlink_message_t* msg)
 
  267 return _MAV_RETURN_uint8_t(msg,  4);
 
  276static inline void mavlink_msg_mission_request_int_decode(
const mavlink_message_t* msg, mavlink_mission_request_int_t* mission_request_int)
 
  278#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  279    mission_request_int->seq = mavlink_msg_mission_request_int_get_seq(msg);
 
  280    mission_request_int->target_system = mavlink_msg_mission_request_int_get_target_system(msg);
 
  281    mission_request_int->target_component = mavlink_msg_mission_request_int_get_target_component(msg);
 
  282    mission_request_int->mission_type = mavlink_msg_mission_request_int_get_mission_type(msg);
 
  284        uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN;
 
  285        memset(mission_request_int, 0, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN);
 
  286    memcpy(mission_request_int, _MAV_PAYLOAD(msg), len);