3 #define MAVLINK_MSG_ID_WIND_COV 231 18 #define MAVLINK_MSG_ID_WIND_COV_LEN 40 19 #define MAVLINK_MSG_ID_231_LEN 40 21 #define MAVLINK_MSG_ID_WIND_COV_CRC 105 22 #define MAVLINK_MSG_ID_231_CRC 105 26 #define MAVLINK_MESSAGE_INFO_WIND_COV { \ 29 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wind_cov_t, time_usec) }, \ 30 { "wind_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_cov_t, wind_x) }, \ 31 { "wind_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wind_cov_t, wind_y) }, \ 32 { "wind_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wind_cov_t, wind_z) }, \ 33 { "var_horiz", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wind_cov_t, var_horiz) }, \ 34 { "var_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wind_cov_t, var_vert) }, \ 35 { "wind_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wind_cov_t, wind_alt) }, \ 36 { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wind_cov_t, horiz_accuracy) }, \ 37 { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wind_cov_t, vert_accuracy) }, \ 62 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 116 mavlink_message_t* msg,
119 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 148 #if MAVLINK_CRC_EXTRA 165 return mavlink_msg_wind_cov_pack(system_id, component_id, msg, wind_cov->
time_usec, wind_cov->
wind_x, wind_cov->
wind_y, wind_cov->
wind_z, wind_cov->
var_horiz, wind_cov->
var_vert, wind_cov->
wind_alt, wind_cov->
horiz_accuracy, wind_cov->
vert_accuracy);
179 return mavlink_msg_wind_cov_pack_chan(system_id, component_id, chan, msg, wind_cov->
time_usec, wind_cov->
wind_x, wind_cov->
wind_y, wind_cov->
wind_z, wind_cov->
var_horiz, wind_cov->
var_vert, wind_cov->
wind_alt, wind_cov->
horiz_accuracy, wind_cov->
vert_accuracy);
196 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 200 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 212 #if MAVLINK_CRC_EXTRA 229 #if MAVLINK_CRC_EXTRA 237 #if MAVLINK_MSG_ID_WIND_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN 245 static inline void mavlink_msg_wind_cov_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t
time_usec,
float wind_x,
float wind_y,
float wind_z,
float var_horiz,
float var_vert,
float wind_alt,
float horiz_accuracy,
float vert_accuracy)
247 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 248 char *buf = (
char *)msgbuf;
259 #if MAVLINK_CRC_EXTRA 276 #if MAVLINK_CRC_EXTRA 297 return _MAV_RETURN_uint64_t(msg, 0);
307 return _MAV_RETURN_float(msg, 8);
317 return _MAV_RETURN_float(msg, 12);
327 return _MAV_RETURN_float(msg, 16);
337 return _MAV_RETURN_float(msg, 20);
347 return _MAV_RETURN_float(msg, 24);
357 return _MAV_RETURN_float(msg, 28);
367 return _MAV_RETURN_float(msg, 32);
377 return _MAV_RETURN_float(msg, 36);
388 #if MAVLINK_NEED_BYTE_SWAP static float mavlink_msg_wind_cov_get_var_vert(const mavlink_message_t *msg)
Get field var_vert from wind_cov message.
#define _mav_put_float(buf, wire_offset, b)
static uint16_t mavlink_msg_wind_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy)
Pack a wind_cov message on a channel.
static uint64_t mavlink_msg_wind_cov_get_time_usec(const mavlink_message_t *msg)
Send a wind_cov message.
static uint16_t mavlink_msg_wind_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_wind_cov_t *wind_cov)
Encode a wind_cov struct on a channel.
static float mavlink_msg_wind_cov_get_wind_x(const mavlink_message_t *msg)
Get field wind_x from wind_cov message.
static float mavlink_msg_wind_cov_get_wind_alt(const mavlink_message_t *msg)
Get field wind_alt from wind_cov message.
static float mavlink_msg_wind_cov_get_vert_accuracy(const mavlink_message_t *msg)
Get field vert_accuracy from wind_cov message.
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.
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static float mavlink_msg_wind_cov_get_wind_y(const mavlink_message_t *msg)
Get field wind_y from wind_cov message.
static uint16_t mavlink_msg_wind_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_wind_cov_t *wind_cov)
Encode a wind_cov struct.
#define _MAV_PAYLOAD(msg)
#define MAVLINK_MSG_ID_WIND_COV
#define MAVLINK_MSG_ID_WIND_COV_LEN
static uint16_t mavlink_msg_wind_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy)
Pack a wind_cov message.
static float mavlink_msg_wind_cov_get_horiz_accuracy(const mavlink_message_t *msg)
Get field horiz_accuracy from wind_cov message.
#define MAVLINK_MSG_ID_WIND_COV_CRC
static void mavlink_msg_wind_cov_decode(const mavlink_message_t *msg, mavlink_wind_cov_t *wind_cov)
Decode a wind_cov message into a struct.
static float mavlink_msg_wind_cov_get_wind_z(const mavlink_message_t *msg)
Get field wind_z from wind_cov message.
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.
static float mavlink_msg_wind_cov_get_var_horiz(const mavlink_message_t *msg)
Get field var_horiz from wind_cov message.
struct __mavlink_wind_cov_t mavlink_wind_cov_t