1 | // MESSAGE NAV_CONTROLLER_OUTPUT PACKING |
---|
2 | |
---|
3 | #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 |
---|
4 | |
---|
5 | MAVPACKED( |
---|
6 | typedef struct __mavlink_nav_controller_output_t { |
---|
7 | float nav_roll; /*< Current desired roll in degrees*/ |
---|
8 | float nav_pitch; /*< Current desired pitch in degrees*/ |
---|
9 | float alt_error; /*< Current altitude error in meters*/ |
---|
10 | float aspd_error; /*< Current airspeed error in meters/second*/ |
---|
11 | float xtrack_error; /*< Current crosstrack error on x-y plane in meters*/ |
---|
12 | int16_t nav_bearing; /*< Current desired heading in degrees*/ |
---|
13 | int16_t target_bearing; /*< Bearing to current MISSION/target in degrees*/ |
---|
14 | uint16_t wp_dist; /*< Distance to active MISSION in meters*/ |
---|
15 | }) mavlink_nav_controller_output_t; |
---|
16 | |
---|
17 | #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 |
---|
18 | #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN 26 |
---|
19 | #define MAVLINK_MSG_ID_62_LEN 26 |
---|
20 | #define MAVLINK_MSG_ID_62_MIN_LEN 26 |
---|
21 | |
---|
22 | #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183 |
---|
23 | #define MAVLINK_MSG_ID_62_CRC 183 |
---|
24 | |
---|
25 | |
---|
26 | |
---|
27 | #if MAVLINK_COMMAND_24BIT |
---|
28 | #define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ |
---|
29 | 62, \ |
---|
30 | "NAV_CONTROLLER_OUTPUT", \ |
---|
31 | 8, \ |
---|
32 | { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ |
---|
33 | { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ |
---|
34 | { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ |
---|
35 | { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ |
---|
36 | { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ |
---|
37 | { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ |
---|
38 | { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ |
---|
39 | { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ |
---|
40 | } \ |
---|
41 | } |
---|
42 | #else |
---|
43 | #define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ |
---|
44 | "NAV_CONTROLLER_OUTPUT", \ |
---|
45 | 8, \ |
---|
46 | { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ |
---|
47 | { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ |
---|
48 | { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ |
---|
49 | { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ |
---|
50 | { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ |
---|
51 | { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ |
---|
52 | { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ |
---|
53 | { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ |
---|
54 | } \ |
---|
55 | } |
---|
56 | #endif |
---|
57 | |
---|
58 | /** |
---|
59 | * @brief Pack a nav_controller_output message |
---|
60 | * @param system_id ID of this system |
---|
61 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
62 | * @param msg The MAVLink message to compress the data into |
---|
63 | * |
---|
64 | * @param nav_roll Current desired roll in degrees |
---|
65 | * @param nav_pitch Current desired pitch in degrees |
---|
66 | * @param nav_bearing Current desired heading in degrees |
---|
67 | * @param target_bearing Bearing to current MISSION/target in degrees |
---|
68 | * @param wp_dist Distance to active MISSION in meters |
---|
69 | * @param alt_error Current altitude error in meters |
---|
70 | * @param aspd_error Current airspeed error in meters/second |
---|
71 | * @param xtrack_error Current crosstrack error on x-y plane in meters |
---|
72 | * @return length of the message in bytes (excluding serial stream start sign) |
---|
73 | */ |
---|
74 | static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
---|
75 | float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) |
---|
76 | { |
---|
77 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
78 | char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; |
---|
79 | _mav_put_float(buf, 0, nav_roll); |
---|
80 | _mav_put_float(buf, 4, nav_pitch); |
---|
81 | _mav_put_float(buf, 8, alt_error); |
---|
82 | _mav_put_float(buf, 12, aspd_error); |
---|
83 | _mav_put_float(buf, 16, xtrack_error); |
---|
84 | _mav_put_int16_t(buf, 20, nav_bearing); |
---|
85 | _mav_put_int16_t(buf, 22, target_bearing); |
---|
86 | _mav_put_uint16_t(buf, 24, wp_dist); |
---|
87 | |
---|
88 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); |
---|
89 | #else |
---|
90 | mavlink_nav_controller_output_t packet; |
---|
91 | packet.nav_roll = nav_roll; |
---|
92 | packet.nav_pitch = nav_pitch; |
---|
93 | packet.alt_error = alt_error; |
---|
94 | packet.aspd_error = aspd_error; |
---|
95 | packet.xtrack_error = xtrack_error; |
---|
96 | packet.nav_bearing = nav_bearing; |
---|
97 | packet.target_bearing = target_bearing; |
---|
98 | packet.wp_dist = wp_dist; |
---|
99 | |
---|
100 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); |
---|
101 | #endif |
---|
102 | |
---|
103 | msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; |
---|
104 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); |
---|
105 | } |
---|
106 | |
---|
107 | /** |
---|
108 | * @brief Pack a nav_controller_output message on a channel |
---|
109 | * @param system_id ID of this system |
---|
110 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
111 | * @param chan The MAVLink channel this message will be sent over |
---|
112 | * @param msg The MAVLink message to compress the data into |
---|
113 | * @param nav_roll Current desired roll in degrees |
---|
114 | * @param nav_pitch Current desired pitch in degrees |
---|
115 | * @param nav_bearing Current desired heading in degrees |
---|
116 | * @param target_bearing Bearing to current MISSION/target in degrees |
---|
117 | * @param wp_dist Distance to active MISSION in meters |
---|
118 | * @param alt_error Current altitude error in meters |
---|
119 | * @param aspd_error Current airspeed error in meters/second |
---|
120 | * @param xtrack_error Current crosstrack error on x-y plane in meters |
---|
121 | * @return length of the message in bytes (excluding serial stream start sign) |
---|
122 | */ |
---|
123 | static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
---|
124 | mavlink_message_t* msg, |
---|
125 | float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error) |
---|
126 | { |
---|
127 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
128 | char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; |
---|
129 | _mav_put_float(buf, 0, nav_roll); |
---|
130 | _mav_put_float(buf, 4, nav_pitch); |
---|
131 | _mav_put_float(buf, 8, alt_error); |
---|
132 | _mav_put_float(buf, 12, aspd_error); |
---|
133 | _mav_put_float(buf, 16, xtrack_error); |
---|
134 | _mav_put_int16_t(buf, 20, nav_bearing); |
---|
135 | _mav_put_int16_t(buf, 22, target_bearing); |
---|
136 | _mav_put_uint16_t(buf, 24, wp_dist); |
---|
137 | |
---|
138 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); |
---|
139 | #else |
---|
140 | mavlink_nav_controller_output_t packet; |
---|
141 | packet.nav_roll = nav_roll; |
---|
142 | packet.nav_pitch = nav_pitch; |
---|
143 | packet.alt_error = alt_error; |
---|
144 | packet.aspd_error = aspd_error; |
---|
145 | packet.xtrack_error = xtrack_error; |
---|
146 | packet.nav_bearing = nav_bearing; |
---|
147 | packet.target_bearing = target_bearing; |
---|
148 | packet.wp_dist = wp_dist; |
---|
149 | |
---|
150 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); |
---|
151 | #endif |
---|
152 | |
---|
153 | msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; |
---|
154 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); |
---|
155 | } |
---|
156 | |
---|
157 | /** |
---|
158 | * @brief Encode a nav_controller_output struct |
---|
159 | * |
---|
160 | * @param system_id ID of this system |
---|
161 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
162 | * @param msg The MAVLink message to compress the data into |
---|
163 | * @param nav_controller_output C-struct to read the message contents from |
---|
164 | */ |
---|
165 | static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) |
---|
166 | { |
---|
167 | return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); |
---|
168 | } |
---|
169 | |
---|
170 | /** |
---|
171 | * @brief Encode a nav_controller_output struct on a channel |
---|
172 | * |
---|
173 | * @param system_id ID of this system |
---|
174 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
175 | * @param chan The MAVLink channel this message will be sent over |
---|
176 | * @param msg The MAVLink message to compress the data into |
---|
177 | * @param nav_controller_output C-struct to read the message contents from |
---|
178 | */ |
---|
179 | static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) |
---|
180 | { |
---|
181 | return mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, chan, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); |
---|
182 | } |
---|
183 | |
---|
184 | /** |
---|
185 | * @brief Send a nav_controller_output message |
---|
186 | * @param chan MAVLink channel to send the message |
---|
187 | * |
---|
188 | * @param nav_roll Current desired roll in degrees |
---|
189 | * @param nav_pitch Current desired pitch in degrees |
---|
190 | * @param nav_bearing Current desired heading in degrees |
---|
191 | * @param target_bearing Bearing to current MISSION/target in degrees |
---|
192 | * @param wp_dist Distance to active MISSION in meters |
---|
193 | * @param alt_error Current altitude error in meters |
---|
194 | * @param aspd_error Current airspeed error in meters/second |
---|
195 | * @param xtrack_error Current crosstrack error on x-y plane in meters |
---|
196 | */ |
---|
197 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
---|
198 | |
---|
199 | static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) |
---|
200 | { |
---|
201 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
202 | char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; |
---|
203 | _mav_put_float(buf, 0, nav_roll); |
---|
204 | _mav_put_float(buf, 4, nav_pitch); |
---|
205 | _mav_put_float(buf, 8, alt_error); |
---|
206 | _mav_put_float(buf, 12, aspd_error); |
---|
207 | _mav_put_float(buf, 16, xtrack_error); |
---|
208 | _mav_put_int16_t(buf, 20, nav_bearing); |
---|
209 | _mav_put_int16_t(buf, 22, target_bearing); |
---|
210 | _mav_put_uint16_t(buf, 24, wp_dist); |
---|
211 | |
---|
212 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); |
---|
213 | #else |
---|
214 | mavlink_nav_controller_output_t packet; |
---|
215 | packet.nav_roll = nav_roll; |
---|
216 | packet.nav_pitch = nav_pitch; |
---|
217 | packet.alt_error = alt_error; |
---|
218 | packet.aspd_error = aspd_error; |
---|
219 | packet.xtrack_error = xtrack_error; |
---|
220 | packet.nav_bearing = nav_bearing; |
---|
221 | packet.target_bearing = target_bearing; |
---|
222 | packet.wp_dist = wp_dist; |
---|
223 | |
---|
224 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); |
---|
225 | #endif |
---|
226 | } |
---|
227 | |
---|
228 | /** |
---|
229 | * @brief Send a nav_controller_output message |
---|
230 | * @param chan MAVLink channel to send the message |
---|
231 | * @param struct The MAVLink struct to serialize |
---|
232 | */ |
---|
233 | static inline void mavlink_msg_nav_controller_output_send_struct(mavlink_channel_t chan, const mavlink_nav_controller_output_t* nav_controller_output) |
---|
234 | { |
---|
235 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
236 | mavlink_msg_nav_controller_output_send(chan, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); |
---|
237 | #else |
---|
238 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)nav_controller_output, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); |
---|
239 | #endif |
---|
240 | } |
---|
241 | |
---|
242 | #if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN |
---|
243 | /* |
---|
244 | This varient of _send() can be used to save stack space by re-using |
---|
245 | memory from the receive buffer. The caller provides a |
---|
246 | mavlink_message_t which is the size of a full mavlink message. This |
---|
247 | is usually the receive buffer for the channel, and allows a reply to an |
---|
248 | incoming message with minimum stack space usage. |
---|
249 | */ |
---|
250 | static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) |
---|
251 | { |
---|
252 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
253 | char *buf = (char *)msgbuf; |
---|
254 | _mav_put_float(buf, 0, nav_roll); |
---|
255 | _mav_put_float(buf, 4, nav_pitch); |
---|
256 | _mav_put_float(buf, 8, alt_error); |
---|
257 | _mav_put_float(buf, 12, aspd_error); |
---|
258 | _mav_put_float(buf, 16, xtrack_error); |
---|
259 | _mav_put_int16_t(buf, 20, nav_bearing); |
---|
260 | _mav_put_int16_t(buf, 22, target_bearing); |
---|
261 | _mav_put_uint16_t(buf, 24, wp_dist); |
---|
262 | |
---|
263 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); |
---|
264 | #else |
---|
265 | mavlink_nav_controller_output_t *packet = (mavlink_nav_controller_output_t *)msgbuf; |
---|
266 | packet->nav_roll = nav_roll; |
---|
267 | packet->nav_pitch = nav_pitch; |
---|
268 | packet->alt_error = alt_error; |
---|
269 | packet->aspd_error = aspd_error; |
---|
270 | packet->xtrack_error = xtrack_error; |
---|
271 | packet->nav_bearing = nav_bearing; |
---|
272 | packet->target_bearing = target_bearing; |
---|
273 | packet->wp_dist = wp_dist; |
---|
274 | |
---|
275 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); |
---|
276 | #endif |
---|
277 | } |
---|
278 | #endif |
---|
279 | |
---|
280 | #endif |
---|
281 | |
---|
282 | // MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING |
---|
283 | |
---|
284 | |
---|
285 | /** |
---|
286 | * @brief Get field nav_roll from nav_controller_output message |
---|
287 | * |
---|
288 | * @return Current desired roll in degrees |
---|
289 | */ |
---|
290 | static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) |
---|
291 | { |
---|
292 | return _MAV_RETURN_float(msg, 0); |
---|
293 | } |
---|
294 | |
---|
295 | /** |
---|
296 | * @brief Get field nav_pitch from nav_controller_output message |
---|
297 | * |
---|
298 | * @return Current desired pitch in degrees |
---|
299 | */ |
---|
300 | static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) |
---|
301 | { |
---|
302 | return _MAV_RETURN_float(msg, 4); |
---|
303 | } |
---|
304 | |
---|
305 | /** |
---|
306 | * @brief Get field nav_bearing from nav_controller_output message |
---|
307 | * |
---|
308 | * @return Current desired heading in degrees |
---|
309 | */ |
---|
310 | static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) |
---|
311 | { |
---|
312 | return _MAV_RETURN_int16_t(msg, 20); |
---|
313 | } |
---|
314 | |
---|
315 | /** |
---|
316 | * @brief Get field target_bearing from nav_controller_output message |
---|
317 | * |
---|
318 | * @return Bearing to current MISSION/target in degrees |
---|
319 | */ |
---|
320 | static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) |
---|
321 | { |
---|
322 | return _MAV_RETURN_int16_t(msg, 22); |
---|
323 | } |
---|
324 | |
---|
325 | /** |
---|
326 | * @brief Get field wp_dist from nav_controller_output message |
---|
327 | * |
---|
328 | * @return Distance to active MISSION in meters |
---|
329 | */ |
---|
330 | static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) |
---|
331 | { |
---|
332 | return _MAV_RETURN_uint16_t(msg, 24); |
---|
333 | } |
---|
334 | |
---|
335 | /** |
---|
336 | * @brief Get field alt_error from nav_controller_output message |
---|
337 | * |
---|
338 | * @return Current altitude error in meters |
---|
339 | */ |
---|
340 | static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) |
---|
341 | { |
---|
342 | return _MAV_RETURN_float(msg, 8); |
---|
343 | } |
---|
344 | |
---|
345 | /** |
---|
346 | * @brief Get field aspd_error from nav_controller_output message |
---|
347 | * |
---|
348 | * @return Current airspeed error in meters/second |
---|
349 | */ |
---|
350 | static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) |
---|
351 | { |
---|
352 | return _MAV_RETURN_float(msg, 12); |
---|
353 | } |
---|
354 | |
---|
355 | /** |
---|
356 | * @brief Get field xtrack_error from nav_controller_output message |
---|
357 | * |
---|
358 | * @return Current crosstrack error on x-y plane in meters |
---|
359 | */ |
---|
360 | static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) |
---|
361 | { |
---|
362 | return _MAV_RETURN_float(msg, 16); |
---|
363 | } |
---|
364 | |
---|
365 | /** |
---|
366 | * @brief Decode a nav_controller_output message into a struct |
---|
367 | * |
---|
368 | * @param msg The message to decode |
---|
369 | * @param nav_controller_output C-struct to decode the message contents into |
---|
370 | */ |
---|
371 | static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) |
---|
372 | { |
---|
373 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
374 | nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); |
---|
375 | nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); |
---|
376 | nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); |
---|
377 | nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); |
---|
378 | nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); |
---|
379 | nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); |
---|
380 | nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg); |
---|
381 | nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg); |
---|
382 | #else |
---|
383 | uint8_t len = msg->len < MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN? msg->len : MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN; |
---|
384 | memset(nav_controller_output, 0, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); |
---|
385 | memcpy(nav_controller_output, _MAV_PAYLOAD(msg), len); |
---|
386 | #endif |
---|
387 | } |
---|