mavlink_msg_sim_state.h
Go to the documentation of this file.
00001 // MESSAGE SIM_STATE PACKING
00002 
00003 #define MAVLINK_MSG_ID_SIM_STATE 108
00004 
00005 typedef struct __mavlink_sim_state_t
00006 {
00007  float q1; /*< True attitude quaternion component 1, w (1 in null-rotation)*/
00008  float q2; /*< True attitude quaternion component 2, x (0 in null-rotation)*/
00009  float q3; /*< True attitude quaternion component 3, y (0 in null-rotation)*/
00010  float q4; /*< True attitude quaternion component 4, z (0 in null-rotation)*/
00011  float roll; /*< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs*/
00012  float pitch; /*< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs*/
00013  float yaw; /*< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs*/
00014  float xacc; /*< X acceleration m/s/s*/
00015  float yacc; /*< Y acceleration m/s/s*/
00016  float zacc; /*< Z acceleration m/s/s*/
00017  float xgyro; /*< Angular speed around X axis rad/s*/
00018  float ygyro; /*< Angular speed around Y axis rad/s*/
00019  float zgyro; /*< Angular speed around Z axis rad/s*/
00020  float lat; /*< Latitude in degrees*/
00021  float lon; /*< Longitude in degrees*/
00022  float alt; /*< Altitude in meters*/
00023  float std_dev_horz; /*< Horizontal position standard deviation*/
00024  float std_dev_vert; /*< Vertical position standard deviation*/
00025  float vn; /*< True velocity in m/s in NORTH direction in earth-fixed NED frame*/
00026  float ve; /*< True velocity in m/s in EAST direction in earth-fixed NED frame*/
00027  float vd; /*< True velocity in m/s in DOWN direction in earth-fixed NED frame*/
00028 } mavlink_sim_state_t;
00029 
00030 #define MAVLINK_MSG_ID_SIM_STATE_LEN 84
00031 #define MAVLINK_MSG_ID_108_LEN 84
00032 
00033 #define MAVLINK_MSG_ID_SIM_STATE_CRC 32
00034 #define MAVLINK_MSG_ID_108_CRC 32
00035 
00036 
00037 
00038 #define MAVLINK_MESSAGE_INFO_SIM_STATE { \
00039         "SIM_STATE", \
00040         21, \
00041         {  { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \
00042          { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \
00043          { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \
00044          { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \
00045          { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \
00046          { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \
00047          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \
00048          { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \
00049          { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \
00050          { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \
00051          { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \
00052          { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \
00053          { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \
00054          { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \
00055          { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \
00056          { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \
00057          { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \
00058          { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \
00059          { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \
00060          { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \
00061          { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \
00062          } \
00063 }
00064 
00065 
00095 static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00096                                                        float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd)
00097 {
00098 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00099         char buf[MAVLINK_MSG_ID_SIM_STATE_LEN];
00100         _mav_put_float(buf, 0, q1);
00101         _mav_put_float(buf, 4, q2);
00102         _mav_put_float(buf, 8, q3);
00103         _mav_put_float(buf, 12, q4);
00104         _mav_put_float(buf, 16, roll);
00105         _mav_put_float(buf, 20, pitch);
00106         _mav_put_float(buf, 24, yaw);
00107         _mav_put_float(buf, 28, xacc);
00108         _mav_put_float(buf, 32, yacc);
00109         _mav_put_float(buf, 36, zacc);
00110         _mav_put_float(buf, 40, xgyro);
00111         _mav_put_float(buf, 44, ygyro);
00112         _mav_put_float(buf, 48, zgyro);
00113         _mav_put_float(buf, 52, lat);
00114         _mav_put_float(buf, 56, lon);
00115         _mav_put_float(buf, 60, alt);
00116         _mav_put_float(buf, 64, std_dev_horz);
00117         _mav_put_float(buf, 68, std_dev_vert);
00118         _mav_put_float(buf, 72, vn);
00119         _mav_put_float(buf, 76, ve);
00120         _mav_put_float(buf, 80, vd);
00121 
00122         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN);
00123 #else
00124         mavlink_sim_state_t packet;
00125         packet.q1 = q1;
00126         packet.q2 = q2;
00127         packet.q3 = q3;
00128         packet.q4 = q4;
00129         packet.roll = roll;
00130         packet.pitch = pitch;
00131         packet.yaw = yaw;
00132         packet.xacc = xacc;
00133         packet.yacc = yacc;
00134         packet.zacc = zacc;
00135         packet.xgyro = xgyro;
00136         packet.ygyro = ygyro;
00137         packet.zgyro = zgyro;
00138         packet.lat = lat;
00139         packet.lon = lon;
00140         packet.alt = alt;
00141         packet.std_dev_horz = std_dev_horz;
00142         packet.std_dev_vert = std_dev_vert;
00143         packet.vn = vn;
00144         packet.ve = ve;
00145         packet.vd = vd;
00146 
00147         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN);
00148 #endif
00149 
00150         msg->msgid = MAVLINK_MSG_ID_SIM_STATE;
00151 #if MAVLINK_CRC_EXTRA
00152     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
00153 #else
00154     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN);
00155 #endif
00156 }
00157 
00187 static inline uint16_t mavlink_msg_sim_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00188                                                            mavlink_message_t* msg,
00189                                                            float q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd)
00190 {
00191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00192         char buf[MAVLINK_MSG_ID_SIM_STATE_LEN];
00193         _mav_put_float(buf, 0, q1);
00194         _mav_put_float(buf, 4, q2);
00195         _mav_put_float(buf, 8, q3);
00196         _mav_put_float(buf, 12, q4);
00197         _mav_put_float(buf, 16, roll);
00198         _mav_put_float(buf, 20, pitch);
00199         _mav_put_float(buf, 24, yaw);
00200         _mav_put_float(buf, 28, xacc);
00201         _mav_put_float(buf, 32, yacc);
00202         _mav_put_float(buf, 36, zacc);
00203         _mav_put_float(buf, 40, xgyro);
00204         _mav_put_float(buf, 44, ygyro);
00205         _mav_put_float(buf, 48, zgyro);
00206         _mav_put_float(buf, 52, lat);
00207         _mav_put_float(buf, 56, lon);
00208         _mav_put_float(buf, 60, alt);
00209         _mav_put_float(buf, 64, std_dev_horz);
00210         _mav_put_float(buf, 68, std_dev_vert);
00211         _mav_put_float(buf, 72, vn);
00212         _mav_put_float(buf, 76, ve);
00213         _mav_put_float(buf, 80, vd);
00214 
00215         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN);
00216 #else
00217         mavlink_sim_state_t packet;
00218         packet.q1 = q1;
00219         packet.q2 = q2;
00220         packet.q3 = q3;
00221         packet.q4 = q4;
00222         packet.roll = roll;
00223         packet.pitch = pitch;
00224         packet.yaw = yaw;
00225         packet.xacc = xacc;
00226         packet.yacc = yacc;
00227         packet.zacc = zacc;
00228         packet.xgyro = xgyro;
00229         packet.ygyro = ygyro;
00230         packet.zgyro = zgyro;
00231         packet.lat = lat;
00232         packet.lon = lon;
00233         packet.alt = alt;
00234         packet.std_dev_horz = std_dev_horz;
00235         packet.std_dev_vert = std_dev_vert;
00236         packet.vn = vn;
00237         packet.ve = ve;
00238         packet.vd = vd;
00239 
00240         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN);
00241 #endif
00242 
00243         msg->msgid = MAVLINK_MSG_ID_SIM_STATE;
00244 #if MAVLINK_CRC_EXTRA
00245     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
00246 #else
00247     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN);
00248 #endif
00249 }
00250 
00259 static inline uint16_t mavlink_msg_sim_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state)
00260 {
00261         return mavlink_msg_sim_state_pack(system_id, component_id, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd);
00262 }
00263 
00273 static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state)
00274 {
00275         return mavlink_msg_sim_state_pack_chan(system_id, component_id, chan, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd);
00276 }
00277 
00304 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00305 
00306 static inline void mavlink_msg_sim_state_send(mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd)
00307 {
00308 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00309         char buf[MAVLINK_MSG_ID_SIM_STATE_LEN];
00310         _mav_put_float(buf, 0, q1);
00311         _mav_put_float(buf, 4, q2);
00312         _mav_put_float(buf, 8, q3);
00313         _mav_put_float(buf, 12, q4);
00314         _mav_put_float(buf, 16, roll);
00315         _mav_put_float(buf, 20, pitch);
00316         _mav_put_float(buf, 24, yaw);
00317         _mav_put_float(buf, 28, xacc);
00318         _mav_put_float(buf, 32, yacc);
00319         _mav_put_float(buf, 36, zacc);
00320         _mav_put_float(buf, 40, xgyro);
00321         _mav_put_float(buf, 44, ygyro);
00322         _mav_put_float(buf, 48, zgyro);
00323         _mav_put_float(buf, 52, lat);
00324         _mav_put_float(buf, 56, lon);
00325         _mav_put_float(buf, 60, alt);
00326         _mav_put_float(buf, 64, std_dev_horz);
00327         _mav_put_float(buf, 68, std_dev_vert);
00328         _mav_put_float(buf, 72, vn);
00329         _mav_put_float(buf, 76, ve);
00330         _mav_put_float(buf, 80, vd);
00331 
00332 #if MAVLINK_CRC_EXTRA
00333     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
00334 #else
00335     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN);
00336 #endif
00337 #else
00338         mavlink_sim_state_t packet;
00339         packet.q1 = q1;
00340         packet.q2 = q2;
00341         packet.q3 = q3;
00342         packet.q4 = q4;
00343         packet.roll = roll;
00344         packet.pitch = pitch;
00345         packet.yaw = yaw;
00346         packet.xacc = xacc;
00347         packet.yacc = yacc;
00348         packet.zacc = zacc;
00349         packet.xgyro = xgyro;
00350         packet.ygyro = ygyro;
00351         packet.zgyro = zgyro;
00352         packet.lat = lat;
00353         packet.lon = lon;
00354         packet.alt = alt;
00355         packet.std_dev_horz = std_dev_horz;
00356         packet.std_dev_vert = std_dev_vert;
00357         packet.vn = vn;
00358         packet.ve = ve;
00359         packet.vd = vd;
00360 
00361 #if MAVLINK_CRC_EXTRA
00362     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
00363 #else
00364     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN);
00365 #endif
00366 #endif
00367 }
00368 
00369 #if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00370 /*
00371   This varient of _send() can be used to save stack space by re-using
00372   memory from the receive buffer.  The caller provides a
00373   mavlink_message_t which is the size of a full mavlink message. This
00374   is usually the receive buffer for the channel, and allows a reply to an
00375   incoming message with minimum stack space usage.
00376  */
00377 static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd)
00378 {
00379 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00380         char *buf = (char *)msgbuf;
00381         _mav_put_float(buf, 0, q1);
00382         _mav_put_float(buf, 4, q2);
00383         _mav_put_float(buf, 8, q3);
00384         _mav_put_float(buf, 12, q4);
00385         _mav_put_float(buf, 16, roll);
00386         _mav_put_float(buf, 20, pitch);
00387         _mav_put_float(buf, 24, yaw);
00388         _mav_put_float(buf, 28, xacc);
00389         _mav_put_float(buf, 32, yacc);
00390         _mav_put_float(buf, 36, zacc);
00391         _mav_put_float(buf, 40, xgyro);
00392         _mav_put_float(buf, 44, ygyro);
00393         _mav_put_float(buf, 48, zgyro);
00394         _mav_put_float(buf, 52, lat);
00395         _mav_put_float(buf, 56, lon);
00396         _mav_put_float(buf, 60, alt);
00397         _mav_put_float(buf, 64, std_dev_horz);
00398         _mav_put_float(buf, 68, std_dev_vert);
00399         _mav_put_float(buf, 72, vn);
00400         _mav_put_float(buf, 76, ve);
00401         _mav_put_float(buf, 80, vd);
00402 
00403 #if MAVLINK_CRC_EXTRA
00404     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
00405 #else
00406     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN);
00407 #endif
00408 #else
00409         mavlink_sim_state_t *packet = (mavlink_sim_state_t *)msgbuf;
00410         packet->q1 = q1;
00411         packet->q2 = q2;
00412         packet->q3 = q3;
00413         packet->q4 = q4;
00414         packet->roll = roll;
00415         packet->pitch = pitch;
00416         packet->yaw = yaw;
00417         packet->xacc = xacc;
00418         packet->yacc = yacc;
00419         packet->zacc = zacc;
00420         packet->xgyro = xgyro;
00421         packet->ygyro = ygyro;
00422         packet->zgyro = zgyro;
00423         packet->lat = lat;
00424         packet->lon = lon;
00425         packet->alt = alt;
00426         packet->std_dev_horz = std_dev_horz;
00427         packet->std_dev_vert = std_dev_vert;
00428         packet->vn = vn;
00429         packet->ve = ve;
00430         packet->vd = vd;
00431 
00432 #if MAVLINK_CRC_EXTRA
00433     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
00434 #else
00435     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN);
00436 #endif
00437 #endif
00438 }
00439 #endif
00440 
00441 #endif
00442 
00443 // MESSAGE SIM_STATE UNPACKING
00444 
00445 
00451 static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg)
00452 {
00453         return _MAV_RETURN_float(msg,  0);
00454 }
00455 
00461 static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg)
00462 {
00463         return _MAV_RETURN_float(msg,  4);
00464 }
00465 
00471 static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg)
00472 {
00473         return _MAV_RETURN_float(msg,  8);
00474 }
00475 
00481 static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg)
00482 {
00483         return _MAV_RETURN_float(msg,  12);
00484 }
00485 
00491 static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg)
00492 {
00493         return _MAV_RETURN_float(msg,  16);
00494 }
00495 
00501 static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg)
00502 {
00503         return _MAV_RETURN_float(msg,  20);
00504 }
00505 
00511 static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg)
00512 {
00513         return _MAV_RETURN_float(msg,  24);
00514 }
00515 
00521 static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t* msg)
00522 {
00523         return _MAV_RETURN_float(msg,  28);
00524 }
00525 
00531 static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t* msg)
00532 {
00533         return _MAV_RETURN_float(msg,  32);
00534 }
00535 
00541 static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t* msg)
00542 {
00543         return _MAV_RETURN_float(msg,  36);
00544 }
00545 
00551 static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t* msg)
00552 {
00553         return _MAV_RETURN_float(msg,  40);
00554 }
00555 
00561 static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t* msg)
00562 {
00563         return _MAV_RETURN_float(msg,  44);
00564 }
00565 
00571 static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t* msg)
00572 {
00573         return _MAV_RETURN_float(msg,  48);
00574 }
00575 
00581 static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t* msg)
00582 {
00583         return _MAV_RETURN_float(msg,  52);
00584 }
00585 
00591 static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg)
00592 {
00593         return _MAV_RETURN_float(msg,  56);
00594 }
00595 
00601 static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg)
00602 {
00603         return _MAV_RETURN_float(msg,  60);
00604 }
00605 
00611 static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t* msg)
00612 {
00613         return _MAV_RETURN_float(msg,  64);
00614 }
00615 
00621 static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t* msg)
00622 {
00623         return _MAV_RETURN_float(msg,  68);
00624 }
00625 
00631 static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg)
00632 {
00633         return _MAV_RETURN_float(msg,  72);
00634 }
00635 
00641 static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg)
00642 {
00643         return _MAV_RETURN_float(msg,  76);
00644 }
00645 
00651 static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t* msg)
00652 {
00653         return _MAV_RETURN_float(msg,  80);
00654 }
00655 
00662 static inline void mavlink_msg_sim_state_decode(const mavlink_message_t* msg, mavlink_sim_state_t* sim_state)
00663 {
00664 #if MAVLINK_NEED_BYTE_SWAP
00665         sim_state->q1 = mavlink_msg_sim_state_get_q1(msg);
00666         sim_state->q2 = mavlink_msg_sim_state_get_q2(msg);
00667         sim_state->q3 = mavlink_msg_sim_state_get_q3(msg);
00668         sim_state->q4 = mavlink_msg_sim_state_get_q4(msg);
00669         sim_state->roll = mavlink_msg_sim_state_get_roll(msg);
00670         sim_state->pitch = mavlink_msg_sim_state_get_pitch(msg);
00671         sim_state->yaw = mavlink_msg_sim_state_get_yaw(msg);
00672         sim_state->xacc = mavlink_msg_sim_state_get_xacc(msg);
00673         sim_state->yacc = mavlink_msg_sim_state_get_yacc(msg);
00674         sim_state->zacc = mavlink_msg_sim_state_get_zacc(msg);
00675         sim_state->xgyro = mavlink_msg_sim_state_get_xgyro(msg);
00676         sim_state->ygyro = mavlink_msg_sim_state_get_ygyro(msg);
00677         sim_state->zgyro = mavlink_msg_sim_state_get_zgyro(msg);
00678         sim_state->lat = mavlink_msg_sim_state_get_lat(msg);
00679         sim_state->lon = mavlink_msg_sim_state_get_lon(msg);
00680         sim_state->alt = mavlink_msg_sim_state_get_alt(msg);
00681         sim_state->std_dev_horz = mavlink_msg_sim_state_get_std_dev_horz(msg);
00682         sim_state->std_dev_vert = mavlink_msg_sim_state_get_std_dev_vert(msg);
00683         sim_state->vn = mavlink_msg_sim_state_get_vn(msg);
00684         sim_state->ve = mavlink_msg_sim_state_get_ve(msg);
00685         sim_state->vd = mavlink_msg_sim_state_get_vd(msg);
00686 #else
00687         memcpy(sim_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SIM_STATE_LEN);
00688 #endif
00689 }


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