4#define MAVLINK_MSG_ID_WIND 168
7typedef struct __mavlink_wind_t {
13#define MAVLINK_MSG_ID_WIND_LEN 12
14#define MAVLINK_MSG_ID_WIND_MIN_LEN 12
15#define MAVLINK_MSG_ID_168_LEN 12
16#define MAVLINK_MSG_ID_168_MIN_LEN 12
18#define MAVLINK_MSG_ID_WIND_CRC 1
19#define MAVLINK_MSG_ID_168_CRC 1
23#if MAVLINK_COMMAND_24BIT
24#define MAVLINK_MESSAGE_INFO_WIND { \
28 { { "direction", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_wind_t, direction) }, \
29 { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_wind_t, speed) }, \
30 { "speed_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_t, speed_z) }, \
34#define MAVLINK_MESSAGE_INFO_WIND { \
37 { { "direction", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_wind_t, direction) }, \
38 { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_wind_t, speed) }, \
39 { "speed_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_t, speed_z) }, \
55static inline uint16_t mavlink_msg_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
56 float direction,
float speed,
float speed_z)
58#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
59 char buf[MAVLINK_MSG_ID_WIND_LEN];
60 _mav_put_float(buf, 0, direction);
61 _mav_put_float(buf, 4, speed);
62 _mav_put_float(buf, 8, speed_z);
64 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN);
66 mavlink_wind_t packet;
67 packet.direction = direction;
69 packet.speed_z = speed_z;
71 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN);
74 msg->msgid = MAVLINK_MSG_ID_WIND;
75 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
89static inline uint16_t mavlink_msg_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
90 mavlink_message_t* msg,
91 float direction,
float speed,
float speed_z)
93#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
94 char buf[MAVLINK_MSG_ID_WIND_LEN];
95 _mav_put_float(buf, 0, direction);
96 _mav_put_float(buf, 4, speed);
97 _mav_put_float(buf, 8, speed_z);
99 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN);
101 mavlink_wind_t packet;
102 packet.direction = direction;
103 packet.speed = speed;
104 packet.speed_z = speed_z;
106 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN);
109 msg->msgid = MAVLINK_MSG_ID_WIND;
110 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
121static inline uint16_t mavlink_msg_wind_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_wind_t* wind)
123 return mavlink_msg_wind_pack(system_id, component_id, msg, wind->direction, wind->speed, wind->speed_z);
135static inline uint16_t mavlink_msg_wind_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_wind_t* wind)
137 return mavlink_msg_wind_pack_chan(system_id, component_id, chan, msg, wind->direction, wind->speed, wind->speed_z);
148#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
150static inline void mavlink_msg_wind_send(mavlink_channel_t chan,
float direction,
float speed,
float speed_z)
152#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
153 char buf[MAVLINK_MSG_ID_WIND_LEN];
154 _mav_put_float(buf, 0, direction);
155 _mav_put_float(buf, 4, speed);
156 _mav_put_float(buf, 8, speed_z);
158 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
160 mavlink_wind_t packet;
161 packet.direction = direction;
162 packet.speed = speed;
163 packet.speed_z = speed_z;
165 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (
const char *)&packet, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
174static inline void mavlink_msg_wind_send_struct(mavlink_channel_t chan,
const mavlink_wind_t* wind)
176#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
177 mavlink_msg_wind_send(chan, wind->direction, wind->speed, wind->speed_z);
179 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (
const char *)wind, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
183#if MAVLINK_MSG_ID_WIND_LEN <= MAVLINK_MAX_PAYLOAD_LEN
191static inline void mavlink_msg_wind_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,
float direction,
float speed,
float speed_z)
193#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
194 char *buf = (
char *)msgbuf;
195 _mav_put_float(buf, 0, direction);
196 _mav_put_float(buf, 4, speed);
197 _mav_put_float(buf, 8, speed_z);
199 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
201 mavlink_wind_t *packet = (mavlink_wind_t *)msgbuf;
202 packet->direction = direction;
203 packet->speed = speed;
204 packet->speed_z = speed_z;
206 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (
const char *)packet, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
221static inline float mavlink_msg_wind_get_direction(
const mavlink_message_t* msg)
223 return _MAV_RETURN_float(msg, 0);
231static inline float mavlink_msg_wind_get_speed(
const mavlink_message_t* msg)
233 return _MAV_RETURN_float(msg, 4);
241static inline float mavlink_msg_wind_get_speed_z(
const mavlink_message_t* msg)
243 return _MAV_RETURN_float(msg, 8);
252static inline void mavlink_msg_wind_decode(
const mavlink_message_t* msg, mavlink_wind_t* wind)
254#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
255 wind->direction = mavlink_msg_wind_get_direction(msg);
256 wind->speed = mavlink_msg_wind_get_speed(msg);
257 wind->speed_z = mavlink_msg_wind_get_speed_z(msg);
259 uint8_t len = msg->len < MAVLINK_MSG_ID_WIND_LEN? msg->len : MAVLINK_MSG_ID_WIND_LEN;
260 memset(wind, 0, MAVLINK_MSG_ID_WIND_LEN);
261 memcpy(wind, _MAV_PAYLOAD(msg), len);