3 #define MAVLINK_MSG_ID_WIND 168
12 #define MAVLINK_MSG_ID_WIND_LEN 12
13 #define MAVLINK_MSG_ID_168_LEN 12
15 #define MAVLINK_MSG_ID_WIND_CRC 1
16 #define MAVLINK_MSG_ID_168_CRC 1
20 #define MAVLINK_MESSAGE_INFO_WIND { \
23 { { "direction", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_wind_t, direction) }, \
24 { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_wind_t, speed) }, \
25 { "speed_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_t, speed_z) }, \
41 static inline uint16_t mavlink_msg_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42 float direction,
float speed,
float speed_z)
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
79 static inline uint16_t mavlink_msg_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
80 mavlink_message_t* msg,
81 float direction,
float speed,
float speed_z)
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
100 #if MAVLINK_CRC_EXTRA
115 static inline uint16_t mavlink_msg_wind_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_wind_t* wind)
117 return mavlink_msg_wind_pack(system_id, component_id, msg, wind->
direction, wind->
speed, wind->
speed_z);
129 static 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)
131 return mavlink_msg_wind_pack_chan(system_id, component_id, chan, msg, wind->
direction, wind->
speed, wind->
speed_z);
142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
144 static inline void mavlink_msg_wind_send(
mavlink_channel_t chan,
float direction,
float speed,
float speed_z)
146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
152 #if MAVLINK_CRC_EXTRA
160 packet.
speed = speed;
163 #if MAVLINK_CRC_EXTRA
171 #if MAVLINK_MSG_ID_WIND_LEN <= MAVLINK_MAX_PAYLOAD_LEN
179 static inline void mavlink_msg_wind_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan,
float direction,
float speed,
float speed_z)
181 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 char *buf = (
char *)msgbuf;
187 #if MAVLINK_CRC_EXTRA
195 packet->
speed = speed;
198 #if MAVLINK_CRC_EXTRA
217 static inline float mavlink_msg_wind_get_direction(
const mavlink_message_t* msg)
219 return _MAV_RETURN_float(msg, 0);
227 static inline float mavlink_msg_wind_get_speed(
const mavlink_message_t* msg)
229 return _MAV_RETURN_float(msg, 4);
237 static inline float mavlink_msg_wind_get_speed_z(
const mavlink_message_t* msg)
239 return _MAV_RETURN_float(msg, 8);
248 static inline void mavlink_msg_wind_decode(
const mavlink_message_t* msg,
mavlink_wind_t* wind)
250 #if MAVLINK_NEED_BYTE_SWAP
251 wind->
direction = mavlink_msg_wind_get_direction(msg);
252 wind->
speed = mavlink_msg_wind_get_speed(msg);
253 wind->
speed_z = mavlink_msg_wind_get_speed_z(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
#define MAVLINK_MSG_ID_WIND_CRC
Definition: mavlink_msg_wind.h:15
#define MAVLINK_MSG_ID_WIND
Definition: mavlink_msg_wind.h:3
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 MAVLINK_MSG_ID_WIND_LEN
Definition: mavlink_msg_wind.h:12
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
struct __mavlink_wind_t mavlink_wind_t
mavlink_channel_t
Definition: mavlink_types.h:178
float speed_z
vertical wind speed (m/s)
Definition: mavlink_msg_wind.h:9
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
float speed
wind speed in ground plane (m/s)
Definition: mavlink_msg_wind.h:8
Definition: mavlink_msg_wind.h:5
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
float direction
wind direction that wind is coming from (degrees)
Definition: mavlink_msg_wind.h:7