Merge remote-tracking branch 'upstream/master' into abo_fw_alt_vel_control
[inav.git] / lib / main / MAVLink / common / mavlink_msg_vfr_hud.h
blobf1706ea65c6e1bf8561ffb85236be914af2669a5
1 #pragma once
2 // MESSAGE VFR_HUD PACKING
4 #define MAVLINK_MSG_ID_VFR_HUD 74
7 typedef struct __mavlink_vfr_hud_t {
8 float airspeed; /*< [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.*/
9 float groundspeed; /*< [m/s] Current ground speed.*/
10 float alt; /*< [m] Current altitude (MSL).*/
11 float climb; /*< [m/s] Current climb rate.*/
12 int16_t heading; /*< [deg] Current heading in compass units (0-360, 0=north).*/
13 uint16_t throttle; /*< [%] Current throttle setting (0 to 100).*/
14 } mavlink_vfr_hud_t;
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
21 #define MAVLINK_MSG_ID_VFR_HUD_CRC 20
22 #define MAVLINK_MSG_ID_74_CRC 20
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 } \
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 } \
51 #endif
53 /**
54 * @brief Pack a vfr_hud message
55 * @param system_id ID of this system
56 * @param component_id ID of this component (e.g. 200 for IMU)
57 * @param msg The MAVLink message to compress the data into
59 * @param airspeed [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.
60 * @param groundspeed [m/s] Current ground speed.
61 * @param heading [deg] Current heading in compass units (0-360, 0=north).
62 * @param throttle [%] Current throttle setting (0 to 100).
63 * @param alt [m] Current altitude (MSL).
64 * @param climb [m/s] Current climb rate.
65 * @return length of the message in bytes (excluding serial stream start sign)
67 static 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)
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);
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;
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN);
90 #endif
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);
96 /**
97 * @brief Pack a vfr_hud message on a channel
98 * @param system_id ID of this system
99 * @param component_id ID of this component (e.g. 200 for IMU)
100 * @param chan The MAVLink channel this message will be sent over
101 * @param msg The MAVLink message to compress the data into
102 * @param airspeed [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.
103 * @param groundspeed [m/s] Current ground speed.
104 * @param heading [deg] Current heading in compass units (0-360, 0=north).
105 * @param throttle [%] Current throttle setting (0 to 100).
106 * @param alt [m] Current altitude (MSL).
107 * @param climb [m/s] Current climb rate.
108 * @return length of the message in bytes (excluding serial stream start sign)
110 static 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)
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);
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;
133 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN);
134 #endif
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);
141 * @brief Encode a vfr_hud struct
143 * @param system_id ID of this system
144 * @param component_id ID of this component (e.g. 200 for IMU)
145 * @param msg The MAVLink message to compress the data into
146 * @param vfr_hud C-struct to read the message contents from
148 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)
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);
154 * @brief Encode a vfr_hud struct on a channel
156 * @param system_id ID of this system
157 * @param component_id ID of this component (e.g. 200 for IMU)
158 * @param chan The MAVLink channel this message will be sent over
159 * @param msg The MAVLink message to compress the data into
160 * @param vfr_hud C-struct to read the message contents from
162 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)
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);
168 * @brief Send a vfr_hud message
169 * @param chan MAVLink channel to send the message
171 * @param airspeed [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.
172 * @param groundspeed [m/s] Current ground speed.
173 * @param heading [deg] Current heading in compass units (0-360, 0=north).
174 * @param throttle [%] Current throttle setting (0 to 100).
175 * @param alt [m] Current altitude (MSL).
176 * @param climb [m/s] Current climb rate.
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
180 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)
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);
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;
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
206 * @brief Send a vfr_hud message
207 * @param chan MAVLink channel to send the message
208 * @param struct The MAVLink struct to serialize
210 static inline void mavlink_msg_vfr_hud_send_struct(mavlink_channel_t chan, const mavlink_vfr_hud_t* vfr_hud)
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
219 #if MAVLINK_MSG_ID_VFR_HUD_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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.
227 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)
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);
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;
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
251 #endif
253 #endif
255 // MESSAGE VFR_HUD UNPACKING
259 * @brief Get field airspeed from vfr_hud message
261 * @return [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.
263 static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg)
265 return _MAV_RETURN_float(msg, 0);
269 * @brief Get field groundspeed from vfr_hud message
271 * @return [m/s] Current ground speed.
273 static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg)
275 return _MAV_RETURN_float(msg, 4);
279 * @brief Get field heading from vfr_hud message
281 * @return [deg] Current heading in compass units (0-360, 0=north).
283 static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg)
285 return _MAV_RETURN_int16_t(msg, 16);
289 * @brief Get field throttle from vfr_hud message
291 * @return [%] Current throttle setting (0 to 100).
293 static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg)
295 return _MAV_RETURN_uint16_t(msg, 18);
299 * @brief Get field alt from vfr_hud message
301 * @return [m] Current altitude (MSL).
303 static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg)
305 return _MAV_RETURN_float(msg, 8);
309 * @brief Get field climb from vfr_hud message
311 * @return [m/s] Current climb rate.
313 static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg)
315 return _MAV_RETURN_float(msg, 12);
319 * @brief Decode a vfr_hud message into a struct
321 * @param msg The message to decode
322 * @param vfr_hud C-struct to decode the message contents into
324 static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud)
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