RflySimSDK v3.05
RflySimSDK说明文档
载入中...
搜索中...
未找到
mavlink_msg_vfr_hud.h
1#pragma once
2// MESSAGE VFR_HUD PACKING
3
4#define MAVLINK_MSG_ID_VFR_HUD 74
5
6MAVPACKED(
7typedef struct __mavlink_vfr_hud_t {
8 float airspeed; /*< Current airspeed in m/s*/
9 float groundspeed; /*< Current ground speed in m/s*/
10 float alt; /*< Current altitude (MSL), in meters*/
11 float climb; /*< Current climb rate in meters/second*/
12 int16_t heading; /*< Current heading in degrees, in compass units (0..360, 0=north)*/
13 uint16_t throttle; /*< Current throttle setting in integer percent, 0 to 100*/
14}) mavlink_vfr_hud_t;
15
16#define MAVLINK_MSG_ID_VFR_HUD_LEN 20
17#define MAVLINK_MSG_ID_VFR_HUD_MIN_LEN 20
18#define MAVLINK_MSG_ID_74_LEN 20
19#define MAVLINK_MSG_ID_74_MIN_LEN 20
20
21#define MAVLINK_MSG_ID_VFR_HUD_CRC 20
22#define MAVLINK_MSG_ID_74_CRC 20
23
24
25
26#if MAVLINK_COMMAND_24BIT
27#define MAVLINK_MESSAGE_INFO_VFR_HUD { \
28 74, \
29 "VFR_HUD", \
30 6, \
31 { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \
32 { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \
33 { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \
34 { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \
35 { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \
36 { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \
37 } \
38}
39#else
40#define MAVLINK_MESSAGE_INFO_VFR_HUD { \
41 "VFR_HUD", \
42 6, \
43 { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \
44 { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \
45 { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \
46 { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \
47 { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \
48 { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \
49 } \
50}
51#endif
52
67static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
68 float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
69{
70#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
71 char buf[MAVLINK_MSG_ID_VFR_HUD_LEN];
72 _mav_put_float(buf, 0, airspeed);
73 _mav_put_float(buf, 4, groundspeed);
74 _mav_put_float(buf, 8, alt);
75 _mav_put_float(buf, 12, climb);
76 _mav_put_int16_t(buf, 16, heading);
77 _mav_put_uint16_t(buf, 18, throttle);
78
79 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN);
80#else
81 mavlink_vfr_hud_t packet;
82 packet.airspeed = airspeed;
83 packet.groundspeed = groundspeed;
84 packet.alt = alt;
85 packet.climb = climb;
86 packet.heading = heading;
87 packet.throttle = throttle;
88
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN);
90#endif
91
92 msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
93 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
94}
95
110static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
111 mavlink_message_t* msg,
112 float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb)
113{
114#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
115 char buf[MAVLINK_MSG_ID_VFR_HUD_LEN];
116 _mav_put_float(buf, 0, airspeed);
117 _mav_put_float(buf, 4, groundspeed);
118 _mav_put_float(buf, 8, alt);
119 _mav_put_float(buf, 12, climb);
120 _mav_put_int16_t(buf, 16, heading);
121 _mav_put_uint16_t(buf, 18, throttle);
122
123 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN);
124#else
125 mavlink_vfr_hud_t packet;
126 packet.airspeed = airspeed;
127 packet.groundspeed = groundspeed;
128 packet.alt = alt;
129 packet.climb = climb;
130 packet.heading = heading;
131 packet.throttle = throttle;
132
133 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN);
134#endif
135
136 msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
137 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
138}
139
148static 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)
149{
150 return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb);
151}
152
162static 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)
163{
164 return mavlink_msg_vfr_hud_pack_chan(system_id, component_id, chan, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb);
165}
166
178#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
179
180static 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)
181{
182#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
183 char buf[MAVLINK_MSG_ID_VFR_HUD_LEN];
184 _mav_put_float(buf, 0, airspeed);
185 _mav_put_float(buf, 4, groundspeed);
186 _mav_put_float(buf, 8, alt);
187 _mav_put_float(buf, 12, climb);
188 _mav_put_int16_t(buf, 16, heading);
189 _mav_put_uint16_t(buf, 18, throttle);
190
191 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
192#else
193 mavlink_vfr_hud_t packet;
194 packet.airspeed = airspeed;
195 packet.groundspeed = groundspeed;
196 packet.alt = alt;
197 packet.climb = climb;
198 packet.heading = heading;
199 packet.throttle = throttle;
200
201 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
202#endif
203}
204
210static inline void mavlink_msg_vfr_hud_send_struct(mavlink_channel_t chan, const mavlink_vfr_hud_t* vfr_hud)
211{
212#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213 mavlink_msg_vfr_hud_send(chan, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb);
214#else
215 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)vfr_hud, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
216#endif
217}
218
219#if MAVLINK_MSG_ID_VFR_HUD_LEN <= MAVLINK_MAX_PAYLOAD_LEN
220/*
221 This varient of _send() can be used to save stack space by re-using
222 memory from the receive buffer. The caller provides a
223 mavlink_message_t which is the size of a full mavlink message. This
224 is usually the receive buffer for the channel, and allows a reply to an
225 incoming message with minimum stack space usage.
226 */
227static 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)
228{
229#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
230 char *buf = (char *)msgbuf;
231 _mav_put_float(buf, 0, airspeed);
232 _mav_put_float(buf, 4, groundspeed);
233 _mav_put_float(buf, 8, alt);
234 _mav_put_float(buf, 12, climb);
235 _mav_put_int16_t(buf, 16, heading);
236 _mav_put_uint16_t(buf, 18, throttle);
237
238 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
239#else
240 mavlink_vfr_hud_t *packet = (mavlink_vfr_hud_t *)msgbuf;
241 packet->airspeed = airspeed;
242 packet->groundspeed = groundspeed;
243 packet->alt = alt;
244 packet->climb = climb;
245 packet->heading = heading;
246 packet->throttle = throttle;
247
248 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
249#endif
250}
251#endif
252
253#endif
254
255// MESSAGE VFR_HUD UNPACKING
256
257
263static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg)
264{
265 return _MAV_RETURN_float(msg, 0);
266}
267
273static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg)
274{
275 return _MAV_RETURN_float(msg, 4);
276}
277
283static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg)
284{
285 return _MAV_RETURN_int16_t(msg, 16);
286}
287
293static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg)
294{
295 return _MAV_RETURN_uint16_t(msg, 18);
296}
297
303static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg)
304{
305 return _MAV_RETURN_float(msg, 8);
306}
307
313static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg)
314{
315 return _MAV_RETURN_float(msg, 12);
316}
317
324static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud)
325{
326#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
327 vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg);
328 vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg);
329 vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg);
330 vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg);
331 vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg);
332 vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg);
333#else
334 uint8_t len = msg->len < MAVLINK_MSG_ID_VFR_HUD_LEN? msg->len : MAVLINK_MSG_ID_VFR_HUD_LEN;
335 memset(vfr_hud, 0, MAVLINK_MSG_ID_VFR_HUD_LEN);
336 memcpy(vfr_hud, _MAV_PAYLOAD(msg), len);
337#endif
338}