mavlink_msg_hil_controls.h
Go to the documentation of this file.
00001 // MESSAGE HIL_CONTROLS PACKING
00002 
00003 #define MAVLINK_MSG_ID_HIL_CONTROLS 91
00004 
00005 typedef struct __mavlink_hil_controls_t
00006 {
00007  uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
00008  float roll_ailerons; /*< Control output -1 .. 1*/
00009  float pitch_elevator; /*< Control output -1 .. 1*/
00010  float yaw_rudder; /*< Control output -1 .. 1*/
00011  float throttle; /*< Throttle 0 .. 1*/
00012  float aux1; /*< Aux 1, -1 .. 1*/
00013  float aux2; /*< Aux 2, -1 .. 1*/
00014  float aux3; /*< Aux 3, -1 .. 1*/
00015  float aux4; /*< Aux 4, -1 .. 1*/
00016  uint8_t mode; /*< System mode (MAV_MODE)*/
00017  uint8_t nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/
00018 } mavlink_hil_controls_t;
00019 
00020 #define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42
00021 #define MAVLINK_MSG_ID_91_LEN 42
00022 
00023 #define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63
00024 #define MAVLINK_MSG_ID_91_CRC 63
00025 
00026 
00027 
00028 #define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \
00029         "HIL_CONTROLS", \
00030         11, \
00031         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \
00032          { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \
00033          { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \
00034          { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \
00035          { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \
00036          { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \
00037          { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \
00038          { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \
00039          { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \
00040          { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \
00041          { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \
00042          } \
00043 }
00044 
00045 
00065 static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00066                                                        uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
00067 {
00068 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00069         char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN];
00070         _mav_put_uint64_t(buf, 0, time_usec);
00071         _mav_put_float(buf, 8, roll_ailerons);
00072         _mav_put_float(buf, 12, pitch_elevator);
00073         _mav_put_float(buf, 16, yaw_rudder);
00074         _mav_put_float(buf, 20, throttle);
00075         _mav_put_float(buf, 24, aux1);
00076         _mav_put_float(buf, 28, aux2);
00077         _mav_put_float(buf, 32, aux3);
00078         _mav_put_float(buf, 36, aux4);
00079         _mav_put_uint8_t(buf, 40, mode);
00080         _mav_put_uint8_t(buf, 41, nav_mode);
00081 
00082         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00083 #else
00084         mavlink_hil_controls_t packet;
00085         packet.time_usec = time_usec;
00086         packet.roll_ailerons = roll_ailerons;
00087         packet.pitch_elevator = pitch_elevator;
00088         packet.yaw_rudder = yaw_rudder;
00089         packet.throttle = throttle;
00090         packet.aux1 = aux1;
00091         packet.aux2 = aux2;
00092         packet.aux3 = aux3;
00093         packet.aux4 = aux4;
00094         packet.mode = mode;
00095         packet.nav_mode = nav_mode;
00096 
00097         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00098 #endif
00099 
00100         msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
00101 #if MAVLINK_CRC_EXTRA
00102     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
00103 #else
00104     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00105 #endif
00106 }
00107 
00127 static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00128                                                            mavlink_message_t* msg,
00129                                                            uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode)
00130 {
00131 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00132         char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN];
00133         _mav_put_uint64_t(buf, 0, time_usec);
00134         _mav_put_float(buf, 8, roll_ailerons);
00135         _mav_put_float(buf, 12, pitch_elevator);
00136         _mav_put_float(buf, 16, yaw_rudder);
00137         _mav_put_float(buf, 20, throttle);
00138         _mav_put_float(buf, 24, aux1);
00139         _mav_put_float(buf, 28, aux2);
00140         _mav_put_float(buf, 32, aux3);
00141         _mav_put_float(buf, 36, aux4);
00142         _mav_put_uint8_t(buf, 40, mode);
00143         _mav_put_uint8_t(buf, 41, nav_mode);
00144 
00145         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00146 #else
00147         mavlink_hil_controls_t packet;
00148         packet.time_usec = time_usec;
00149         packet.roll_ailerons = roll_ailerons;
00150         packet.pitch_elevator = pitch_elevator;
00151         packet.yaw_rudder = yaw_rudder;
00152         packet.throttle = throttle;
00153         packet.aux1 = aux1;
00154         packet.aux2 = aux2;
00155         packet.aux3 = aux3;
00156         packet.aux4 = aux4;
00157         packet.mode = mode;
00158         packet.nav_mode = nav_mode;
00159 
00160         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00161 #endif
00162 
00163         msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
00164 #if MAVLINK_CRC_EXTRA
00165     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
00166 #else
00167     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00168 #endif
00169 }
00170 
00179 static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
00180 {
00181         return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode);
00182 }
00183 
00193 static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
00194 {
00195         return mavlink_msg_hil_controls_pack_chan(system_id, component_id, chan, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode);
00196 }
00197 
00214 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00215 
00216 static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
00217 {
00218 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00219         char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN];
00220         _mav_put_uint64_t(buf, 0, time_usec);
00221         _mav_put_float(buf, 8, roll_ailerons);
00222         _mav_put_float(buf, 12, pitch_elevator);
00223         _mav_put_float(buf, 16, yaw_rudder);
00224         _mav_put_float(buf, 20, throttle);
00225         _mav_put_float(buf, 24, aux1);
00226         _mav_put_float(buf, 28, aux2);
00227         _mav_put_float(buf, 32, aux3);
00228         _mav_put_float(buf, 36, aux4);
00229         _mav_put_uint8_t(buf, 40, mode);
00230         _mav_put_uint8_t(buf, 41, nav_mode);
00231 
00232 #if MAVLINK_CRC_EXTRA
00233     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
00234 #else
00235     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00236 #endif
00237 #else
00238         mavlink_hil_controls_t packet;
00239         packet.time_usec = time_usec;
00240         packet.roll_ailerons = roll_ailerons;
00241         packet.pitch_elevator = pitch_elevator;
00242         packet.yaw_rudder = yaw_rudder;
00243         packet.throttle = throttle;
00244         packet.aux1 = aux1;
00245         packet.aux2 = aux2;
00246         packet.aux3 = aux3;
00247         packet.aux4 = aux4;
00248         packet.mode = mode;
00249         packet.nav_mode = nav_mode;
00250 
00251 #if MAVLINK_CRC_EXTRA
00252     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
00253 #else
00254     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00255 #endif
00256 #endif
00257 }
00258 
00259 #if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00260 /*
00261   This varient of _send() can be used to save stack space by re-using
00262   memory from the receive buffer.  The caller provides a
00263   mavlink_message_t which is the size of a full mavlink message. This
00264   is usually the receive buffer for the channel, and allows a reply to an
00265   incoming message with minimum stack space usage.
00266  */
00267 static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
00268 {
00269 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00270         char *buf = (char *)msgbuf;
00271         _mav_put_uint64_t(buf, 0, time_usec);
00272         _mav_put_float(buf, 8, roll_ailerons);
00273         _mav_put_float(buf, 12, pitch_elevator);
00274         _mav_put_float(buf, 16, yaw_rudder);
00275         _mav_put_float(buf, 20, throttle);
00276         _mav_put_float(buf, 24, aux1);
00277         _mav_put_float(buf, 28, aux2);
00278         _mav_put_float(buf, 32, aux3);
00279         _mav_put_float(buf, 36, aux4);
00280         _mav_put_uint8_t(buf, 40, mode);
00281         _mav_put_uint8_t(buf, 41, nav_mode);
00282 
00283 #if MAVLINK_CRC_EXTRA
00284     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
00285 #else
00286     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00287 #endif
00288 #else
00289         mavlink_hil_controls_t *packet = (mavlink_hil_controls_t *)msgbuf;
00290         packet->time_usec = time_usec;
00291         packet->roll_ailerons = roll_ailerons;
00292         packet->pitch_elevator = pitch_elevator;
00293         packet->yaw_rudder = yaw_rudder;
00294         packet->throttle = throttle;
00295         packet->aux1 = aux1;
00296         packet->aux2 = aux2;
00297         packet->aux3 = aux3;
00298         packet->aux4 = aux4;
00299         packet->mode = mode;
00300         packet->nav_mode = nav_mode;
00301 
00302 #if MAVLINK_CRC_EXTRA
00303     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
00304 #else
00305     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00306 #endif
00307 #endif
00308 }
00309 #endif
00310 
00311 #endif
00312 
00313 // MESSAGE HIL_CONTROLS UNPACKING
00314 
00315 
00321 static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg)
00322 {
00323         return _MAV_RETURN_uint64_t(msg,  0);
00324 }
00325 
00331 static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg)
00332 {
00333         return _MAV_RETURN_float(msg,  8);
00334 }
00335 
00341 static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg)
00342 {
00343         return _MAV_RETURN_float(msg,  12);
00344 }
00345 
00351 static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg)
00352 {
00353         return _MAV_RETURN_float(msg,  16);
00354 }
00355 
00361 static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg)
00362 {
00363         return _MAV_RETURN_float(msg,  20);
00364 }
00365 
00371 static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg)
00372 {
00373         return _MAV_RETURN_float(msg,  24);
00374 }
00375 
00381 static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg)
00382 {
00383         return _MAV_RETURN_float(msg,  28);
00384 }
00385 
00391 static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg)
00392 {
00393         return _MAV_RETURN_float(msg,  32);
00394 }
00395 
00401 static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg)
00402 {
00403         return _MAV_RETURN_float(msg,  36);
00404 }
00405 
00411 static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg)
00412 {
00413         return _MAV_RETURN_uint8_t(msg,  40);
00414 }
00415 
00421 static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg)
00422 {
00423         return _MAV_RETURN_uint8_t(msg,  41);
00424 }
00425 
00432 static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls)
00433 {
00434 #if MAVLINK_NEED_BYTE_SWAP
00435         hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg);
00436         hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg);
00437         hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg);
00438         hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg);
00439         hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg);
00440         hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg);
00441         hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg);
00442         hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg);
00443         hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg);
00444         hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg);
00445         hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg);
00446 #else
00447         memcpy(hil_controls, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
00448 #endif
00449 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35