4#define MAVLINK_MSG_ID_ASL_OBCTRL 207 
    7typedef struct __mavlink_asl_obctrl_t {
 
   15 uint8_t obctrl_status; 
 
   16}) mavlink_asl_obctrl_t;
 
   18#define MAVLINK_MSG_ID_ASL_OBCTRL_LEN 33 
   19#define MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN 33 
   20#define MAVLINK_MSG_ID_207_LEN 33 
   21#define MAVLINK_MSG_ID_207_MIN_LEN 33 
   23#define MAVLINK_MSG_ID_ASL_OBCTRL_CRC 234 
   24#define MAVLINK_MSG_ID_207_CRC 234 
   28#if MAVLINK_COMMAND_24BIT 
   29#define MAVLINK_MESSAGE_INFO_ASL_OBCTRL { \ 
   33    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_asl_obctrl_t, timestamp) }, \ 
   34         { "uElev", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_asl_obctrl_t, uElev) }, \ 
   35         { "uThrot", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_asl_obctrl_t, uThrot) }, \ 
   36         { "uThrot2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_asl_obctrl_t, uThrot2) }, \ 
   37         { "uAilL", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_asl_obctrl_t, uAilL) }, \ 
   38         { "uAilR", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_asl_obctrl_t, uAilR) }, \ 
   39         { "uRud", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_asl_obctrl_t, uRud) }, \ 
   40         { "obctrl_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_asl_obctrl_t, obctrl_status) }, \ 
   44#define MAVLINK_MESSAGE_INFO_ASL_OBCTRL { \ 
   47    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_asl_obctrl_t, timestamp) }, \ 
   48         { "uElev", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_asl_obctrl_t, uElev) }, \ 
   49         { "uThrot", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_asl_obctrl_t, uThrot) }, \ 
   50         { "uThrot2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_asl_obctrl_t, uThrot2) }, \ 
   51         { "uAilL", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_asl_obctrl_t, uAilL) }, \ 
   52         { "uAilR", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_asl_obctrl_t, uAilR) }, \ 
   53         { "uRud", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_asl_obctrl_t, uRud) }, \ 
   54         { "obctrl_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_asl_obctrl_t, obctrl_status) }, \ 
   75static inline uint16_t mavlink_msg_asl_obctrl_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
 
   76                               uint64_t timestamp, 
float uElev, 
float uThrot, 
float uThrot2, 
float uAilL, 
float uAilR, 
float uRud, uint8_t obctrl_status)
 
   78#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
   79 char buf[MAVLINK_MSG_ID_ASL_OBCTRL_LEN];
 
   80    _mav_put_uint64_t(buf, 0, timestamp);
 
   81    _mav_put_float(buf, 8, uElev);
 
   82    _mav_put_float(buf, 12, uThrot);
 
   83    _mav_put_float(buf, 16, uThrot2);
 
   84    _mav_put_float(buf, 20, uAilL);
 
   85    _mav_put_float(buf, 24, uAilR);
 
   86    _mav_put_float(buf, 28, uRud);
 
   87    _mav_put_uint8_t(buf, 32, obctrl_status);
 
   89        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ASL_OBCTRL_LEN);
 
   91    mavlink_asl_obctrl_t packet;
 
   92    packet.timestamp = timestamp;
 
   94    packet.uThrot = uThrot;
 
   95    packet.uThrot2 = uThrot2;
 
   99    packet.obctrl_status = obctrl_status;
 
  101        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ASL_OBCTRL_LEN);
 
  104    msg->msgid = MAVLINK_MSG_ID_ASL_OBCTRL;
 
  105 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_CRC);
 
  124static inline uint16_t mavlink_msg_asl_obctrl_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
 
  125                               mavlink_message_t* msg,
 
  126                                   uint64_t timestamp,
