3 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61
15 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 68
16 #define MAVLINK_MSG_ID_61_LEN 68
18 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 153
19 #define MAVLINK_MSG_ID_61_CRC 153
21 #define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4
22 #define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9
24 #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \
25 "ATTITUDE_QUATERNION_COV", \
27 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_boot_ms) }, \
28 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \
29 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \
30 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \
31 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \
32 { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 32, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \
51 static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
52 uint32_t time_boot_ms,
const float *q,
float rollspeed,
float pitchspeed,
float yawspeed,
const float *covariance)
54 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
60 _mav_put_float_array(buf, 4, q, 4);
61 _mav_put_float_array(buf, 32, covariance, 9);
69 mav_array_memcpy(packet.
q, q,
sizeof(
float)*4);
70 mav_array_memcpy(packet.
covariance, covariance,
sizeof(
float)*9);
96 static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
97 mavlink_message_t* msg,
98 uint32_t time_boot_ms,
const float *q,
float rollspeed,
float pitchspeed,
float yawspeed,
const float *covariance)
100 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
106 _mav_put_float_array(buf, 4, q, 4);
107 _mav_put_float_array(buf, 32, covariance, 9);
115 mav_array_memcpy(packet.
q, q,
sizeof(
float)*4);
116 mav_array_memcpy(packet.
covariance, covariance,
sizeof(
float)*9);
121 #if MAVLINK_CRC_EXTRA
136 static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
138 return mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, msg, attitude_quaternion_cov->
time_boot_ms, attitude_quaternion_cov->
q, attitude_quaternion_cov->
rollspeed, attitude_quaternion_cov->
pitchspeed, attitude_quaternion_cov->
yawspeed, attitude_quaternion_cov->
covariance);
150 static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
152 return mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, chan, msg, attitude_quaternion_cov->
time_boot_ms, attitude_quaternion_cov->
q, attitude_quaternion_cov->
rollspeed, attitude_quaternion_cov->
pitchspeed, attitude_quaternion_cov->
yawspeed, attitude_quaternion_cov->
covariance);
166 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
168 static inline void mavlink_msg_attitude_quaternion_cov_send(
mavlink_channel_t chan, uint32_t time_boot_ms,
const float *q,
float rollspeed,
float pitchspeed,
float yawspeed,
const float *covariance)
170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
176 _mav_put_float_array(buf, 4, q, 4);
177 _mav_put_float_array(buf, 32, covariance, 9);
178 #if MAVLINK_CRC_EXTRA
189 mav_array_memcpy(packet.
q, q,
sizeof(
float)*4);
190 mav_array_memcpy(packet.
covariance, covariance,
sizeof(
float)*9);
191 #if MAVLINK_CRC_EXTRA
199 #if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
207 static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint32_t time_boot_ms,
const float *q,
float rollspeed,
float pitchspeed,
float yawspeed,
const float *covariance)
209 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
210 char *buf = (
char *)msgbuf;
215 _mav_put_float_array(buf, 4, q, 4);
216 _mav_put_float_array(buf, 32, covariance, 9);
217 #if MAVLINK_CRC_EXTRA
228 mav_array_memcpy(packet->
q, q,
sizeof(
float)*4);
229 mav_array_memcpy(packet->
covariance, covariance,
sizeof(
float)*9);
230 #if MAVLINK_CRC_EXTRA
249 static inline uint32_t mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(
const mavlink_message_t* msg)
251 return _MAV_RETURN_uint32_t(msg, 0);
259 static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(
const mavlink_message_t* msg,
float *q)
261 return _MAV_RETURN_float_array(msg, q, 4, 4);
269 static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(
const mavlink_message_t* msg)
271 return _MAV_RETURN_float(msg, 20);
279 static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(
const mavlink_message_t* msg)
281 return _MAV_RETURN_float(msg, 24);
289 static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(
const mavlink_message_t* msg)
291 return _MAV_RETURN_float(msg, 28);
299 static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(
const mavlink_message_t* msg,
float *covariance)
301 return _MAV_RETURN_float_array(msg, covariance, 9, 32);
312 #if MAVLINK_NEED_BYTE_SWAP
313 attitude_quaternion_cov->
time_boot_ms = mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(msg);
314 mavlink_msg_attitude_quaternion_cov_get_q(msg, attitude_quaternion_cov->
q);
315 attitude_quaternion_cov->
rollspeed = mavlink_msg_attitude_quaternion_cov_get_rollspeed(msg);
316 attitude_quaternion_cov->
pitchspeed = mavlink_msg_attitude_quaternion_cov_get_pitchspeed(msg);
317 attitude_quaternion_cov->
yawspeed = mavlink_msg_attitude_quaternion_cov_get_yawspeed(msg);
318 mavlink_msg_attitude_quaternion_cov_get_covariance(msg, attitude_quaternion_cov->
covariance);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
float q[4]
Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
Definition: mavlink_msg_attitude_quaternion_cov.h:8
uint32_t time_boot_ms
Timestamp (milliseconds since system boot)
Definition: mavlink_msg_attitude_quaternion_cov.h:7
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV
Definition: mavlink_msg_attitude_quaternion_cov.h:3
float rollspeed
Roll angular speed (rad/s)
Definition: mavlink_msg_attitude_quaternion_cov.h:9
Definition: mavlink_msg_attitude_quaternion_cov.h:5
float covariance[9]
Attitude covariance.
Definition: mavlink_msg_attitude_quaternion_cov.h:12
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
float yawspeed
Yaw angular speed (rad/s)
Definition: mavlink_msg_attitude_quaternion_cov.h:11
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC
Definition: mavlink_msg_attitude_quaternion_cov.h:18
float pitchspeed
Pitch angular speed (rad/s)
Definition: mavlink_msg_attitude_quaternion_cov.h:10
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN
Definition: mavlink_msg_attitude_quaternion_cov.h:15
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
struct __mavlink_attitude_quaternion_cov_t mavlink_attitude_quaternion_cov_t
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141