Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE VFR_HUD PACKING
2
 
3
#define MAVLINK_MSG_ID_VFR_HUD 74
4
 
5
typedef struct __mavlink_vfr_hud_t
6
{
7
 float airspeed; ///< Current airspeed in m/s
8
 float groundspeed; ///< Current ground speed in m/s
9
 float alt; ///< Current altitude (MSL), in meters
10
 float climb; ///< Current climb rate in meters/second
11
 int16_t heading; ///< Current heading in degrees, in compass units (0..360, 0=north)
12
 uint16_t throttle; ///< Current throttle setting in integer percent, 0 to 100
13
} mavlink_vfr_hud_t;
14
 
15
#define MAVLINK_MSG_ID_VFR_HUD_LEN 20
16
#define MAVLINK_MSG_ID_74_LEN 20
17
 
18
 
19
 
20
#define MAVLINK_MESSAGE_INFO_VFR_HUD { \
21
        "VFR_HUD", \
22
        6, \
23
        {  { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \
24
         { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \
25
         { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \
26
         { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \
27
         { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \
28
         { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \
29
         } \
30
}
31
 
32
 
33
/**
34
 * @brief Pack a vfr_hud message
35
 * @param system_id ID of this system
36
 * @param component_id ID of this component (e.g. 200 for IMU)
37
 * @param msg The MAVLink message to compress the data into
38
 *
39
 * @param airspeed Current airspeed in m/s
40
 * @param groundspeed Current ground speed in m/s
41
 * @param heading Current heading in degrees, in compass units (0..360, 0=north)
42
 * @param throttle Current throttle setting in integer percent, 0 to 100
43
 * @param alt Current altitude (MSL), in meters
44
 * @param climb Current climb rate in meters/second
45
 * @return length of the message in bytes (excluding serial stream start sign)
46
 */
47
static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48
                                                       float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
49
{
50
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51
        char buf[20];
52
        _mav_put_float(buf, 0, airspeed);
53
        _mav_put_float(buf, 4, groundspeed);
54
        _mav_put_float(buf, 8, alt);
55
        _mav_put_float(buf, 12, climb);
56
        _mav_put_int16_t(buf, 16, heading);
57
        _mav_put_uint16_t(buf, 18, throttle);
58
 
59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
60
#else
61
        mavlink_vfr_hud_t packet;
62
        packet.airspeed = airspeed;
63
        packet.groundspeed = groundspeed;
64
        packet.alt = alt;
65
        packet.climb = climb;
66
        packet.heading = heading;
67
        packet.throttle = throttle;
68
 
69
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
70
#endif
71
 
72
        msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
73
        return mavlink_finalize_message(msg, system_id, component_id, 20, 20);
74
}
75
 
76
/**
77
 * @brief Pack a vfr_hud message on a channel
78
 * @param system_id ID of this system
79
 * @param component_id ID of this component (e.g. 200 for IMU)
80
 * @param chan The MAVLink channel this message was sent over
81
 * @param msg The MAVLink message to compress the data into
82
 * @param airspeed Current airspeed in m/s
83
 * @param groundspeed Current ground speed in m/s
84
 * @param heading Current heading in degrees, in compass units (0..360, 0=north)
85
 * @param throttle Current throttle setting in integer percent, 0 to 100
86
 * @param alt Current altitude (MSL), in meters
87
 * @param climb Current climb rate in meters/second
88
 * @return length of the message in bytes (excluding serial stream start sign)
89
 */
90
static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
91
                                                           mavlink_message_t* msg,
92
                                                           float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb)
93
{
94
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
95
        char buf[20];
96
        _mav_put_float(buf, 0, airspeed);
97
        _mav_put_float(buf, 4, groundspeed);
98
        _mav_put_float(buf, 8, alt);
99
        _mav_put_float(buf, 12, climb);
100
        _mav_put_int16_t(buf, 16, heading);
101
        _mav_put_uint16_t(buf, 18, throttle);
102
 
103
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
104
#else
105
        mavlink_vfr_hud_t packet;
106
        packet.airspeed = airspeed;
107
        packet.groundspeed = groundspeed;
108
        packet.alt = alt;
109
        packet.climb = climb;
110
        packet.heading = heading;
111
        packet.throttle = throttle;
112
 
113
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
114
#endif
115
 
116
        msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
117
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 20);
118
}
119
 
120
/**
121
 * @brief Encode a vfr_hud struct into a message
122
 *
123
 * @param system_id ID of this system
124
 * @param component_id ID of this component (e.g. 200 for IMU)
125
 * @param msg The MAVLink message to compress the data into
126
 * @param vfr_hud C-struct to read the message contents from
127
 */
128
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)
129
{
130
        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);
131
}
132
 
133
/**
134
 * @brief Send a vfr_hud message
135
 * @param chan MAVLink channel to send the message
136
 *
137
 * @param airspeed Current airspeed in m/s
138
 * @param groundspeed Current ground speed in m/s
139
 * @param heading Current heading in degrees, in compass units (0..360, 0=north)
140
 * @param throttle Current throttle setting in integer percent, 0 to 100
141
 * @param alt Current altitude (MSL), in meters
142
 * @param climb Current climb rate in meters/second
143
 */
144
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
145
 
146
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)
147
{
148
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
149
        char buf[20];
150
        _mav_put_float(buf, 0, airspeed);
151
        _mav_put_float(buf, 4, groundspeed);
152
        _mav_put_float(buf, 8, alt);
153
        _mav_put_float(buf, 12, climb);
154
        _mav_put_int16_t(buf, 16, heading);
155
        _mav_put_uint16_t(buf, 18, throttle);
156
 
157
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, 20, 20);
158
#else
159
        mavlink_vfr_hud_t packet;