float uElev,
float uThrot,
float uThrot2,
float uAilL,
float uAilR,
float uRud,uint8_t obctrl_status)
 
  128#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  129 char buf[MAVLINK_MSG_ID_ASL_OBCTRL_LEN];
 
  130    _mav_put_uint64_t(buf, 0, timestamp);
 
  131    _mav_put_float(buf, 8, uElev);
 
  132    _mav_put_float(buf, 12, uThrot);
 
  133    _mav_put_float(buf, 16, uThrot2);
 
  134    _mav_put_float(buf, 20, uAilL);
 
  135    _mav_put_float(buf, 24, uAilR);
 
  136    _mav_put_float(buf, 28, uRud);
 
  137    _mav_put_uint8_t(buf, 32, obctrl_status);
 
  139        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ASL_OBCTRL_LEN);
 
  141    mavlink_asl_obctrl_t packet;
 
  142    packet.timestamp = timestamp;
 
  143    packet.uElev = uElev;
 
  144    packet.uThrot = uThrot;
 
  145    packet.uThrot2 = uThrot2;
 
  146    packet.uAilL = uAilL;
 
  147    packet.uAilR = uAilR;
 
  149    packet.obctrl_status = obctrl_status;
 
  151        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ASL_OBCTRL_LEN);
 
  154    msg->msgid = MAVLINK_MSG_ID_ASL_OBCTRL;
 
  155 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_CRC);
 
  166static inline uint16_t mavlink_msg_asl_obctrl_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 
const mavlink_asl_obctrl_t* asl_obctrl)
 
  168 return mavlink_msg_asl_obctrl_pack(system_id, component_id, msg, asl_obctrl->timestamp, asl_obctrl->uElev, asl_obctrl->uThrot, asl_obctrl->uThrot2, asl_obctrl->uAilL, asl_obctrl->uAilR, asl_obctrl->uRud, asl_obctrl->obctrl_status);
 
  180static inline uint16_t mavlink_msg_asl_obctrl_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, 
const mavlink_asl_obctrl_t* asl_obctrl)
 
  182 return mavlink_msg_asl_obctrl_pack_chan(system_id, component_id, chan, msg, asl_obctrl->timestamp, asl_obctrl->uElev, asl_obctrl->uThrot, asl_obctrl->uThrot2, asl_obctrl->uAilL, asl_obctrl->uAilR, asl_obctrl->uRud, asl_obctrl->obctrl_status);
 
  198#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 
  200static inline void mavlink_msg_asl_obctrl_send(mavlink_channel_t chan, uint64_t timestamp, 
float uElev, 
float uThrot, 
float uThrot2, 
float uAilL, 
float uAilR, 
float uRud, uint8_t obctrl_status)
 
  202#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  203 char buf[MAVLINK_MSG_ID_ASL_OBCTRL_LEN];
 
  204    _mav_put_uint64_t(buf, 0, timestamp);
 
  205    _mav_put_float(buf, 8, uElev);
 
  206    _mav_put_float(buf, 12, uThrot);
 
  207    _mav_put_float(buf, 16, uThrot2);
 
  208    _mav_put_float(buf, 20, uAilL);
 
  209    _mav_put_float(buf, 24, uAilR);
 
  210    _mav_put_float(buf, 28, uRud);
 
  211    _mav_put_uint8_t(buf, 32, obctrl_status);
 
  213    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ASL_OBCTRL, buf, MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_CRC);
 
  215    mavlink_asl_obctrl_t packet;
 
  216    packet.timestamp = timestamp;
 
  217    packet.uElev = uElev;
 
  218    packet.uThrot = uThrot;
 
  219    packet.uThrot2 = uThrot2;
 
  220    packet.uAilL = uAilL;
 
  221    packet.uAilR = uAilR;
 
  223    packet.obctrl_status = obctrl_status;
 
  225    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ASL_OBCTRL, (
const char *)&packet, MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_CRC);
 
  234static inline void mavlink_msg_asl_obctrl_send_struct(mavlink_channel_t chan, 
const mavlink_asl_obctrl_t* asl_obctrl)
 
  236#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  237    mavlink_msg_asl_obctrl_send(chan, asl_obctrl->timestamp, asl_obctrl->uElev, asl_obctrl->uThrot, asl_obctrl->uThrot2, asl_obctrl->uAilL, asl_obctrl->uAilR, asl_obctrl->uRud, asl_obctrl->obctrl_status);
 
  239    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ASL_OBCTRL, (
const char *)asl_obctrl, MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_CRC);
 
  243#if MAVLINK_MSG_ID_ASL_OBCTRL_LEN <= MAVLINK_MAX_PAYLOAD_LEN 
  251static inline void mavlink_msg_asl_obctrl_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, 
