[324] | 1 | // MESSAGE LOCAL_POSITION_NED_COV PACKING
|
---|
| 2 |
|
---|
| 3 | #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64
|
---|
| 4 |
|
---|
| 5 | typedef struct MAVLINK_PACKED __mavlink_local_position_ned_cov_t
|
---|
| 6 | {
|
---|
| 7 | 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.*/
|
---|
| 8 | uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp*/
|
---|
| 9 | float x; /*< X Position*/
|
---|
| 10 | float y; /*< Y Position*/
|
---|
| 11 | float z; /*< Z Position*/
|
---|
| 12 | float vx; /*< X Speed (m/s)*/
|
---|
| 13 | float vy; /*< Y Speed (m/s)*/
|
---|
| 14 | float vz; /*< Z Speed (m/s)*/
|
---|
| 15 | float ax; /*< X Acceleration (m/s^2)*/
|
---|
| 16 | float ay; /*< Y Acceleration (m/s^2)*/
|
---|
| 17 | float az; /*< Z Acceleration (m/s^2)*/
|
---|
| 18 | float covariance[45]; /*< Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)*/
|
---|
| 19 | uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/
|
---|
| 20 | } mavlink_local_position_ned_cov_t;
|
---|
| 21 |
|
---|
| 22 | #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 229
|
---|
| 23 | #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN 229
|
---|
| 24 | #define MAVLINK_MSG_ID_64_LEN 229
|
---|
| 25 | #define MAVLINK_MSG_ID_64_MIN_LEN 229
|
---|
| 26 |
|
---|
| 27 | #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 59
|
---|
| 28 | #define MAVLINK_MSG_ID_64_CRC 59
|
---|
| 29 |
|
---|
| 30 | #define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 45
|
---|
| 31 |
|
---|
| 32 | #if MAVLINK_COMMAND_24BIT
|
---|
| 33 | #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \
|
---|
| 34 | 64, \
|
---|
| 35 | "LOCAL_POSITION_NED_COV", \
|
---|
| 36 | 13, \
|
---|
| 37 | { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_utc) }, \
|
---|
| 38 | { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_local_position_ned_cov_t, time_boot_ms) }, \
|
---|
| 39 | { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, x) }, \
|
---|
| 40 | { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, y) }, \
|
---|
| 41 | { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, z) }, \
|
---|
| 42 | { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vx) }, \
|
---|
| 43 | { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vy) }, \
|
---|
| 44 | { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, vz) }, \
|
---|
| 45 | { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ax) }, \
|
---|
| 46 | { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, ay) }, \
|
---|
| 47 | { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_local_position_ned_cov_t, az) }, \
|
---|
| 48 | { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 48, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
|
---|
| 49 | { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
|
---|
| 50 | } \
|
---|
| 51 | }
|
---|
| 52 | #else
|
---|
| 53 | #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \
|
---|
| 54 | "LOCAL_POSITION_NED_COV", \
|
---|
| 55 | 13, \
|
---|
| 56 | { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_utc) }, \
|
---|
| 57 | { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_local_position_ned_cov_t, time_boot_ms) }, \
|
---|
| 58 | { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, x) }, \
|
---|
| 59 | { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, y) }, \
|
---|
| 60 | { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, z) }, \
|
---|
| 61 | { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vx) }, \
|
---|
| 62 | { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vy) }, \
|
---|
| 63 | { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, vz) }, \
|
---|
| 64 | { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ax) }, \
|
---|
| 65 | { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, ay) }, \
|
---|
| 66 | { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_local_position_ned_cov_t, az) }, \
|
---|
| 67 | { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 48, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
|
---|
| 68 | { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
|
---|
| 69 | } \
|
---|
| 70 | }
|
---|
| 71 | #endif
|
---|
| 72 |
|
---|
| 73 | /**
|
---|
| 74 | * @brief Pack a local_position_ned_cov message
|
---|
| 75 | * @param system_id ID of this system
|
---|
| 76 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 77 | * @param msg The MAVLink message to compress the data into
|
---|
| 78 | *
|
---|
| 79 | * @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp
|
---|
| 80 | * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
---|
| 81 | * @param estimator_type Class id of the estimator this estimate originated from.
|
---|
| 82 | * @param x X Position
|
---|
| 83 | * @param y Y Position
|
---|
| 84 | * @param z Z Position
|
---|
| 85 | * @param vx X Speed (m/s)
|
---|
| 86 | * @param vy Y Speed (m/s)
|
---|
| 87 | * @param vz Z Speed (m/s)
|
---|
| 88 | * @param ax X Acceleration (m/s^2)
|
---|
| 89 | * @param ay Y Acceleration (m/s^2)
|
---|
| 90 | * @param az Z Acceleration (m/s^2)
|
---|
| 91 | * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
|
---|
| 92 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
| 93 | */
|
---|
| 94 | static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
---|
| 95 | 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)
|
---|
| 96 | {
|
---|
| 97 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 98 | char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
|
---|
| 99 | _mav_put_uint64_t(buf, 0, time_utc);
|
---|
| 100 | _mav_put_uint32_t(buf, 8, time_boot_ms);
|
---|
| 101 | _mav_put_float(buf, 12, x);
|
---|
| 102 | _mav_put_float(buf, 16, y);
|
---|
| 103 | _mav_put_float(buf, 20, z);
|
---|
| 104 | _mav_put_float(buf, 24, vx);
|
---|
| 105 | _mav_put_float(buf, 28, vy);
|
---|
| 106 | _mav_put_float(buf, 32, vz);
|
---|
| 107 | _mav_put_float(buf, 36, ax);
|
---|
| 108 | _mav_put_float(buf, 40, ay);
|
---|
| 109 | _mav_put_float(buf, 44, az);
|
---|
| 110 | _mav_put_uint8_t(buf, 228, estimator_type);
|
---|
| 111 | _mav_put_float_array(buf, 48, covariance, 45);
|
---|
| 112 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
---|
| 113 | #else
|
---|
| 114 | mavlink_local_position_ned_cov_t packet;
|
---|
| 115 | packet.time_utc = time_utc;
|
---|
| 116 | packet.time_boot_ms = time_boot_ms;
|
---|
| 117 | packet.x = x;
|
---|
| 118 | packet.y = y;
|
---|
| 119 | packet.z = z;
|
---|
| 120 | packet.vx = vx;
|
---|
| 121 | packet.vy = vy;
|
---|
| 122 | packet.vz = vz;
|
---|
| 123 | packet.ax = ax;
|
---|
| 124 | packet.ay = ay;
|
---|
| 125 | packet.az = az;
|
---|
| 126 | packet.estimator_type = estimator_type;
|
---|
| 127 | mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
|
---|
| 128 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
---|
| 129 | #endif
|
---|
| 130 |
|
---|
| 131 | msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
|
---|
| 132 | 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);
|
---|
| 133 | }
|
---|
| 134 |
|
---|
| 135 | /**
|
---|
| 136 | * @brief Pack a local_position_ned_cov message on a channel
|
---|
| 137 | * @param system_id ID of this system
|
---|
| 138 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 139 | * @param chan The MAVLink channel this message will be sent over
|
---|
| 140 | * @param msg The MAVLink message to compress the data into
|
---|
| 141 | * @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp
|
---|
| 142 | * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
---|
| 143 | * @param estimator_type Class id of the estimator this estimate originated from.
|
---|
| 144 | * @param x X Position
|
---|
| 145 | * @param y Y Position
|
---|
| 146 | * @param z Z Position
|
---|
| 147 | * @param vx X Speed (m/s)
|
---|
| 148 | * @param vy Y Speed (m/s)
|
---|
| 149 | * @param vz Z Speed (m/s)
|
---|
| 150 | * @param ax X Acceleration (m/s^2)
|
---|
| 151 | * @param ay Y Acceleration (m/s^2)
|
---|
| 152 | * @param az Z Acceleration (m/s^2)
|
---|
| 153 | * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
|
---|
| 154 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
| 155 | */
|
---|
| 156 | static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
---|
| 157 | mavlink_message_t* msg,
|
---|
| 158 | 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)
|
---|
| 159 | {
|
---|
| 160 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 161 | char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
|
---|
| 162 | _mav_put_uint64_t(buf, 0, time_utc);
|
---|
| 163 | _mav_put_uint32_t(buf, 8, time_boot_ms);
|
---|
| 164 | _mav_put_float(buf, 12, x);
|
---|
| 165 | _mav_put_float(buf, 16, y);
|
---|
| 166 | _mav_put_float(buf, 20, z);
|
---|
| 167 | _mav_put_float(buf, 24, vx);
|
---|
| 168 | _mav_put_float(buf, 28, vy);
|
---|
| 169 | _mav_put_float(buf, 32, vz);
|
---|
| 170 | _mav_put_float(buf, 36, ax);
|
---|
| 171 | _mav_put_float(buf, 40, ay);
|
---|
| 172 | _mav_put_float(buf, 44, az);
|
---|
| 173 | _mav_put_uint8_t(buf, 228, estimator_type);
|
---|
| 174 | _mav_put_float_array(buf, 48, covariance, 45);
|
---|
| 175 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
---|
| 176 | #else
|
---|
| 177 | mavlink_local_position_ned_cov_t packet;
|
---|
| 178 | packet.time_utc = time_utc;
|
---|
| 179 | packet.time_boot_ms = time_boot_ms;
|
---|
| 180 | packet.x = x;
|
---|
| 181 | packet.y = y;
|
---|
| 182 | packet.z = z;
|
---|
| 183 | packet.vx = vx;
|
---|
| 184 | packet.vy = vy;
|
---|
| 185 | packet.vz = vz;
|
---|
| 186 | packet.ax = ax;
|
---|
| 187 | packet.ay = ay;
|
---|
| 188 | packet.az = az;
|
---|
| 189 | packet.estimator_type = estimator_type;
|
---|
| 190 | mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
|
---|
| 191 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
---|
| 192 | #endif
|
---|
| 193 |
|
---|
| 194 | msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
|
---|
| 195 | 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);
|
---|
| 196 | }
|
---|
| 197 |
|
---|
| 198 | /**
|
---|
| 199 | * @brief Encode a local_position_ned_cov struct
|
---|
| 200 | *
|
---|
| 201 | * @param system_id ID of this system
|
---|
| 202 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 203 | * @param msg The MAVLink message to compress the data into
|
---|
| 204 | * @param local_position_ned_cov C-struct to read the message contents from
|
---|
| 205 | */
|
---|
| 206 | 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)
|
---|
| 207 | {
|
---|
| 208 | 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);
|
---|
| 209 | }
|
---|
| 210 |
|
---|
| 211 | /**
|
---|
| 212 | * @brief Encode a local_position_ned_cov struct on a channel
|
---|
| 213 | *
|
---|
| 214 | * @param system_id ID of this system
|
---|
| 215 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 216 | * @param chan The MAVLink channel this message will be sent over
|
---|
| 217 | * @param msg The MAVLink message to compress the data into
|
---|
| 218 | * @param local_position_ned_cov C-struct to read the message contents from
|
---|
| 219 | */
|
---|
| 220 | 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)
|
---|
| 221 | {
|
---|
| 222 | 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);
|
---|
| 223 | }
|
---|
| 224 |
|
---|
| 225 | /**
|
---|
| 226 | * @brief Send a local_position_ned_cov message
|
---|
| 227 | * @param chan MAVLink channel to send the message
|
---|
| 228 | *
|
---|
| 229 | * @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp
|
---|
| 230 | * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
---|
| 231 | * @param estimator_type Class id of the estimator this estimate originated from.
|
---|
| 232 | * @param x X Position
|
---|
| 233 | * @param y Y Position
|
---|
| 234 | * @param z Z Position
|
---|
| 235 | * @param vx X Speed (m/s)
|
---|
| 236 | * @param vy Y Speed (m/s)
|
---|
| 237 | * @param vz Z Speed (m/s)
|
---|
| 238 | * @param ax X Acceleration (m/s^2)
|
---|
| 239 | * @param ay Y Acceleration (m/s^2)
|
---|
| 240 | * @param az Z Acceleration (m/s^2)
|
---|
| 241 | * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
|
---|
| 242 | */
|
---|
| 243 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
---|
| 244 |
|
---|
| 245 | 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)
|
---|
| 246 | {
|
---|
| 247 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 248 | char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
|
---|
| 249 | _mav_put_uint64_t(buf, 0, time_utc);
|
---|
| 250 | _mav_put_uint32_t(buf, 8, time_boot_ms);
|
---|
| 251 | _mav_put_float(buf, 12, x);
|
---|
| 252 | _mav_put_float(buf, 16, y);
|
---|
| 253 | _mav_put_float(buf, 20, z);
|
---|
| 254 | _mav_put_float(buf, 24, vx);
|
---|
| 255 | _mav_put_float(buf, 28, vy);
|
---|
| 256 | _mav_put_float(buf, 32, vz);
|
---|
| 257 | _mav_put_float(buf, 36, ax);
|
---|
| 258 | _mav_put_float(buf, 40, ay);
|
---|
| 259 | _mav_put_float(buf, 44, az);
|
---|
| 260 | _mav_put_uint8_t(buf, 228, estimator_type);
|
---|
| 261 | _mav_put_float_array(buf, 48, covariance, 45);
|
---|
| 262 | _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);
|
---|
| 263 | #else
|
---|
| 264 | mavlink_local_position_ned_cov_t packet;
|
---|
| 265 | packet.time_utc = time_utc;
|
---|
| 266 | packet.time_boot_ms = time_boot_ms;
|
---|
| 267 | packet.x = x;
|
---|
| 268 | packet.y = y;
|
---|
| 269 | packet.z = z;
|
---|
| 270 | packet.vx = vx;
|
---|
| 271 | packet.vy = vy;
|
---|
| 272 | packet.vz = vz;
|
---|
| 273 | packet.ax = ax;
|
---|
| 274 | packet.ay = ay;
|
---|
| 275 | packet.az = az;
|
---|
| 276 | packet.estimator_type = estimator_type;
|
---|
| 277 | mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
|
---|
| 278 | _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);
|
---|
| 279 | #endif
|
---|
| 280 | }
|
---|
| 281 |
|
---|
| 282 | /**
|
---|
| 283 | * @brief Send a local_position_ned_cov message
|
---|
| 284 | * @param chan MAVLink channel to send the message
|
---|
| 285 | * @param struct The MAVLink struct to serialize
|
---|
| 286 | */
|
---|
| 287 | 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)
|
---|
| 288 | {
|
---|
| 289 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 290 | mavlink_msg_local_position_ned_cov_send(chan, 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);
|
---|
| 291 | #else
|
---|
| 292 | _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);
|
---|
| 293 | #endif
|
---|
| 294 | }
|
---|
| 295 |
|
---|
| 296 | #if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
---|
| 297 | /*
|
---|
| 298 | This varient of _send() can be used to save stack space by re-using
|
---|
| 299 | memory from the receive buffer. The caller provides a
|
---|
| 300 | mavlink_message_t which is the size of a full mavlink message. This
|
---|
| 301 | is usually the receive buffer for the channel, and allows a reply to an
|
---|
| 302 | incoming message with minimum stack space usage.
|
---|
| 303 | */
|
---|
| 304 | 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)
|
---|
| 305 | {
|
---|
| 306 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 307 | char *buf = (char *)msgbuf;
|
---|
| 308 | _mav_put_uint64_t(buf, 0, time_utc);
|
---|
| 309 | _mav_put_uint32_t(buf, 8, time_boot_ms);
|
---|
| 310 | _mav_put_float(buf, 12, x);
|
---|
| 311 | _mav_put_float(buf, 16, y);
|
---|
| 312 | _mav_put_float(buf, 20, z);
|
---|
| 313 | _mav_put_float(buf, 24, vx);
|
---|
| 314 | _mav_put_float(buf, 28, vy);
|
---|
| 315 | _mav_put_float(buf, 32, vz);
|
---|
| 316 | _mav_put_float(buf, 36, ax);
|
---|
| 317 | _mav_put_float(buf, 40, ay);
|
---|
| 318 | _mav_put_float(buf, 44, az);
|
---|
| 319 | _mav_put_uint8_t(buf, 228, estimator_type);
|
---|
| 320 | _mav_put_float_array(buf, 48, covariance, 45);
|
---|
| 321 | _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);
|
---|
| 322 | #else
|
---|
| 323 | mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf;
|
---|
| 324 | packet->time_utc = time_utc;
|
---|
| 325 | packet->time_boot_ms = time_boot_ms;
|
---|
| 326 | packet->x = x;
|
---|
| 327 | packet->y = y;
|
---|
| 328 | packet->z = z;
|
---|
| 329 | packet->vx = vx;
|
---|
| 330 | packet->vy = vy;
|
---|
| 331 | packet->vz = vz;
|
---|
| 332 | packet->ax = ax;
|
---|
| 333 | packet->ay = ay;
|
---|
| 334 | packet->az = az;
|
---|
| 335 | packet->estimator_type = estimator_type;
|
---|
| 336 | mav_array_memcpy(packet->covariance, covariance, sizeof(float)*45);
|
---|
| 337 | _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);
|
---|
| 338 | #endif
|
---|
| 339 | }
|
---|
| 340 | #endif
|
---|
| 341 |
|
---|
| 342 | #endif
|
---|
| 343 |
|
---|
| 344 | // MESSAGE LOCAL_POSITION_NED_COV UNPACKING
|
---|
| 345 |
|
---|
| 346 |
|
---|
| 347 | /**
|
---|
| 348 | * @brief Get field time_boot_ms from local_position_ned_cov message
|
---|
| 349 | *
|
---|
| 350 | * @return Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp
|
---|
| 351 | */
|
---|
| 352 | static inline uint32_t mavlink_msg_local_position_ned_cov_get_time_boot_ms(const mavlink_message_t* msg)
|
---|
| 353 | {
|
---|
| 354 | return _MAV_RETURN_uint32_t(msg, 8);
|
---|
| 355 | }
|
---|
| 356 |
|
---|
| 357 | /**
|
---|
| 358 | * @brief Get field time_utc from local_position_ned_cov message
|
---|
| 359 | *
|
---|
| 360 | * @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
---|
| 361 | */
|
---|
| 362 | static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_utc(const mavlink_message_t* msg)
|
---|
| 363 | {
|
---|
| 364 | return _MAV_RETURN_uint64_t(msg, 0);
|
---|
| 365 | }
|
---|
| 366 |
|
---|
| 367 | /**
|
---|
| 368 | * @brief Get field estimator_type from local_position_ned_cov message
|
---|
| 369 | *
|
---|
| 370 | * @return Class id of the estimator this estimate originated from.
|
---|
| 371 | */
|
---|
| 372 | static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg)
|
---|
| 373 | {
|
---|
| 374 | return _MAV_RETURN_uint8_t(msg, 228);
|
---|
| 375 | }
|
---|
| 376 |
|
---|
| 377 | /**
|
---|
| 378 | * @brief Get field x from local_position_ned_cov message
|
---|
| 379 | *
|
---|
| 380 | * @return X Position
|
---|
| 381 | */
|
---|
| 382 | static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg)
|
---|
| 383 | {
|
---|
| 384 | return _MAV_RETURN_float(msg, 12);
|
---|
| 385 | }
|
---|
| 386 |
|
---|
| 387 | /**
|
---|
| 388 | * @brief Get field y from local_position_ned_cov message
|
---|
| 389 | *
|
---|
| 390 | * @return Y Position
|
---|
| 391 | */
|
---|
| 392 | static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg)
|
---|
| 393 | {
|
---|
| 394 | return _MAV_RETURN_float(msg, 16);
|
---|
| 395 | }
|
---|
| 396 |
|
---|
| 397 | /**
|
---|
| 398 | * @brief Get field z from local_position_ned_cov message
|
---|
| 399 | *
|
---|
| 400 | * @return Z Position
|
---|
| 401 | */
|
---|
| 402 | static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg)
|
---|
| 403 | {
|
---|
| 404 | return _MAV_RETURN_float(msg, 20);
|
---|
| 405 | }
|
---|
| 406 |
|
---|
| 407 | /**
|
---|
| 408 | * @brief Get field vx from local_position_ned_cov message
|
---|
| 409 | *
|
---|
| 410 | * @return X Speed (m/s)
|
---|
| 411 | */
|
---|
| 412 | static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg)
|
---|
| 413 | {
|
---|
| 414 | return _MAV_RETURN_float(msg, 24);
|
---|
| 415 | }
|
---|
| 416 |
|
---|
| 417 | /**
|
---|
| 418 | * @brief Get field vy from local_position_ned_cov message
|
---|
| 419 | *
|
---|
| 420 | * @return Y Speed (m/s)
|
---|
| 421 | */
|
---|
| 422 | static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg)
|
---|
| 423 | {
|
---|
| 424 | return _MAV_RETURN_float(msg, 28);
|
---|
| 425 | }
|
---|
| 426 |
|
---|
| 427 | /**
|
---|
| 428 | * @brief Get field vz from local_position_ned_cov message
|
---|
| 429 | *
|
---|
| 430 | * @return Z Speed (m/s)
|
---|
| 431 | */
|
---|
| 432 | static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg)
|
---|
| 433 | {
|
---|
| 434 | return _MAV_RETURN_float(msg, 32);
|
---|
| 435 | }
|
---|
| 436 |
|
---|
| 437 | /**
|
---|
| 438 | * @brief Get field ax from local_position_ned_cov message
|
---|
| 439 | *
|
---|
| 440 | * @return X Acceleration (m/s^2)
|
---|
| 441 | */
|
---|
| 442 | static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg)
|
---|
| 443 | {
|
---|
| 444 | return _MAV_RETURN_float(msg, 36);
|
---|
| 445 | }
|
---|
| 446 |
|
---|
| 447 | /**
|
---|
| 448 | * @brief Get field ay from local_position_ned_cov message
|
---|
| 449 | *
|
---|
| 450 | * @return Y Acceleration (m/s^2)
|
---|
| 451 | */
|
---|
| 452 | static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg)
|
---|
| 453 | {
|
---|
| 454 | return _MAV_RETURN_float(msg, 40);
|
---|
| 455 | }
|
---|
| 456 |
|
---|
| 457 | /**
|
---|
| 458 | * @brief Get field az from local_position_ned_cov message
|
---|
| 459 | *
|
---|
| 460 | * @return Z Acceleration (m/s^2)
|
---|
| 461 | */
|
---|
| 462 | static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg)
|
---|
| 463 | {
|
---|
| 464 | return _MAV_RETURN_float(msg, 44);
|
---|
| 465 | }
|
---|
| 466 |
|
---|
| 467 | /**
|
---|
| 468 | * @brief Get field covariance from local_position_ned_cov message
|
---|
| 469 | *
|
---|
| 470 | * @return Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
|
---|
| 471 | */
|
---|
| 472 | static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
|
---|
| 473 | {
|
---|
| 474 | return _MAV_RETURN_float_array(msg, covariance, 45, 48);
|
---|
| 475 | }
|
---|
| 476 |
|
---|
| 477 | /**
|
---|
| 478 | * @brief Decode a local_position_ned_cov message into a struct
|
---|
| 479 | *
|
---|
| 480 | * @param msg The message to decode
|
---|
| 481 | * @param local_position_ned_cov C-struct to decode the message contents into
|
---|
| 482 | */
|
---|
| 483 | 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)
|
---|
| 484 | {
|
---|
| 485 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 486 | local_position_ned_cov->time_utc = mavlink_msg_local_position_ned_cov_get_time_utc(msg);
|
---|
| 487 | local_position_ned_cov->time_boot_ms = mavlink_msg_local_position_ned_cov_get_time_boot_ms(msg);
|
---|
| 488 | local_position_ned_cov->x = mavlink_msg_local_position_ned_cov_get_x(msg);
|
---|
| 489 | local_position_ned_cov->y = mavlink_msg_local_position_ned_cov_get_y(msg);
|
---|
| 490 | local_position_ned_cov->z = mavlink_msg_local_position_ned_cov_get_z(msg);
|
---|
| 491 | local_position_ned_cov->vx = mavlink_msg_local_position_ned_cov_get_vx(msg);
|
---|
| 492 | local_position_ned_cov->vy = mavlink_msg_local_position_ned_cov_get_vy(msg);
|
---|
| 493 | local_position_ned_cov->vz = mavlink_msg_local_position_ned_cov_get_vz(msg);
|
---|
| 494 | local_position_ned_cov->ax = mavlink_msg_local_position_ned_cov_get_ax(msg);
|
---|
| 495 | local_position_ned_cov->ay = mavlink_msg_local_position_ned_cov_get_ay(msg);
|
---|
| 496 | local_position_ned_cov->az = mavlink_msg_local_position_ned_cov_get_az(msg);
|
---|
| 497 | mavlink_msg_local_position_ned_cov_get_covariance(msg, local_position_ned_cov->covariance);
|
---|
| 498 | local_position_ned_cov->estimator_type = mavlink_msg_local_position_ned_cov_get_estimator_type(msg);
|
---|
| 499 | #else
|
---|
| 500 | uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN;
|
---|
| 501 | memset(local_position_ned_cov, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
---|
| 502 | memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), len);
|
---|
| 503 | #endif
|
---|
| 504 | }
|
---|