mavlink_msg_global_position_int_cov.h
Go to the documentation of this file.
00001 // MESSAGE GLOBAL_POSITION_INT_COV PACKING
00002 
00003 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63
00004 
00005 typedef struct __mavlink_global_position_int_cov_t
00006 {
00007  uint64_t time_utc; /*< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.*/
00008  uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
00009  int32_t lat; /*< Latitude, expressed as degrees * 1E7*/
00010  int32_t lon; /*< Longitude, expressed as degrees * 1E7*/
00011  int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), above MSL*/
00012  int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/
00013  float vx; /*< Ground X Speed (Latitude), expressed as m/s*/
00014  float vy; /*< Ground Y Speed (Longitude), expressed as m/s*/
00015  float vz; /*< Ground Z Speed (Altitude), expressed as m/s*/
00016  float covariance[36]; /*< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)*/
00017  uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/
00018 } mavlink_global_position_int_cov_t;
00019 
00020 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 185
00021 #define MAVLINK_MSG_ID_63_LEN 185
00022 
00023 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 51
00024 #define MAVLINK_MSG_ID_63_CRC 51
00025 
00026 #define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36
00027 
00028 #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \
00029         "GLOBAL_POSITION_INT_COV", \
00030         11, \
00031         {  { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_utc) }, \
00032          { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, time_boot_ms) }, \
00033          { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lat) }, \
00034          { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, lon) }, \
00035          { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, alt) }, \
00036          { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \
00037          { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vx) }, \
00038          { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vy) }, \
00039          { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_int_cov_t, vz) }, \
00040          { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 40, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
00041          { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 184, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
00042          } \
00043 }
00044 
00045 
00065 static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00066                                                        uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
00067 {
00068 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00069         char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
00070         _mav_put_uint64_t(buf, 0, time_utc);
00071         _mav_put_uint32_t(buf, 8, time_boot_ms);
00072         _mav_put_int32_t(buf, 12, lat);
00073         _mav_put_int32_t(buf, 16, lon);
00074         _mav_put_int32_t(buf, 20, alt);
00075         _mav_put_int32_t(buf, 24, relative_alt);
00076         _mav_put_float(buf, 28, vx);
00077         _mav_put_float(buf, 32, vy);
00078         _mav_put_float(buf, 36, vz);
00079         _mav_put_uint8_t(buf, 184, estimator_type);
00080         _mav_put_float_array(buf, 40, covariance, 36);
00081         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00082 #else
00083         mavlink_global_position_int_cov_t packet;
00084         packet.time_utc = time_utc;
00085         packet.time_boot_ms = time_boot_ms;
00086         packet.lat = lat;
00087         packet.lon = lon;
00088         packet.alt = alt;
00089         packet.relative_alt = relative_alt;
00090         packet.vx = vx;
00091         packet.vy = vy;
00092         packet.vz = vz;
00093         packet.estimator_type = estimator_type;
00094         mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
00095         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00096 #endif
00097 
00098         msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV;
00099 #if MAVLINK_CRC_EXTRA
00100     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
00101 #else
00102     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00103 #endif
00104 }
00105 
00125 static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00126                                                            mavlink_message_t* msg,
00127                                                            uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,float vx,float vy,float vz,const float *covariance)
00128 {
00129 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00130         char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
00131         _mav_put_uint64_t(buf, 0, time_utc);
00132         _mav_put_uint32_t(buf, 8, time_boot_ms);
00133         _mav_put_int32_t(buf, 12, lat);
00134         _mav_put_int32_t(buf, 16, lon);
00135         _mav_put_int32_t(buf, 20, alt);
00136         _mav_put_int32_t(buf, 24, relative_alt);
00137         _mav_put_float(buf, 28, vx);
00138         _mav_put_float(buf, 32, vy);
00139         _mav_put_float(buf, 36, vz);
00140         _mav_put_uint8_t(buf, 184, estimator_type);
00141         _mav_put_float_array(buf, 40, covariance, 36);
00142         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00143 #else
00144         mavlink_global_position_int_cov_t packet;
00145         packet.time_utc = time_utc;
00146         packet.time_boot_ms = time_boot_ms;
00147         packet.lat = lat;
00148         packet.lon = lon;
00149         packet.alt = alt;
00150         packet.relative_alt = relative_alt;
00151         packet.vx = vx;
00152         packet.vy = vy;
00153         packet.vz = vz;
00154         packet.estimator_type = estimator_type;
00155         mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
00156         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00157 #endif
00158 
00159         msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV;
00160 #if MAVLINK_CRC_EXTRA
00161     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
00162 #else
00163     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00164 #endif
00165 }
00166 
00175 static inline uint16_t mavlink_msg_global_position_int_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov)
00176 {
00177         return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
00178 }
00179 
00189 static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov)
00190 {
00191         return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
00192 }
00193 
00210 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00211 
00212 static inline void mavlink_msg_global_position_int_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
00213 {
00214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00215         char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
00216         _mav_put_uint64_t(buf, 0, time_utc);
00217         _mav_put_uint32_t(buf, 8, time_boot_ms);
00218         _mav_put_int32_t(buf, 12, lat);
00219         _mav_put_int32_t(buf, 16, lon);
00220         _mav_put_int32_t(buf, 20, alt);
00221         _mav_put_int32_t(buf, 24, relative_alt);
00222         _mav_put_float(buf, 28, vx);
00223         _mav_put_float(buf, 32, vy);
00224         _mav_put_float(buf, 36, vz);
00225         _mav_put_uint8_t(buf, 184, estimator_type);
00226         _mav_put_float_array(buf, 40, covariance, 36);
00227 #if MAVLINK_CRC_EXTRA
00228     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
00229 #else
00230     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00231 #endif
00232 #else
00233         mavlink_global_position_int_cov_t packet;
00234         packet.time_utc = time_utc;
00235         packet.time_boot_ms = time_boot_ms;
00236         packet.lat = lat;
00237         packet.lon = lon;
00238         packet.alt = alt;
00239         packet.relative_alt = relative_alt;
00240         packet.vx = vx;
00241         packet.vy = vy;
00242         packet.vz = vz;
00243         packet.estimator_type = estimator_type;
00244         mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
00245 #if MAVLINK_CRC_EXTRA
00246     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
00247 #else
00248     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00249 #endif
00250 #endif
00251 }
00252 
00253 #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00254 /*
00255   This varient of _send() can be used to save stack space by re-using
00256   memory from the receive buffer.  The caller provides a
00257   mavlink_message_t which is the size of a full mavlink message. This
00258   is usually the receive buffer for the channel, and allows a reply to an
00259   incoming message with minimum stack space usage.
00260  */
00261 static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
00262 {
00263 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00264         char *buf = (char *)msgbuf;
00265         _mav_put_uint64_t(buf, 0, time_utc);
00266         _mav_put_uint32_t(buf, 8, time_boot_ms);
00267         _mav_put_int32_t(buf, 12, lat);
00268         _mav_put_int32_t(buf, 16, lon);
00269         _mav_put_int32_t(buf, 20, alt);
00270         _mav_put_int32_t(buf, 24, relative_alt);
00271         _mav_put_float(buf, 28, vx);
00272         _mav_put_float(buf, 32, vy);
00273         _mav_put_float(buf, 36, vz);
00274         _mav_put_uint8_t(buf, 184, estimator_type);
00275         _mav_put_float_array(buf, 40, covariance, 36);
00276 #if MAVLINK_CRC_EXTRA
00277     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
00278 #else
00279     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00280 #endif
00281 #else
00282         mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_t *)msgbuf;
00283         packet->time_utc = time_utc;
00284         packet->time_boot_ms = time_boot_ms;
00285         packet->lat = lat;
00286         packet->lon = lon;
00287         packet->alt = alt;
00288         packet->relative_alt = relative_alt;
00289         packet->vx = vx;
00290         packet->vy = vy;
00291         packet->vz = vz;
00292         packet->estimator_type = estimator_type;
00293         mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36);
00294 #if MAVLINK_CRC_EXTRA
00295     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
00296 #else
00297     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00298 #endif
00299 #endif
00300 }
00301 #endif
00302 
00303 #endif
00304 
00305 // MESSAGE GLOBAL_POSITION_INT_COV UNPACKING
00306 
00307 
00313 static inline uint32_t mavlink_msg_global_position_int_cov_get_time_boot_ms(const mavlink_message_t* msg)
00314 {
00315         return _MAV_RETURN_uint32_t(msg,  8);
00316 }
00317 
00323 static inline uint64_t mavlink_msg_global_position_int_cov_get_time_utc(const mavlink_message_t* msg)
00324 {
00325         return _MAV_RETURN_uint64_t(msg,  0);
00326 }
00327 
00333 static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg)
00334 {
00335         return _MAV_RETURN_uint8_t(msg,  184);
00336 }
00337 
00343 static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg)
00344 {
00345         return _MAV_RETURN_int32_t(msg,  12);
00346 }
00347 
00353 static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg)
00354 {
00355         return _MAV_RETURN_int32_t(msg,  16);
00356 }
00357 
00363 static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg)
00364 {
00365         return _MAV_RETURN_int32_t(msg,  20);
00366 }
00367 
00373 static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg)
00374 {
00375         return _MAV_RETURN_int32_t(msg,  24);
00376 }
00377 
00383 static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg)
00384 {
00385         return _MAV_RETURN_float(msg,  28);
00386 }
00387 
00393 static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg)
00394 {
00395         return _MAV_RETURN_float(msg,  32);
00396 }
00397 
00403 static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg)
00404 {
00405         return _MAV_RETURN_float(msg,  36);
00406 }
00407 
00413 static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
00414 {
00415         return _MAV_RETURN_float_array(msg, covariance, 36,  40);
00416 }
00417 
00424 static inline void mavlink_msg_global_position_int_cov_decode(const mavlink_message_t* msg, mavlink_global_position_int_cov_t* global_position_int_cov)
00425 {
00426 #if MAVLINK_NEED_BYTE_SWAP
00427         global_position_int_cov->time_utc = mavlink_msg_global_position_int_cov_get_time_utc(msg);
00428         global_position_int_cov->time_boot_ms = mavlink_msg_global_position_int_cov_get_time_boot_ms(msg);
00429         global_position_int_cov->lat = mavlink_msg_global_position_int_cov_get_lat(msg);
00430         global_position_int_cov->lon = mavlink_msg_global_position_int_cov_get_lon(msg);
00431         global_position_int_cov->alt = mavlink_msg_global_position_int_cov_get_alt(msg);
00432         global_position_int_cov->relative_alt = mavlink_msg_global_position_int_cov_get_relative_alt(msg);
00433         global_position_int_cov->vx = mavlink_msg_global_position_int_cov_get_vx(msg);
00434         global_position_int_cov->vy = mavlink_msg_global_position_int_cov_get_vy(msg);
00435         global_position_int_cov->vz = mavlink_msg_global_position_int_cov_get_vz(msg);
00436         mavlink_msg_global_position_int_cov_get_covariance(msg, global_position_int_cov->covariance);
00437         global_position_int_cov->estimator_type = mavlink_msg_global_position_int_cov_get_estimator_type(msg);
00438 #else
00439         memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
00440 #endif
00441 }


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