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
54 char buf[MAVLINK_MSG_ID_VFR_HUD_LEN];
55 _mav_put_float(buf, 0, airspeed);
56 _mav_put_float(buf, 4, groundspeed);
57 _mav_put_float(buf, 8, alt);
58 _mav_put_float(buf, 12, climb);
59 _mav_put_int16_t(buf, 16, heading);
60 _mav_put_uint16_t(buf, 18, throttle);
62 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN);
72 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN);
75 msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
77 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
79 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_LEN);
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
102 char buf[MAVLINK_MSG_ID_VFR_HUD_LEN];
103 _mav_put_float(buf, 0, airspeed);
104 _mav_put_float(buf, 4, groundspeed);
105 _mav_put_float(buf, 8, alt);
106 _mav_put_float(buf, 12, climb);
107 _mav_put_int16_t(buf, 16, heading);
108 _mav_put_uint16_t(buf, 18, throttle);
110 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN);
116 packet.
climb = climb;
120 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN);
123 msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
124 #if MAVLINK_CRC_EXTRA
125 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
127 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_LEN);
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
174 char buf[MAVLINK_MSG_ID_VFR_HUD_LEN];
175 _mav_put_float(buf, 0, airspeed);
176 _mav_put_float(buf, 4, groundspeed);
177 _mav_put_float(buf, 8, alt);
178 _mav_put_float(buf, 12, climb);
179 _mav_put_int16_t(buf, 16, heading);
180 _mav_put_uint16_t(buf, 18, throttle);
182 #if MAVLINK_CRC_EXTRA
183 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
185 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN);
192 packet.
climb = climb;
196 #if MAVLINK_CRC_EXTRA
197 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (
const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
199 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (
const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_LEN);
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;
216 _mav_put_float(buf, 0, airspeed);
217 _mav_put_float(buf, 4, groundspeed);
218 _mav_put_float(buf, 8, alt);
219 _mav_put_float(buf, 12, climb);
220 _mav_put_int16_t(buf, 16, heading);
221 _mav_put_uint16_t(buf, 18, throttle);
223 #if MAVLINK_CRC_EXTRA
224 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
226 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN);
233 packet->
climb = climb;
237 #if MAVLINK_CRC_EXTRA
238 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (
const char *)packet, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
240 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (
const char *)packet, MAVLINK_MSG_ID_VFR_HUD_LEN);
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);
327 memcpy(vfr_hud, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VFR_HUD_LEN);
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
float groundspeed
Current ground speed in m/s.
Definition: mavlink_msg_vfr_hud.h:8
int16_t heading
Current heading in degrees, in compass units (0..360, 0=north)
Definition: mavlink_msg_vfr_hud.h:11
uint16_t throttle
Current throttle setting in integer percent, 0 to 100.
Definition: mavlink_msg_vfr_hud.h:12
float airspeed
Current airspeed in m/s.
Definition: mavlink_msg_vfr_hud.h:7
Definition: mavlink_msg_vfr_hud.h:5