3 #define MAVLINK_MSG_ID_VFR_HUD 74
15 #define MAVLINK_MSG_ID_VFR_HUD_LEN 20
16 #define MAVLINK_MSG_ID_74_LEN 20
18 #define MAVLINK_MSG_ID_VFR_HUD_CRC 20
19 #define MAVLINK_MSG_ID_74_CRC 20
23 #define MAVLINK_MESSAGE_INFO_VFR_HUD { \
26 { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \
27 { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \
28 { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \
29 { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \
30 { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \
31 { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \
50 static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51 float airspeed,
float groundspeed, int16_t heading, uint16_t
throttle,
float alt,
float climb)
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
97 static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
98 mavlink_message_t* msg,
99 float airspeed,
float groundspeed,int16_t heading,uint16_t
throttle,
float alt,
float climb)
101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
116 packet.
climb = climb;
124 #if MAVLINK_CRC_EXTRA
139 static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_vfr_hud_t* vfr_hud)
153 static inline uint16_t mavlink_msg_vfr_hud_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_vfr_hud_t* vfr_hud)
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
171 static inline void mavlink_msg_vfr_hud_send(
mavlink_channel_t chan,
float airspeed,
float groundspeed, int16_t heading, uint16_t throttle,
float alt,
float climb)
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 #if MAVLINK_CRC_EXTRA
192 packet.
climb = climb;
196 #if MAVLINK_CRC_EXTRA
204 #if MAVLINK_MSG_ID_VFR_HUD_LEN <= MAVLINK_MAX_PAYLOAD_LEN
212 static inline void mavlink_msg_vfr_hud_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan,
float airspeed,
float groundspeed, int16_t heading, uint16_t throttle,
float alt,
float climb)
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215 char *buf = (
char *)msgbuf;
223 #if MAVLINK_CRC_EXTRA
233 packet->
climb = climb;
237 #if MAVLINK_CRC_EXTRA
256 static inline float mavlink_msg_vfr_hud_get_airspeed(
const mavlink_message_t* msg)
258 return _MAV_RETURN_float(msg, 0);
266 static inline float mavlink_msg_vfr_hud_get_groundspeed(
const mavlink_message_t* msg)
268 return _MAV_RETURN_float(msg, 4);
276 static inline int16_t mavlink_msg_vfr_hud_get_heading(
const mavlink_message_t* msg)
278 return _MAV_RETURN_int16_t(msg, 16);
286 static inline uint16_t mavlink_msg_vfr_hud_get_throttle(
const mavlink_message_t* msg)
288 return _MAV_RETURN_uint16_t(msg, 18);
296 static inline float mavlink_msg_vfr_hud_get_alt(
const mavlink_message_t* msg)
298 return _MAV_RETURN_float(msg, 8);
306 static inline float mavlink_msg_vfr_hud_get_climb(
const mavlink_message_t* msg)
308 return _MAV_RETURN_float(msg, 12);
317 static inline void mavlink_msg_vfr_hud_decode(
const mavlink_message_t* msg,
mavlink_vfr_hud_t* vfr_hud)
319 #if MAVLINK_NEED_BYTE_SWAP
320 vfr_hud->
airspeed = mavlink_msg_vfr_hud_get_airspeed(msg);
321 vfr_hud->
groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg);
322 vfr_hud->
alt = mavlink_msg_vfr_hud_get_alt(msg);
323 vfr_hud->
climb = mavlink_msg_vfr_hud_get_climb(msg);
324 vfr_hud->
heading = mavlink_msg_vfr_hud_get_heading(msg);
325 vfr_hud->
throttle = mavlink_msg_vfr_hud_get_throttle(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
float alt
Current altitude (MSL), in meters.
Definition: mavlink_msg_vfr_hud.h:9
float climb
Current climb rate in meters/second.
Definition: mavlink_msg_vfr_hud.h:10
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
struct throttle_correction_config throttle
Definition: config.h:98
#define MAVLINK_MSG_ID_VFR_HUD
Definition: mavlink_msg_vfr_hud.h:3
mavlink_channel_t
Definition: mavlink_types.h:178
struct __mavlink_vfr_hud_t mavlink_vfr_hud_t
float groundspeed
Current ground speed in m/s.
Definition: mavlink_msg_vfr_hud.h:8
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
#define MAVLINK_MSG_ID_VFR_HUD_CRC
Definition: mavlink_msg_vfr_hud.h:18
int16_t heading
Current heading in degrees, in compass units (0..360, 0=north)
Definition: mavlink_msg_vfr_hud.h:11
#define MAVLINK_MSG_ID_VFR_HUD_LEN
Definition: mavlink_msg_vfr_hud.h:15
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
uint16_t throttle
Current throttle setting in integer percent, 0 to 100.
Definition: mavlink_msg_vfr_hud.h:12
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
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:140
float airspeed
Current airspeed in m/s.
Definition: mavlink_msg_vfr_hud.h:7
Definition: mavlink_msg_vfr_hud.h:5