123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558 |
- #pragma once
- // MESSAGE LOCAL_POSITION_NED_COV PACKING
- #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64
- typedef struct __mavlink_local_position_ned_cov_t {
- uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
- float x; /*< [m] X Position*/
- float y; /*< [m] Y Position*/
- float z; /*< [m] Z Position*/
- float vx; /*< [m/s] X Speed*/
- float vy; /*< [m/s] Y Speed*/
- float vz; /*< [m/s] Z Speed*/
- float ax; /*< [m/s/s] X Acceleration*/
- float ay; /*< [m/s/s] Y Acceleration*/
- float az; /*< [m/s/s] Z Acceleration*/
- float covariance[45]; /*< Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/
- uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/
- } mavlink_local_position_ned_cov_t;
- #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 225
- #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN 225
- #define MAVLINK_MSG_ID_64_LEN 225
- #define MAVLINK_MSG_ID_64_MIN_LEN 225
- #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 191
- #define MAVLINK_MSG_ID_64_CRC 191
- #define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 45
- #if MAVLINK_COMMAND_24BIT
- #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \
- 64, \
- "LOCAL_POSITION_NED_COV", \
- 12, \
- { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \
- { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
- { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \
- { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, vx) }, \
- { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vy) }, \
- { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vz) }, \
- { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, ax) }, \
- { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \
- { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \
- { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
- } \
- }
- #else
- #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \
- "LOCAL_POSITION_NED_COV", \
- 12, \
- { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \
- { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
- { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \
- { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, vx) }, \
- { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vy) }, \
- { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vz) }, \
- { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, ax) }, \
- { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \
- { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \
- { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
- } \
- }
- #endif
- /**
- * @brief Pack a local_position_ned_cov message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- *
- * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
- * @param estimator_type Class id of the estimator this estimate originated from.
- * @param x [m] X Position
- * @param y [m] Y Position
- * @param z [m] Z Position
- * @param vx [m/s] X Speed
- * @param vy [m/s] Y Speed
- * @param vz [m/s] Z Speed
- * @param ax [m/s/s] X Acceleration
- * @param ay [m/s/s] Y Acceleration
- * @param az [m/s/s] Z Acceleration
- * @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t time_usec, 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)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
- _mav_put_uint64_t(buf, 0, time_usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, vx);
- _mav_put_float(buf, 24, vy);
- _mav_put_float(buf, 28, vz);
- _mav_put_float(buf, 32, ax);
- _mav_put_float(buf, 36, ay);
- _mav_put_float(buf, 40, az);
- _mav_put_uint8_t(buf, 224, estimator_type);
- _mav_put_float_array(buf, 44, covariance, 45);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
- #else
- mavlink_local_position_ned_cov_t packet;
- packet.time_usec = time_usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.vx = vx;
- packet.vy = vy;
- packet.vz = vz;
- packet.ax = ax;
- packet.ay = ay;
- packet.az = az;
- packet.estimator_type = estimator_type;
- mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
- }
- /**
- * @brief Pack a local_position_ned_cov message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- *
- * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
- * @param estimator_type Class id of the estimator this estimate originated from.
- * @param x [m] X Position
- * @param y [m] Y Position
- * @param z [m] Z Position
- * @param vx [m/s] X Speed
- * @param vy [m/s] Y Speed
- * @param vz [m/s] Z Speed
- * @param ax [m/s/s] X Acceleration
- * @param ay [m/s/s] Y Acceleration
- * @param az [m/s/s] Z Acceleration
- * @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_local_position_ned_cov_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
- uint64_t time_usec, 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)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
- _mav_put_uint64_t(buf, 0, time_usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, vx);
- _mav_put_float(buf, 24, vy);
- _mav_put_float(buf, 28, vz);
- _mav_put_float(buf, 32, ax);
- _mav_put_float(buf, 36, ay);
- _mav_put_float(buf, 40, az);
- _mav_put_uint8_t(buf, 224, estimator_type);
- _mav_put_float_array(buf, 44, covariance, 45);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
- #else
- mavlink_local_position_ned_cov_t packet;
- packet.time_usec = time_usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.vx = vx;
- packet.vy = vy;
- packet.vz = vz;
- packet.ax = ax;
- packet.ay = ay;
- packet.az = az;
- packet.estimator_type = estimator_type;
- mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
- #if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
- #else
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
- #endif
- }
- /**
- * @brief Pack a local_position_ned_cov message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
- * @param estimator_type Class id of the estimator this estimate originated from.
- * @param x [m] X Position
- * @param y [m] Y Position
- * @param z [m] Z Position
- * @param vx [m/s] X Speed
- * @param vy [m/s] Y Speed
- * @param vz [m/s] Z Speed
- * @param ax [m/s/s] X Acceleration
- * @param ay [m/s/s] Y Acceleration
- * @param az [m/s/s] Z Acceleration
- * @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t time_usec,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)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
- _mav_put_uint64_t(buf, 0, time_usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, vx);
- _mav_put_float(buf, 24, vy);
- _mav_put_float(buf, 28, vz);
- _mav_put_float(buf, 32, ax);
- _mav_put_float(buf, 36, ay);
- _mav_put_float(buf, 40, az);
- _mav_put_uint8_t(buf, 224, estimator_type);
- _mav_put_float_array(buf, 44, covariance, 45);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
- #else
- mavlink_local_position_ned_cov_t packet;
- packet.time_usec = time_usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.vx = vx;
- packet.vy = vy;
- packet.vz = vz;
- packet.ax = ax;
- packet.ay = ay;
- packet.az = az;
- packet.estimator_type = estimator_type;
- mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
- }
- /**
- * @brief Encode a local_position_ned_cov struct
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- * @param local_position_ned_cov C-struct to read the message contents from
- */
- 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)
- {
- return mavlink_msg_local_position_ned_cov_pack(system_id, component_id, msg, local_position_ned_cov->time_usec, 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);
- }
- /**
- * @brief Encode a local_position_ned_cov struct on a channel
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param local_position_ned_cov C-struct to read the message contents from
- */
- 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)
- {
- return mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, chan, msg, local_position_ned_cov->time_usec, 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);
- }
- /**
- * @brief Encode a local_position_ned_cov struct with provided status structure
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- * @param local_position_ned_cov C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_local_position_ned_cov_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov)
- {
- return mavlink_msg_local_position_ned_cov_pack_status(system_id, component_id, _status, msg, local_position_ned_cov->time_usec, 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);
- }
- /**
- * @brief Send a local_position_ned_cov message
- * @param chan MAVLink channel to send the message
- *
- * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
- * @param estimator_type Class id of the estimator this estimate originated from.
- * @param x [m] X Position
- * @param y [m] Y Position
- * @param z [m] Z Position
- * @param vx [m/s] X Speed
- * @param vy [m/s] Y Speed
- * @param vz [m/s] Z Speed
- * @param ax [m/s/s] X Acceleration
- * @param ay [m/s/s] Y Acceleration
- * @param az [m/s/s] Z Acceleration
- * @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
- */
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- static inline void mavlink_msg_local_position_ned_cov_send(mavlink_channel_t chan, uint64_t time_usec, 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)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
- _mav_put_uint64_t(buf, 0, time_usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, vx);
- _mav_put_float(buf, 24, vy);
- _mav_put_float(buf, 28, vz);
- _mav_put_float(buf, 32, ax);
- _mav_put_float(buf, 36, ay);
- _mav_put_float(buf, 40, az);
- _mav_put_uint8_t(buf, 224, estimator_type);
- _mav_put_float_array(buf, 44, covariance, 45);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
- #else
- mavlink_local_position_ned_cov_t packet;
- packet.time_usec = time_usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.vx = vx;
- packet.vy = vy;
- packet.vz = vz;
- packet.ax = ax;
- packet.ay = ay;
- packet.az = az;
- packet.estimator_type = estimator_type;
- mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
- #endif
- }
- /**
- * @brief Send a local_position_ned_cov message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
- static inline void mavlink_msg_local_position_ned_cov_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_cov_t* local_position_ned_cov)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_local_position_ned_cov_send(chan, local_position_ned_cov->time_usec, 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);
- #else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)local_position_ned_cov, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
- #endif
- }
- #if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
- /*
- This variant of _send() can be used to save stack space by re-using
- memory from the receive buffer. The caller provides a
- mavlink_message_t which is the size of a full mavlink message. This
- is usually the receive buffer for the channel, and allows a reply to an
- incoming message with minimum stack space usage.
- */
- static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, 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)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, time_usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, vx);
- _mav_put_float(buf, 24, vy);
- _mav_put_float(buf, 28, vz);
- _mav_put_float(buf, 32, ax);
- _mav_put_float(buf, 36, ay);
- _mav_put_float(buf, 40, az);
- _mav_put_uint8_t(buf, 224, estimator_type);
- _mav_put_float_array(buf, 44, covariance, 45);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
- #else
- mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf;
- packet->time_usec = time_usec;
- packet->x = x;
- packet->y = y;
- packet->z = z;
- packet->vx = vx;
- packet->vy = vy;
- packet->vz = vz;
- packet->ax = ax;
- packet->ay = ay;
- packet->az = az;
- packet->estimator_type = estimator_type;
- mav_array_memcpy(packet->covariance, covariance, sizeof(float)*45);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
- #endif
- }
- #endif
- #endif
- // MESSAGE LOCAL_POSITION_NED_COV UNPACKING
- /**
- * @brief Get field time_usec from local_position_ned_cov message
- *
- * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
- */
- static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_usec(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint64_t(msg, 0);
- }
- /**
- * @brief Get field estimator_type from local_position_ned_cov message
- *
- * @return Class id of the estimator this estimate originated from.
- */
- static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 224);
- }
- /**
- * @brief Get field x from local_position_ned_cov message
- *
- * @return [m] X Position
- */
- static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 8);
- }
- /**
- * @brief Get field y from local_position_ned_cov message
- *
- * @return [m] Y Position
- */
- static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 12);
- }
- /**
- * @brief Get field z from local_position_ned_cov message
- *
- * @return [m] Z Position
- */
- static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 16);
- }
- /**
- * @brief Get field vx from local_position_ned_cov message
- *
- * @return [m/s] X Speed
- */
- static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 20);
- }
- /**
- * @brief Get field vy from local_position_ned_cov message
- *
- * @return [m/s] Y Speed
- */
- static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 24);
- }
- /**
- * @brief Get field vz from local_position_ned_cov message
- *
- * @return [m/s] Z Speed
- */
- static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 28);
- }
- /**
- * @brief Get field ax from local_position_ned_cov message
- *
- * @return [m/s/s] X Acceleration
- */
- static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 32);
- }
- /**
- * @brief Get field ay from local_position_ned_cov message
- *
- * @return [m/s/s] Y Acceleration
- */
- static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 36);
- }
- /**
- * @brief Get field az from local_position_ned_cov message
- *
- * @return [m/s/s] Z Acceleration
- */
- static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 40);
- }
- /**
- * @brief Get field covariance from local_position_ned_cov message
- *
- * @return Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
- */
- static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
- {
- return _MAV_RETURN_float_array(msg, covariance, 45, 44);
- }
- /**
- * @brief Decode a local_position_ned_cov message into a struct
- *
- * @param msg The message to decode
- * @param local_position_ned_cov C-struct to decode the message contents into
- */
- 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)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- local_position_ned_cov->time_usec = mavlink_msg_local_position_ned_cov_get_time_usec(msg);
- local_position_ned_cov->x = mavlink_msg_local_position_ned_cov_get_x(msg);
- local_position_ned_cov->y = mavlink_msg_local_position_ned_cov_get_y(msg);
- local_position_ned_cov->z = mavlink_msg_local_position_ned_cov_get_z(msg);
- local_position_ned_cov->vx = mavlink_msg_local_position_ned_cov_get_vx(msg);
- local_position_ned_cov->vy = mavlink_msg_local_position_ned_cov_get_vy(msg);
- local_position_ned_cov->vz = mavlink_msg_local_position_ned_cov_get_vz(msg);
- local_position_ned_cov->ax = mavlink_msg_local_position_ned_cov_get_ax(msg);
- local_position_ned_cov->ay = mavlink_msg_local_position_ned_cov_get_ay(msg);
- local_position_ned_cov->az = mavlink_msg_local_position_ned_cov_get_az(msg);
- mavlink_msg_local_position_ned_cov_get_covariance(msg, local_position_ned_cov->covariance);
- local_position_ned_cov->estimator_type = mavlink_msg_local_position_ned_cov_get_estimator_type(msg);
- #else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN;
- memset(local_position_ned_cov, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
- memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), len);
- #endif
- }
|