float uElev, 
float uThrot, 
float uThrot2, 
float uAilL, 
float uAilR, 
float uRud, uint8_t obctrl_status)
 
  253#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  254 char *buf = (
char *)msgbuf;
 
  255    _mav_put_uint64_t(buf, 0, timestamp);
 
  256    _mav_put_float(buf, 8, uElev);
 
  257    _mav_put_float(buf, 12, uThrot);
 
  258    _mav_put_float(buf, 16, uThrot2);
 
  259    _mav_put_float(buf, 20, uAilL);
 
  260    _mav_put_float(buf, 24, uAilR);
 
  261    _mav_put_float(buf, 28, uRud);
 
  262    _mav_put_uint8_t(buf, 32, obctrl_status);
 
  264    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ASL_OBCTRL, buf, MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_CRC);
 
  266    mavlink_asl_obctrl_t *packet = (mavlink_asl_obctrl_t *)msgbuf;
 
  267    packet->timestamp = timestamp;
 
  268    packet->uElev = uElev;
 
  269    packet->uThrot = uThrot;
 
  270    packet->uThrot2 = uThrot2;
 
  271    packet->uAilL = uAilL;
 
  272    packet->uAilR = uAilR;
 
  274    packet->obctrl_status = obctrl_status;
 
  276    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ASL_OBCTRL, (
const char *)packet, MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_CRC);
 
  291static inline uint64_t mavlink_msg_asl_obctrl_get_timestamp(
const mavlink_message_t* msg)
 
  293 return _MAV_RETURN_uint64_t(msg,  0);
 
  301static inline float mavlink_msg_asl_obctrl_get_uElev(
const mavlink_message_t* msg)
 
  303 return _MAV_RETURN_float(msg,  8);
 
  311static inline float mavlink_msg_asl_obctrl_get_uThrot(
const mavlink_message_t* msg)
 
  313 return _MAV_RETURN_float(msg,  12);
 
  321static inline float mavlink_msg_asl_obctrl_get_uThrot2(
const mavlink_message_t* msg)
 
  323 return _MAV_RETURN_float(msg,  16);
 
  331static inline float mavlink_msg_asl_obctrl_get_uAilL(
const mavlink_message_t* msg)
 
  333 return _MAV_RETURN_float(msg,  20);
 
  341static inline float mavlink_msg_asl_obctrl_get_uAilR(
const mavlink_message_t* msg)
 
  343 return _MAV_RETURN_float(msg,  24);
 
  351static inline float mavlink_msg_asl_obctrl_get_uRud(
const mavlink_message_t* msg)
 
  353 return _MAV_RETURN_float(msg,  28);
 
  361static inline uint8_t mavlink_msg_asl_obctrl_get_obctrl_status(
const mavlink_message_t* msg)
 
  363 return _MAV_RETURN_uint8_t(msg,  32);
 
  372static inline void mavlink_msg_asl_obctrl_decode(
const mavlink_message_t* msg, mavlink_asl_obctrl_t* asl_obctrl)
 
  374#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 
  375    asl_obctrl->timestamp = mavlink_msg_asl_obctrl_get_timestamp(msg);
 
  376    asl_obctrl->uElev = mavlink_msg_asl_obctrl_get_uElev(msg);
 
  377    asl_obctrl->uThrot = mavlink_msg_asl_obctrl_get_uThrot(msg);
 
  378    asl_obctrl->uThrot2 = mavlink_msg_asl_obctrl_get_uThrot2(msg);
 
  379    asl_obctrl->uAilL = mavlink_msg_asl_obctrl_get_uAilL(msg);
 
  380    asl_obctrl->uAilR = mavlink_msg_asl_obctrl_get_uAilR(msg);
 
  381    asl_obctrl->uRud = mavlink_msg_asl_obctrl_get_uRud(msg);
 
  382    asl_obctrl->obctrl_status = mavlink_msg_asl_obctrl_get_obctrl_status(msg);
 
  384        uint8_t len = msg->len < MAVLINK_MSG_ID_ASL_OBCTRL_LEN? msg->len : MAVLINK_MSG_ID_ASL_OBCTRL_LEN;
 
  385        memset(asl_obctrl, 0, MAVLINK_MSG_ID_ASL_OBCTRL_LEN);
 
  386    memcpy(asl_obctrl, _MAV_PAYLOAD(msg), len);