mavlink_msg_hil_state_quaternion.h
Go to the documentation of this file.
00001 // MESSAGE HIL_STATE_QUATERNION PACKING
00002 
00003 #define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115
00004 
00005 typedef struct __mavlink_hil_state_quaternion_t
00006 {
00007  uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
00008  float attitude_quaternion[4]; /*< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)*/
00009  float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/
00010  float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/
00011  float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/
00012  int32_t lat; /*< Latitude, expressed as * 1E7*/
00013  int32_t lon; /*< Longitude, expressed as * 1E7*/
00014  int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/
00015  int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/
00016  int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/
00017  int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/
00018  uint16_t ind_airspeed; /*< Indicated airspeed, expressed as m/s * 100*/
00019  uint16_t true_airspeed; /*< True airspeed, expressed as m/s * 100*/
00020  int16_t xacc; /*< X acceleration (mg)*/
00021  int16_t yacc; /*< Y acceleration (mg)*/
00022  int16_t zacc; /*< Z acceleration (mg)*/
00023 } mavlink_hil_state_quaternion_t;
00024 
00025 #define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64
00026 #define MAVLINK_MSG_ID_115_LEN 64
00027 
00028 #define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4
00029 #define MAVLINK_MSG_ID_115_CRC 4
00030 
00031 #define MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_ATTITUDE_QUATERNION_LEN 4
00032 
00033 #define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \
00034         "HIL_STATE_QUATERNION", \
00035         16, \
00036         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \
00037          { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \
00038          { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \
00039          { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \
00040          { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \
00041          { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \
00042          { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \
00043          { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \
00044          { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \
00045          { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \
00046          { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \
00047          { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \
00048          { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \
00049          { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \
00050          { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \
00051          { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \
00052          } \
00053 }
00054 
00055 
00080 static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00081                                                        uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc)
00082 {
00083 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00084         char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN];
00085         _mav_put_uint64_t(buf, 0, time_usec);
00086         _mav_put_float(buf, 24, rollspeed);
00087         _mav_put_float(buf, 28, pitchspeed);
00088         _mav_put_float(buf, 32, yawspeed);
00089         _mav_put_int32_t(buf, 36, lat);
00090         _mav_put_int32_t(buf, 40, lon);
00091         _mav_put_int32_t(buf, 44, alt);
00092         _mav_put_int16_t(buf, 48, vx);
00093         _mav_put_int16_t(buf, 50, vy);
00094         _mav_put_int16_t(buf, 52, vz);
00095         _mav_put_uint16_t(buf, 54, ind_airspeed);
00096         _mav_put_uint16_t(buf, 56, true_airspeed);
00097         _mav_put_int16_t(buf, 58, xacc);
00098         _mav_put_int16_t(buf, 60, yacc);
00099         _mav_put_int16_t(buf, 62, zacc);
00100         _mav_put_float_array(buf, 8, attitude_quaternion, 4);
00101         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00102 #else
00103         mavlink_hil_state_quaternion_t packet;
00104         packet.time_usec = time_usec;
00105         packet.rollspeed = rollspeed;
00106         packet.pitchspeed = pitchspeed;
00107         packet.yawspeed = yawspeed;
00108         packet.lat = lat;
00109         packet.lon = lon;
00110         packet.alt = alt;
00111         packet.vx = vx;
00112         packet.vy = vy;
00113         packet.vz = vz;
00114         packet.ind_airspeed = ind_airspeed;
00115         packet.true_airspeed = true_airspeed;
00116         packet.xacc = xacc;
00117         packet.yacc = yacc;
00118         packet.zacc = zacc;
00119         mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4);
00120         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00121 #endif
00122 
00123         msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION;
00124 #if MAVLINK_CRC_EXTRA
00125     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
00126 #else
00127     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00128 #endif
00129 }
00130 
00155 static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00156                                                            mavlink_message_t* msg,
00157                                                            uint64_t time_usec,const float *attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t ind_airspeed,uint16_t true_airspeed,int16_t xacc,int16_t yacc,int16_t zacc)
00158 {
00159 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00160         char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN];
00161         _mav_put_uint64_t(buf, 0, time_usec);
00162         _mav_put_float(buf, 24, rollspeed);
00163         _mav_put_float(buf, 28, pitchspeed);
00164         _mav_put_float(buf, 32, yawspeed);
00165         _mav_put_int32_t(buf, 36, lat);
00166         _mav_put_int32_t(buf, 40, lon);
00167         _mav_put_int32_t(buf, 44, alt);
00168         _mav_put_int16_t(buf, 48, vx);
00169         _mav_put_int16_t(buf, 50, vy);
00170         _mav_put_int16_t(buf, 52, vz);
00171         _mav_put_uint16_t(buf, 54, ind_airspeed);
00172         _mav_put_uint16_t(buf, 56, true_airspeed);
00173         _mav_put_int16_t(buf, 58, xacc);
00174         _mav_put_int16_t(buf, 60, yacc);
00175         _mav_put_int16_t(buf, 62, zacc);
00176         _mav_put_float_array(buf, 8, attitude_quaternion, 4);
00177         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00178 #else
00179         mavlink_hil_state_quaternion_t packet;
00180         packet.time_usec = time_usec;
00181         packet.rollspeed = rollspeed;
00182         packet.pitchspeed = pitchspeed;
00183         packet.yawspeed = yawspeed;
00184         packet.lat = lat;
00185         packet.lon = lon;
00186         packet.alt = alt;
00187         packet.vx = vx;
00188         packet.vy = vy;
00189         packet.vz = vz;
00190         packet.ind_airspeed = ind_airspeed;
00191         packet.true_airspeed = true_airspeed;
00192         packet.xacc = xacc;
00193         packet.yacc = yacc;
00194         packet.zacc = zacc;
00195         mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4);
00196         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00197 #endif
00198 
00199         msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION;
00200 #if MAVLINK_CRC_EXTRA
00201     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
00202 #else
00203     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00204 #endif
00205 }
00206 
00215 static inline uint16_t mavlink_msg_hil_state_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion)
00216 {
00217         return mavlink_msg_hil_state_quaternion_pack(system_id, component_id, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc);
00218 }
00219 
00229 static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion)
00230 {
00231         return mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, chan, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc);
00232 }
00233 
00255 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00256 
00257 static inline void mavlink_msg_hil_state_quaternion_send(mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc)
00258 {
00259 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00260         char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN];
00261         _mav_put_uint64_t(buf, 0, time_usec);
00262         _mav_put_float(buf, 24, rollspeed);
00263         _mav_put_float(buf, 28, pitchspeed);
00264         _mav_put_float(buf, 32, yawspeed);
00265         _mav_put_int32_t(buf, 36, lat);
00266         _mav_put_int32_t(buf, 40, lon);
00267         _mav_put_int32_t(buf, 44, alt);
00268         _mav_put_int16_t(buf, 48, vx);
00269         _mav_put_int16_t(buf, 50, vy);
00270         _mav_put_int16_t(buf, 52, vz);
00271         _mav_put_uint16_t(buf, 54, ind_airspeed);
00272         _mav_put_uint16_t(buf, 56, true_airspeed);
00273         _mav_put_int16_t(buf, 58, xacc);
00274         _mav_put_int16_t(buf, 60, yacc);
00275         _mav_put_int16_t(buf, 62, zacc);
00276         _mav_put_float_array(buf, 8, attitude_quaternion, 4);
00277 #if MAVLINK_CRC_EXTRA
00278     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
00279 #else
00280     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00281 #endif
00282 #else
00283         mavlink_hil_state_quaternion_t packet;
00284         packet.time_usec = time_usec;
00285         packet.rollspeed = rollspeed;
00286         packet.pitchspeed = pitchspeed;
00287         packet.yawspeed = yawspeed;
00288         packet.lat = lat;
00289         packet.lon = lon;
00290         packet.alt = alt;
00291         packet.vx = vx;
00292         packet.vy = vy;
00293         packet.vz = vz;
00294         packet.ind_airspeed = ind_airspeed;
00295         packet.true_airspeed = true_airspeed;
00296         packet.xacc = xacc;
00297         packet.yacc = yacc;
00298         packet.zacc = zacc;
00299         mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4);
00300 #if MAVLINK_CRC_EXTRA
00301     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
00302 #else
00303     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00304 #endif
00305 #endif
00306 }
00307 
00308 #if MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00309 /*
00310   This varient of _send() can be used to save stack space by re-using
00311   memory from the receive buffer.  The caller provides a
00312   mavlink_message_t which is the size of a full mavlink message. This
00313   is usually the receive buffer for the channel, and allows a reply to an
00314   incoming message with minimum stack space usage.
00315  */
00316 static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc)
00317 {
00318 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00319         char *buf = (char *)msgbuf;
00320         _mav_put_uint64_t(buf, 0, time_usec);
00321         _mav_put_float(buf, 24, rollspeed);
00322         _mav_put_float(buf, 28, pitchspeed);
00323         _mav_put_float(buf, 32, yawspeed);
00324         _mav_put_int32_t(buf, 36, lat);
00325         _mav_put_int32_t(buf, 40, lon);
00326         _mav_put_int32_t(buf, 44, alt);
00327         _mav_put_int16_t(buf, 48, vx);
00328         _mav_put_int16_t(buf, 50, vy);
00329         _mav_put_int16_t(buf, 52, vz);
00330         _mav_put_uint16_t(buf, 54, ind_airspeed);
00331         _mav_put_uint16_t(buf, 56, true_airspeed);
00332         _mav_put_int16_t(buf, 58, xacc);
00333         _mav_put_int16_t(buf, 60, yacc);
00334         _mav_put_int16_t(buf, 62, zacc);
00335         _mav_put_float_array(buf, 8, attitude_quaternion, 4);
00336 #if MAVLINK_CRC_EXTRA
00337     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
00338 #else
00339     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00340 #endif
00341 #else
00342         mavlink_hil_state_quaternion_t *packet = (mavlink_hil_state_quaternion_t *)msgbuf;
00343         packet->time_usec = time_usec;
00344         packet->rollspeed = rollspeed;
00345         packet->pitchspeed = pitchspeed;
00346         packet->yawspeed = yawspeed;
00347         packet->lat = lat;
00348         packet->lon = lon;
00349         packet->alt = alt;
00350         packet->vx = vx;
00351         packet->vy = vy;
00352         packet->vz = vz;
00353         packet->ind_airspeed = ind_airspeed;
00354         packet->true_airspeed = true_airspeed;
00355         packet->xacc = xacc;
00356         packet->yacc = yacc;
00357         packet->zacc = zacc;
00358         mav_array_memcpy(packet->attitude_quaternion, attitude_quaternion, sizeof(float)*4);
00359 #if MAVLINK_CRC_EXTRA
00360     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
00361 #else
00362     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00363 #endif
00364 #endif
00365 }
00366 #endif
00367 
00368 #endif
00369 
00370 // MESSAGE HIL_STATE_QUATERNION UNPACKING
00371 
00372 
00378 static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg)
00379 {
00380         return _MAV_RETURN_uint64_t(msg,  0);
00381 }
00382 
00388 static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion)
00389 {
00390         return _MAV_RETURN_float_array(msg, attitude_quaternion, 4,  8);
00391 }
00392 
00398 static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg)
00399 {
00400         return _MAV_RETURN_float(msg,  24);
00401 }
00402 
00408 static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg)
00409 {
00410         return _MAV_RETURN_float(msg,  28);
00411 }
00412 
00418 static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg)
00419 {
00420         return _MAV_RETURN_float(msg,  32);
00421 }
00422 
00428 static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg)
00429 {
00430         return _MAV_RETURN_int32_t(msg,  36);
00431 }
00432 
00438 static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg)
00439 {
00440         return _MAV_RETURN_int32_t(msg,  40);
00441 }
00442 
00448 static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg)
00449 {
00450         return _MAV_RETURN_int32_t(msg,  44);
00451 }
00452 
00458 static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg)
00459 {
00460         return _MAV_RETURN_int16_t(msg,  48);
00461 }
00462 
00468 static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg)
00469 {
00470         return _MAV_RETURN_int16_t(msg,  50);
00471 }
00472 
00478 static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg)
00479 {
00480         return _MAV_RETURN_int16_t(msg,  52);
00481 }
00482 
00488 static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg)
00489 {
00490         return _MAV_RETURN_uint16_t(msg,  54);
00491 }
00492 
00498 static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg)
00499 {
00500         return _MAV_RETURN_uint16_t(msg,  56);
00501 }
00502 
00508 static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg)
00509 {
00510         return _MAV_RETURN_int16_t(msg,  58);
00511 }
00512 
00518 static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg)
00519 {
00520         return _MAV_RETURN_int16_t(msg,  60);
00521 }
00522 
00528 static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg)
00529 {
00530         return _MAV_RETURN_int16_t(msg,  62);
00531 }
00532 
00539 static inline void mavlink_msg_hil_state_quaternion_decode(const mavlink_message_t* msg, mavlink_hil_state_quaternion_t* hil_state_quaternion)
00540 {
00541 #if MAVLINK_NEED_BYTE_SWAP
00542         hil_state_quaternion->time_usec = mavlink_msg_hil_state_quaternion_get_time_usec(msg);
00543         mavlink_msg_hil_state_quaternion_get_attitude_quaternion(msg, hil_state_quaternion->attitude_quaternion);
00544         hil_state_quaternion->rollspeed = mavlink_msg_hil_state_quaternion_get_rollspeed(msg);
00545         hil_state_quaternion->pitchspeed = mavlink_msg_hil_state_quaternion_get_pitchspeed(msg);
00546         hil_state_quaternion->yawspeed = mavlink_msg_hil_state_quaternion_get_yawspeed(msg);
00547         hil_state_quaternion->lat = mavlink_msg_hil_state_quaternion_get_lat(msg);
00548         hil_state_quaternion->lon = mavlink_msg_hil_state_quaternion_get_lon(msg);
00549         hil_state_quaternion->alt = mavlink_msg_hil_state_quaternion_get_alt(msg);
00550         hil_state_quaternion->vx = mavlink_msg_hil_state_quaternion_get_vx(msg);
00551         hil_state_quaternion->vy = mavlink_msg_hil_state_quaternion_get_vy(msg);
00552         hil_state_quaternion->vz = mavlink_msg_hil_state_quaternion_get_vz(msg);
00553         hil_state_quaternion->ind_airspeed = mavlink_msg_hil_state_quaternion_get_ind_airspeed(msg);
00554         hil_state_quaternion->true_airspeed = mavlink_msg_hil_state_quaternion_get_true_airspeed(msg);
00555         hil_state_quaternion->xacc = mavlink_msg_hil_state_quaternion_get_xacc(msg);
00556         hil_state_quaternion->yacc = mavlink_msg_hil_state_quaternion_get_yacc(msg);
00557         hil_state_quaternion->zacc = mavlink_msg_hil_state_quaternion_get_zacc(msg);
00558 #else
00559         memcpy(hil_state_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
00560 #endif
00561 }


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