mavlink_msg_hil_state.h
Go to the documentation of this file.
00001 // MESSAGE HIL_STATE PACKING
00002 
00003 #define MAVLINK_MSG_ID_HIL_STATE 90
00004 
00005 typedef struct __mavlink_hil_state_t
00006 {
00007  uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
00008  float roll; /*< Roll angle (rad)*/
00009  float pitch; /*< Pitch angle (rad)*/
00010  float yaw; /*< Yaw angle (rad)*/
00011  float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/
00012  float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/
00013  float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/
00014  int32_t lat; /*< Latitude, expressed as * 1E7*/
00015  int32_t lon; /*< Longitude, expressed as * 1E7*/
00016  int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/
00017  int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/
00018  int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/
00019  int16_t vz; /*< Ground Z Speed (Altitude), 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_t;
00024 
00025 #define MAVLINK_MSG_ID_HIL_STATE_LEN 56
00026 #define MAVLINK_MSG_ID_90_LEN 56
00027 
00028 #define MAVLINK_MSG_ID_HIL_STATE_CRC 183
00029 #define MAVLINK_MSG_ID_90_CRC 183
00030 
00031 
00032 
00033 #define MAVLINK_MESSAGE_INFO_HIL_STATE { \
00034         "HIL_STATE", \
00035         16, \
00036         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \
00037          { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
00038          { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
00039          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
00040          { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \
00041          { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \
00042          { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \
00043          { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \
00044          { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \
00045          { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \
00046          { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \
00047          { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \
00048          { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \
00049          { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \
00050          { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \
00051          { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \
00052          } \
00053 }
00054 
00055 
00080 static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00081                                                        uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, 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_LEN];
00085         _mav_put_uint64_t(buf, 0, time_usec);
00086         _mav_put_float(buf, 8, roll);
00087         _mav_put_float(buf, 12, pitch);
00088         _mav_put_float(buf, 16, yaw);
00089         _mav_put_float(buf, 20, rollspeed);
00090         _mav_put_float(buf, 24, pitchspeed);
00091         _mav_put_float(buf, 28, yawspeed);
00092         _mav_put_int32_t(buf, 32, lat);
00093         _mav_put_int32_t(buf, 36, lon);
00094         _mav_put_int32_t(buf, 40, alt);
00095         _mav_put_int16_t(buf, 44, vx);
00096         _mav_put_int16_t(buf, 46, vy);
00097         _mav_put_int16_t(buf, 48, vz);
00098         _mav_put_int16_t(buf, 50, xacc);
00099         _mav_put_int16_t(buf, 52, yacc);
00100         _mav_put_int16_t(buf, 54, zacc);
00101 
00102         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN);
00103 #else
00104         mavlink_hil_state_t packet;
00105         packet.time_usec = time_usec;
00106         packet.roll = roll;
00107         packet.pitch = pitch;
00108         packet.yaw = yaw;
00109         packet.rollspeed = rollspeed;
00110         packet.pitchspeed = pitchspeed;
00111         packet.yawspeed = yawspeed;
00112         packet.lat = lat;
00113         packet.lon = lon;
00114         packet.alt = alt;
00115         packet.vx = vx;
00116         packet.vy = vy;
00117         packet.vz = vz;
00118         packet.xacc = xacc;
00119         packet.yacc = yacc;
00120         packet.zacc = zacc;
00121 
00122         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN);
00123 #endif
00124 
00125         msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
00126 #if MAVLINK_CRC_EXTRA
00127     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
00128 #else
00129     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN);
00130 #endif
00131 }
00132 
00157 static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00158                                                            mavlink_message_t* msg,
00159                                                            uint64_t time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc)
00160 {
00161 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00162         char buf[MAVLINK_MSG_ID_HIL_STATE_LEN];
00163         _mav_put_uint64_t(buf, 0, time_usec);
00164         _mav_put_float(buf, 8, roll);
00165         _mav_put_float(buf, 12, pitch);
00166         _mav_put_float(buf, 16, yaw);
00167         _mav_put_float(buf, 20, rollspeed);
00168         _mav_put_float(buf, 24, pitchspeed);
00169         _mav_put_float(buf, 28, yawspeed);
00170         _mav_put_int32_t(buf, 32, lat);
00171         _mav_put_int32_t(buf, 36, lon);
00172         _mav_put_int32_t(buf, 40, alt);
00173         _mav_put_int16_t(buf, 44, vx);
00174         _mav_put_int16_t(buf, 46, vy);
00175         _mav_put_int16_t(buf, 48, vz);
00176         _mav_put_int16_t(buf, 50, xacc);
00177         _mav_put_int16_t(buf, 52, yacc);
00178         _mav_put_int16_t(buf, 54, zacc);
00179 
00180         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN);
00181 #else
00182         mavlink_hil_state_t packet;
00183         packet.time_usec = time_usec;
00184         packet.roll = roll;
00185         packet.pitch = pitch;
00186         packet.yaw = yaw;
00187         packet.rollspeed = rollspeed;
00188         packet.pitchspeed = pitchspeed;
00189         packet.yawspeed = yawspeed;
00190         packet.lat = lat;
00191         packet.lon = lon;
00192         packet.alt = alt;
00193         packet.vx = vx;
00194         packet.vy = vy;
00195         packet.vz = vz;
00196         packet.xacc = xacc;
00197         packet.yacc = yacc;
00198         packet.zacc = zacc;
00199 
00200         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN);
00201 #endif
00202 
00203         msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
00204 #if MAVLINK_CRC_EXTRA
00205     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
00206 #else
00207     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN);
00208 #endif
00209 }
00210 
00219 static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
00220 {
00221         return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
00222 }
00223 
00233 static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
00234 {
00235         return mavlink_msg_hil_state_pack_chan(system_id, component_id, chan, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
00236 }
00237 
00259 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00260 
00261 static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
00262 {
00263 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00264         char buf[MAVLINK_MSG_ID_HIL_STATE_LEN];
00265         _mav_put_uint64_t(buf, 0, time_usec);
00266         _mav_put_float(buf, 8, roll);
00267         _mav_put_float(buf, 12, pitch);
00268         _mav_put_float(buf, 16, yaw);
00269         _mav_put_float(buf, 20, rollspeed);
00270         _mav_put_float(buf, 24, pitchspeed);
00271         _mav_put_float(buf, 28, yawspeed);
00272         _mav_put_int32_t(buf, 32, lat);
00273         _mav_put_int32_t(buf, 36, lon);
00274         _mav_put_int32_t(buf, 40, alt);
00275         _mav_put_int16_t(buf, 44, vx);
00276         _mav_put_int16_t(buf, 46, vy);
00277         _mav_put_int16_t(buf, 48, vz);
00278         _mav_put_int16_t(buf, 50, xacc);
00279         _mav_put_int16_t(buf, 52, yacc);
00280         _mav_put_int16_t(buf, 54, zacc);
00281 
00282 #if MAVLINK_CRC_EXTRA
00283     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
00284 #else
00285     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN);
00286 #endif
00287 #else
00288         mavlink_hil_state_t packet;
00289         packet.time_usec = time_usec;
00290         packet.roll = roll;
00291         packet.pitch = pitch;
00292         packet.yaw = yaw;
00293         packet.rollspeed = rollspeed;
00294         packet.pitchspeed = pitchspeed;
00295         packet.yawspeed = yawspeed;
00296         packet.lat = lat;
00297         packet.lon = lon;
00298         packet.alt = alt;
00299         packet.vx = vx;
00300         packet.vy = vy;
00301         packet.vz = vz;
00302         packet.xacc = xacc;
00303         packet.yacc = yacc;
00304         packet.zacc = zacc;
00305 
00306 #if MAVLINK_CRC_EXTRA
00307     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
00308 #else
00309     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN);
00310 #endif
00311 #endif
00312 }
00313 
00314 #if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00315 /*
00316   This varient of _send() can be used to save stack space by re-using
00317   memory from the receive buffer.  The caller provides a
00318   mavlink_message_t which is the size of a full mavlink message. This
00319   is usually the receive buffer for the channel, and allows a reply to an
00320   incoming message with minimum stack space usage.
00321  */
00322 static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
00323 {
00324 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00325         char *buf = (char *)msgbuf;
00326         _mav_put_uint64_t(buf, 0, time_usec);
00327         _mav_put_float(buf, 8, roll);
00328         _mav_put_float(buf, 12, pitch);
00329         _mav_put_float(buf, 16, yaw);
00330         _mav_put_float(buf, 20, rollspeed);
00331         _mav_put_float(buf, 24, pitchspeed);
00332         _mav_put_float(buf, 28, yawspeed);
00333         _mav_put_int32_t(buf, 32, lat);
00334         _mav_put_int32_t(buf, 36, lon);
00335         _mav_put_int32_t(buf, 40, alt);
00336         _mav_put_int16_t(buf, 44, vx);
00337         _mav_put_int16_t(buf, 46, vy);
00338         _mav_put_int16_t(buf, 48, vz);
00339         _mav_put_int16_t(buf, 50, xacc);
00340         _mav_put_int16_t(buf, 52, yacc);
00341         _mav_put_int16_t(buf, 54, zacc);
00342 
00343 #if MAVLINK_CRC_EXTRA
00344     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
00345 #else
00346     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN);
00347 #endif
00348 #else
00349         mavlink_hil_state_t *packet = (mavlink_hil_state_t *)msgbuf;
00350         packet->time_usec = time_usec;
00351         packet->roll = roll;
00352         packet->pitch = pitch;
00353         packet->yaw = yaw;
00354         packet->rollspeed = rollspeed;
00355         packet->pitchspeed = pitchspeed;
00356         packet->yawspeed = yawspeed;
00357         packet->lat = lat;
00358         packet->lon = lon;
00359         packet->alt = alt;
00360         packet->vx = vx;
00361         packet->vy = vy;
00362         packet->vz = vz;
00363         packet->xacc = xacc;
00364         packet->yacc = yacc;
00365         packet->zacc = zacc;
00366 
00367 #if MAVLINK_CRC_EXTRA
00368     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
00369 #else
00370     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN);
00371 #endif
00372 #endif
00373 }
00374 #endif
00375 
00376 #endif
00377 
00378 // MESSAGE HIL_STATE UNPACKING
00379 
00380 
00386 static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg)
00387 {
00388         return _MAV_RETURN_uint64_t(msg,  0);
00389 }
00390 
00396 static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
00397 {
00398         return _MAV_RETURN_float(msg,  8);
00399 }
00400 
00406 static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg)
00407 {
00408         return _MAV_RETURN_float(msg,  12);
00409 }
00410 
00416 static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
00417 {
00418         return _MAV_RETURN_float(msg,  16);
00419 }
00420 
00426 static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg)
00427 {
00428         return _MAV_RETURN_float(msg,  20);
00429 }
00430 
00436 static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg)
00437 {
00438         return _MAV_RETURN_float(msg,  24);
00439 }
00440 
00446 static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg)
00447 {
00448         return _MAV_RETURN_float(msg,  28);
00449 }
00450 
00456 static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg)
00457 {
00458         return _MAV_RETURN_int32_t(msg,  32);
00459 }
00460 
00466 static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg)
00467 {
00468         return _MAV_RETURN_int32_t(msg,  36);
00469 }
00470 
00476 static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg)
00477 {
00478         return _MAV_RETURN_int32_t(msg,  40);
00479 }
00480 
00486 static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
00487 {
00488         return _MAV_RETURN_int16_t(msg,  44);
00489 }
00490 
00496 static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
00497 {
00498         return _MAV_RETURN_int16_t(msg,  46);
00499 }
00500 
00506 static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
00507 {
00508         return _MAV_RETURN_int16_t(msg,  48);
00509 }
00510 
00516 static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg)
00517 {
00518         return _MAV_RETURN_int16_t(msg,  50);
00519 }
00520 
00526 static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg)
00527 {
00528         return _MAV_RETURN_int16_t(msg,  52);
00529 }
00530 
00536 static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg)
00537 {
00538         return _MAV_RETURN_int16_t(msg,  54);
00539 }
00540 
00547 static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state)
00548 {
00549 #if MAVLINK_NEED_BYTE_SWAP
00550         hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg);
00551         hil_state->roll = mavlink_msg_hil_state_get_roll(msg);
00552         hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg);
00553         hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg);
00554         hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg);
00555         hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg);
00556         hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg);
00557         hil_state->lat = mavlink_msg_hil_state_get_lat(msg);
00558         hil_state->lon = mavlink_msg_hil_state_get_lon(msg);
00559         hil_state->alt = mavlink_msg_hil_state_get_alt(msg);
00560         hil_state->vx = mavlink_msg_hil_state_get_vx(msg);
00561         hil_state->vy = mavlink_msg_hil_state_get_vy(msg);
00562         hil_state->vz = mavlink_msg_hil_state_get_vz(msg);
00563         hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg);
00564         hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg);
00565         hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg);
00566 #else
00567         memcpy(hil_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_LEN);
00568 #endif
00569 }


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