160
        packet.airspeed = airspeed;
161
        packet.groundspeed = groundspeed;
162
        packet.alt = alt;
163
        packet.climb = climb;
164
        packet.heading = heading;
165
        packet.throttle = throttle;
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, 20, 20);
168
#endif
169
}
170
 
171
#endif
172
 
173
// MESSAGE VFR_HUD UNPACKING
174
 
175
 
176
/**
177
 * @brief Get field airspeed from vfr_hud message
178
 *
179
 * @return Current airspeed in m/s
180
 */
181
static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg)
182
{
183
        return _MAV_RETURN_float(msg,  0);
184
}
185
 
186
/**
187
 * @brief Get field groundspeed from vfr_hud message
188
 *
189
 * @return Current ground speed in m/s
190
 */
191
static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg)
192
{
193
        return _MAV_RETURN_float(msg,  4);
194
}
195
 
196
/**
197
 * @brief Get field heading from vfr_hud message
198
 *
199
 * @return Current heading in degrees, in compass units (0..360, 0=north)
200
 */
201
static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg)
202
{
203
        return _MAV_RETURN_int16_t(msg,  16);
204
}
205
 
206
/**
207
 * @brief Get field throttle from vfr_hud message
208
 *
209
 * @return Current throttle setting in integer percent, 0 to 100
210
 */
211
static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg)
212
{
213
        return _MAV_RETURN_uint16_t(msg,  18);
214
}
215
 
216
/**
217
 * @brief Get field alt from vfr_hud message
218
 *
219
 * @return Current altitude (MSL), in meters
220
 */
221
static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg)
222
{
223
        return _MAV_RETURN_float(msg,  8);
224
}
225
 
226
/**
227
 * @brief Get field climb from vfr_hud message
228
 *
229
 * @return Current climb rate in meters/second
230
 */
231
static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg)
232
{
233
        return _MAV_RETURN_float(msg,  12);
234
}
235
 
236
/**
237
 * @brief Decode a vfr_hud message into a struct
238
 *
239
 * @param msg The message to decode
240
 * @param vfr_hud C-struct to decode the message contents into
241
 */
242
static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud)
243
{
244
#if MAVLINK_NEED_BYTE_SWAP
245
        vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg);
246
        vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg);
247
        vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg);
248
        vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg);
249
        vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg);
250
        vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg);
251
#else
252
        memcpy(vfr_hud, _MAV_PAYLOAD(msg), 20);
253
#endif
254
}