mavlink_msg_local_position_ned_cov.h
Go to the documentation of this file.
00001 // MESSAGE LOCAL_POSITION_NED_COV PACKING
00002 
00003 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64
00004 
00005 typedef struct __mavlink_local_position_ned_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). 0 for system without monotonic timestamp*/
00009  float x; /*< X Position*/
00010  float y; /*< Y Position*/
00011  float z; /*< Z Position*/
00012  float vx; /*< X Speed (m/s)*/
00013  float vy; /*< Y Speed (m/s)*/
00014  float vz; /*< Z Speed (m/s)*/
00015  float ax; /*< X Acceleration (m/s^2)*/
00016  float ay; /*< Y Acceleration (m/s^2)*/
00017  float az; /*< Z Acceleration (m/s^2)*/
00018  float covariance[45]; /*< Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)*/
00019  uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/
00020 } mavlink_local_position_ned_cov_t;
00021 
00022 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 229
00023 #define MAVLINK_MSG_ID_64_LEN 229
00024 
00025 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 59
00026 #define MAVLINK_MSG_ID_64_CRC 59
00027 
00028 #define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 45
00029 
00030 #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \
00031         "LOCAL_POSITION_NED_COV", \
00032         13, \
00033         {  { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_utc) }, \
00034          { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_local_position_ned_cov_t, time_boot_ms) }, \
00035          { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, x) }, \
00036          { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, y) }, \
00037          { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, z) }, \
00038          { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vx) }, \
00039          { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vy) }, \
00040          { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, vz) }, \
00041          { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ax) }, \
00042          { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, ay) }, \
00043          { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_local_position_ned_cov_t, az) }, \
00044          { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 48, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
00045          { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
00046          } \
00047 }
00048 
00049 
00071 static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00072                                                        uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance)
00073 {
00074 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00075         char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
00076         _mav_put_uint64_t(buf, 0, time_utc);
00077         _mav_put_uint32_t(buf, 8, time_boot_ms);
00078         _mav_put_float(buf, 12, x);
00079         _mav_put_float(buf, 16, y);
00080         _mav_put_float(buf, 20, z);
00081         _mav_put_float(buf, 24, vx);
00082         _mav_put_float(buf, 28, vy);
00083         _mav_put_float(buf, 32, vz);
00084         _mav_put_float(buf, 36, ax);
00085         _mav_put_float(buf, 40, ay);
00086         _mav_put_float(buf, 44, az);
00087         _mav_put_uint8_t(buf, 228, estimator_type);
00088         _mav_put_float_array(buf, 48, covariance, 45);
00089         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00090 #else
00091         mavlink_local_position_ned_cov_t packet;
00092         packet.time_utc = time_utc;
00093         packet.time_boot_ms = time_boot_ms;
00094         packet.x = x;
00095         packet.y = y;
00096         packet.z = z;
00097         packet.vx = vx;
00098         packet.vy = vy;
00099         packet.vz = vz;
00100         packet.ax = ax;
00101         packet.ay = ay;
00102         packet.az = az;
00103         packet.estimator_type = estimator_type;
00104         mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
00105         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00106 #endif
00107 
00108         msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
00109 #if MAVLINK_CRC_EXTRA
00110     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
00111 #else
00112     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00113 #endif
00114 }
00115 
00137 static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00138                                                            mavlink_message_t* msg,
00139                                                            uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,const float *covariance)
00140 {
00141 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00142         char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
00143         _mav_put_uint64_t(buf, 0, time_utc);
00144         _mav_put_uint32_t(buf, 8, time_boot_ms);
00145         _mav_put_float(buf, 12, x);
00146         _mav_put_float(buf, 16, y);
00147         _mav_put_float(buf, 20, z);
00148         _mav_put_float(buf, 24, vx);
00149         _mav_put_float(buf, 28, vy);
00150         _mav_put_float(buf, 32, vz);
00151         _mav_put_float(buf, 36, ax);
00152         _mav_put_float(buf, 40, ay);
00153         _mav_put_float(buf, 44, az);
00154         _mav_put_uint8_t(buf, 228, estimator_type);
00155         _mav_put_float_array(buf, 48, covariance, 45);
00156         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00157 #else
00158         mavlink_local_position_ned_cov_t packet;
00159         packet.time_utc = time_utc;
00160         packet.time_boot_ms = time_boot_ms;
00161         packet.x = x;
00162         packet.y = y;
00163         packet.z = z;
00164         packet.vx = vx;
00165         packet.vy = vy;
00166         packet.vz = vz;
00167         packet.ax = ax;
00168         packet.ay = ay;
00169         packet.az = az;
00170         packet.estimator_type = estimator_type;
00171         mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
00172         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00173 #endif
00174 
00175         msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
00176 #if MAVLINK_CRC_EXTRA
00177     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
00178 #else
00179     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00180 #endif
00181 }
00182 
00191 static inline uint16_t mavlink_msg_local_position_ned_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov)
00192 {
00193         return mavlink_msg_local_position_ned_cov_pack(system_id, component_id, msg, local_position_ned_cov->time_boot_ms, local_position_ned_cov->time_utc, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance);
00194 }
00195 
00205 static inline uint16_t mavlink_msg_local_position_ned_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov)
00206 {
00207         return mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, chan, msg, local_position_ned_cov->time_boot_ms, local_position_ned_cov->time_utc, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance);
00208 }
00209 
00228 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00229 
00230 static inline void mavlink_msg_local_position_ned_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance)
00231 {
00232 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00233         char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
00234         _mav_put_uint64_t(buf, 0, time_utc);
00235         _mav_put_uint32_t(buf, 8, time_boot_ms);
00236         _mav_put_float(buf, 12, x);
00237         _mav_put_float(buf, 16, y);
00238         _mav_put_float(buf, 20, z);
00239         _mav_put_float(buf, 24, vx);
00240         _mav_put_float(buf, 28, vy);
00241         _mav_put_float(buf, 32, vz);
00242         _mav_put_float(buf, 36, ax);
00243         _mav_put_float(buf, 40, ay);
00244         _mav_put_float(buf, 44, az);
00245         _mav_put_uint8_t(buf, 228, estimator_type);
00246         _mav_put_float_array(buf, 48, covariance, 45);
00247 #if MAVLINK_CRC_EXTRA
00248     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
00249 #else
00250     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00251 #endif
00252 #else
00253         mavlink_local_position_ned_cov_t packet;
00254         packet.time_utc = time_utc;
00255         packet.time_boot_ms = time_boot_ms;
00256         packet.x = x;
00257         packet.y = y;
00258         packet.z = z;
00259         packet.vx = vx;
00260         packet.vy = vy;
00261         packet.vz = vz;
00262         packet.ax = ax;
00263         packet.ay = ay;
00264         packet.az = az;
00265         packet.estimator_type = estimator_type;
00266         mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
00267 #if MAVLINK_CRC_EXTRA
00268     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
00269 #else
00270     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00271 #endif
00272 #endif
00273 }
00274 
00275 #if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00276 /*
00277   This varient of _send() can be used to save stack space by re-using
00278   memory from the receive buffer.  The caller provides a
00279   mavlink_message_t which is the size of a full mavlink message. This
00280   is usually the receive buffer for the channel, and allows a reply to an
00281   incoming message with minimum stack space usage.
00282  */
00283 static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance)
00284 {
00285 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00286         char *buf = (char *)msgbuf;
00287         _mav_put_uint64_t(buf, 0, time_utc);
00288         _mav_put_uint32_t(buf, 8, time_boot_ms);
00289         _mav_put_float(buf, 12, x);
00290         _mav_put_float(buf, 16, y);
00291         _mav_put_float(buf, 20, z);
00292         _mav_put_float(buf, 24, vx);
00293         _mav_put_float(buf, 28, vy);
00294         _mav_put_float(buf, 32, vz);
00295         _mav_put_float(buf, 36, ax);
00296         _mav_put_float(buf, 40, ay);
00297         _mav_put_float(buf, 44, az);
00298         _mav_put_uint8_t(buf, 228, estimator_type);
00299         _mav_put_float_array(buf, 48, covariance, 45);
00300 #if MAVLINK_CRC_EXTRA
00301     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
00302 #else
00303     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00304 #endif
00305 #else
00306         mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf;
00307         packet->time_utc = time_utc;
00308         packet->time_boot_ms = time_boot_ms;
00309         packet->x = x;
00310         packet->y = y;
00311         packet->z = z;
00312         packet->vx = vx;
00313         packet->vy = vy;
00314         packet->vz = vz;
00315         packet->ax = ax;
00316         packet->ay = ay;
00317         packet->az = az;
00318         packet->estimator_type = estimator_type;
00319         mav_array_memcpy(packet->covariance, covariance, sizeof(float)*45);
00320 #if MAVLINK_CRC_EXTRA
00321     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
00322 #else
00323     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00324 #endif
00325 #endif
00326 }
00327 #endif
00328 
00329 #endif
00330 
00331 // MESSAGE LOCAL_POSITION_NED_COV UNPACKING
00332 
00333 
00339 static inline uint32_t mavlink_msg_local_position_ned_cov_get_time_boot_ms(const mavlink_message_t* msg)
00340 {
00341         return _MAV_RETURN_uint32_t(msg,  8);
00342 }
00343 
00349 static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_utc(const mavlink_message_t* msg)
00350 {
00351         return _MAV_RETURN_uint64_t(msg,  0);
00352 }
00353 
00359 static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg)
00360 {
00361         return _MAV_RETURN_uint8_t(msg,  228);
00362 }
00363 
00369 static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg)
00370 {
00371         return _MAV_RETURN_float(msg,  12);
00372 }
00373 
00379 static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg)
00380 {
00381         return _MAV_RETURN_float(msg,  16);
00382 }
00383 
00389 static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg)
00390 {
00391         return _MAV_RETURN_float(msg,  20);
00392 }
00393 
00399 static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg)
00400 {
00401         return _MAV_RETURN_float(msg,  24);
00402 }
00403 
00409 static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg)
00410 {
00411         return _MAV_RETURN_float(msg,  28);
00412 }
00413 
00419 static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg)
00420 {
00421         return _MAV_RETURN_float(msg,  32);
00422 }
00423 
00429 static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg)
00430 {
00431         return _MAV_RETURN_float(msg,  36);
00432 }
00433 
00439 static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg)
00440 {
00441         return _MAV_RETURN_float(msg,  40);
00442 }
00443 
00449 static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg)
00450 {
00451         return _MAV_RETURN_float(msg,  44);
00452 }
00453 
00459 static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
00460 {
00461         return _MAV_RETURN_float_array(msg, covariance, 45,  48);
00462 }
00463 
00470 static inline void mavlink_msg_local_position_ned_cov_decode(const mavlink_message_t* msg, mavlink_local_position_ned_cov_t* local_position_ned_cov)
00471 {
00472 #if MAVLINK_NEED_BYTE_SWAP
00473         local_position_ned_cov->time_utc = mavlink_msg_local_position_ned_cov_get_time_utc(msg);
00474         local_position_ned_cov->time_boot_ms = mavlink_msg_local_position_ned_cov_get_time_boot_ms(msg);
00475         local_position_ned_cov->x = mavlink_msg_local_position_ned_cov_get_x(msg);
00476         local_position_ned_cov->y = mavlink_msg_local_position_ned_cov_get_y(msg);
00477         local_position_ned_cov->z = mavlink_msg_local_position_ned_cov_get_z(msg);
00478         local_position_ned_cov->vx = mavlink_msg_local_position_ned_cov_get_vx(msg);
00479         local_position_ned_cov->vy = mavlink_msg_local_position_ned_cov_get_vy(msg);
00480         local_position_ned_cov->vz = mavlink_msg_local_position_ned_cov_get_vz(msg);
00481         local_position_ned_cov->ax = mavlink_msg_local_position_ned_cov_get_ax(msg);
00482         local_position_ned_cov->ay = mavlink_msg_local_position_ned_cov_get_ay(msg);
00483         local_position_ned_cov->az = mavlink_msg_local_position_ned_cov_get_az(msg);
00484         mavlink_msg_local_position_ned_cov_get_covariance(msg, local_position_ned_cov->covariance);
00485         local_position_ned_cov->estimator_type = mavlink_msg_local_position_ned_cov_get_estimator_type(msg);
00486 #else
00487         memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
00488 #endif
00489 }


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