Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | // MESSAGE WAYPOINT PACKING |
2 | |||
3 | #define MAVLINK_MSG_ID_WAYPOINT 39 |
||
4 | |||
5 | typedef struct __mavlink_waypoint_t |
||
6 | { |
||
7 | uint8_t target_system; ///< System ID |
||
8 | uint8_t target_component; ///< Component ID |
||
9 | uint16_t seq; ///< Sequence |
||
10 | uint8_t frame; ///< The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h |
||
11 | uint8_t command; ///< The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs |
||
12 | uint8_t current; ///< false:0, true:1 |
||
13 | uint8_t autocontinue; ///< autocontinue to next wp |
||
14 | float param1; ///< PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters |
||
15 | float param2; ///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds |
||
16 | float param3; ///< PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. |
||
17 | float param4; ///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH |
||
18 | float x; ///< PARAM5 / local: x position, global: latitude |
||
19 | float y; ///< PARAM6 / y position: global: longitude |
||
20 | float z; ///< PARAM7 / z position: global: altitude |
||
21 | } mavlink_waypoint_t; |
||
22 | |||
23 | #define MAVLINK_MSG_ID_WAYPOINT_LEN 36 |
||
24 | #define MAVLINK_MSG_ID_39_LEN 36 |
||
25 | |||
26 | |||
27 | |||
28 | #define MAVLINK_MESSAGE_INFO_WAYPOINT { \ |
||
29 | "WAYPOINT", \ |
||
30 | 14, \ |
||
31 | { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_t, target_system) }, \ |
||
32 | { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_t, target_component) }, \ |
||
33 | { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_t, seq) }, \ |
||
34 | { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_waypoint_t, frame) }, \ |
||
35 | { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_waypoint_t, command) }, \ |
||
36 | { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_waypoint_t, current) }, \ |
||
37 | { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_waypoint_t, autocontinue) }, \ |
||
38 | { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_waypoint_t, param1) }, \ |
||
39 | { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_waypoint_t, param2) }, \ |
||
40 | { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_waypoint_t, param3) }, \ |
||
41 | { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_waypoint_t, param4) }, \ |
||
42 | { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_waypoint_t, x) }, \ |
||
43 | { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_waypoint_t, y) }, \ |
||
44 | { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_waypoint_t, z) }, \ |
||
45 | } \ |
||
46 | } |
||
47 | |||
48 | |||
49 | /** |
||
50 | * @brief Pack a waypoint message |
||
51 | * @param system_id ID of this system |
||
52 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
53 | * @param msg The MAVLink message to compress the data into |
||
54 | * |
||
55 | * @param target_system System ID |
||
56 | * @param target_component Component ID |
||
57 | * @param seq Sequence |
||
58 | * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h |
||
59 | * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs |
||
60 | * @param current false:0, true:1 |
||
61 | * @param autocontinue autocontinue to next wp |
||
62 | * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters |
||
63 | * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds |
||
64 | * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. |
||
65 | * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH |
||
66 | * @param x PARAM5 / local: x position, global: latitude |
||
67 | * @param y PARAM6 / y position: global: longitude |
||
68 | * @param z PARAM7 / z position: global: altitude |
||
69 | * @return length of the message in bytes (excluding serial stream start sign) |
||
70 | */ |
||
71 | static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
||
72 | uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) |
||
73 | { |
||
74 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
75 | char buf[36]; |
||
76 | _mav_put_uint8_t(buf, 0, target_system); |
||
77 | _mav_put_uint8_t(buf, 1, target_component); |
||
78 | _mav_put_uint16_t(buf, 2, seq); |
||
79 | _mav_put_uint8_t(buf, 4, frame); |
||
80 | _mav_put_uint8_t(buf, 5, command); |
||
81 | _mav_put_uint8_t(buf, 6, current); |
||
82 | _mav_put_uint8_t(buf, 7, autocontinue); |
||
83 | _mav_put_float(buf, 8, param1); |
||
84 | _mav_put_float(buf, 12, param2); |
||
85 | _mav_put_float(buf, 16, param3); |
||
86 | _mav_put_float(buf, 20, param4); |
||
87 | _mav_put_float(buf, 24, x); |
||
88 | _mav_put_float(buf, 28, y); |
||
89 | _mav_put_float(buf, 32, z); |
||
90 | |||
91 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); |
||
92 | #else |
||
93 | mavlink_waypoint_t packet; |
||
94 | packet.target_system = target_system; |
||
95 | packet.target_component = target_component; |
||
96 | packet.seq = seq; |
||
97 | packet.frame = frame; |
||
98 | packet.command = command; |
||
99 | packet.current = current; |
||
100 | packet.autocontinue = autocontinue; |
||
101 | packet.param1 = param1; |
||
102 | packet.param2 = param2; |
||
103 | packet.param3 = param3; |
||
104 | packet.param4 = param4; |
||
105 | packet.x = x; |
||
106 | packet.y = y; |
||
107 | packet.z = z; |
||
108 | |||
109 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); |
||
110 | #endif |
||
111 | |||
112 | msg->msgid = MAVLINK_MSG_ID_WAYPOINT; |
||
113 | return mavlink_finalize_message(msg, system_id, component_id, 36); |
||
114 | } |
||
115 | |||
116 | /** |
||
117 | * @brief Pack a waypoint message on a channel |
||
118 | * @param system_id ID of this system |
||
119 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
120 | * @param chan The MAVLink channel this message was sent over |
||
121 | * @param msg The MAVLink message to compress the data into |
||
122 | * @param target_system System ID |
||
123 | * @param target_component Component ID |
||
124 | * @param seq Sequence |
||
125 | * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h |
||
126 | * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs |
||
127 | * @param current false:0, true:1 |
||
128 | * @param autocontinue autocontinue to next wp |
||
129 | * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters |
||
130 | * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds |
||
131 | * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. |
||
132 | * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH |
||
133 | * @param x PARAM5 / local: x position, global: latitude |
||
134 | * @param y PARAM6 / y position: global: longitude |
||
135 | * @param z PARAM7 / z position: global: altitude |
||
136 | * @return length of the message in bytes (excluding serial stream start sign) |
||
137 | */ |
||
138 | static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
||
139 | mavlink_message_t* msg, |
||
140 | uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint8_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z) |
||
141 | { |
||
142 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
143 | char buf[36]; |
||
144 | _mav_put_uint8_t(buf, 0, target_system); |
||
145 | _mav_put_uint8_t(buf, 1, target_component); |
||
146 | _mav_put_uint16_t(buf, 2, seq); |
||
147 | _mav_put_uint8_t(buf, 4, frame); |
||
148 | _mav_put_uint8_t(buf, 5, command); |
||
149 | _mav_put_uint8_t(buf, 6, current); |
||
150 | _mav_put_uint8_t(buf, 7, autocontinue); |
||
151 | _mav_put_float(buf, 8, param1); |
||
152 | _mav_put_float(buf, 12, param2); |
||
153 | _mav_put_float(buf, 16, param3); |
||
154 | _mav_put_float(buf, 20, param4); |
||
155 | _mav_put_float(buf, 24, x); |
||
156 | _mav_put_float(buf, 28, y); |
||
157 | _mav_put_float(buf, 32, z); |
||
158 | |||
159 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); |
||
160 | #else |
||
161 | mavlink_waypoint_t packet; |
||
162 | packet.target_system = target_system; |
||
163 | packet.target_component = target_component; |
||
164 | packet.seq = seq; |
||
165 | packet.frame = frame; |
||
166 | packet.command = command; |
||
167 | packet.current = current; |
||
168 | packet.autocontinue = autocontinue; |
||
169 | packet.param1 = param1; |
||
170 | packet.param2 = param2; |
||
171 | packet.param3 = param3; |
||
172 | packet.param4 = param4; |
||
173 | packet.x = x; |
||
174 | packet.y = y; |
||
175 | packet.z = z; |
||
176 | |||
177 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); |
||
178 | #endif |
||
179 | |||
180 | msg->msgid = MAVLINK_MSG_ID_WAYPOINT; |
||
181 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36); |
||
182 | } |
||
183 | |||
184 | /** |
||
185 | * @brief Encode a waypoint struct into a message |
||
186 | * |
||
187 | * @param system_id ID of this system |
||
188 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
189 | * @param msg The MAVLink message to compress the data into |
||
190 | * @param waypoint C-struct to read the message contents from |
||
191 | */ |
||
192 | static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_t* waypoint) |
||
193 | { |
||
194 | return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->command, waypoint->current, waypoint->autocontinue, waypoint->param1, waypoint->param2, waypoint->param3, waypoint->param4, waypoint->x, waypoint->y, waypoint->z); |
||
195 | } |
||
196 | |||
197 | /** |
||
198 | * @brief Send a waypoint message |
||
199 | * @param chan MAVLink channel to send the message |
||
200 | * |
||
201 | * @param target_system System ID |
||
202 | * @param target_component Component ID |
||
203 | * @param seq Sequence |
||
204 | * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h |
||
205 | * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs |
||
206 | * @param current false:0, true:1 |
||
207 | * @param autocontinue autocontinue to next wp |
||
208 | * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters |
||
209 | * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds |
||
210 | * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. |
||
211 | * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH |
||
212 | * @param x PARAM5 / local: x position, global: latitude |
||
213 | * @param y PARAM6 / y position: global: longitude |
||
214 | * @param z PARAM7 / z position: global: altitude |
||
215 | */ |
||
216 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||
217 | |||
218 | static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) |
||
219 | { |
||
220 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
221 | char buf[36]; |
||
222 | _mav_put_uint8_t(buf, 0, target_system); |
||
223 | _mav_put_uint8_t(buf, 1, target_component); |
||
224 | _mav_put_uint16_t(buf, 2, seq); |
||
225 | _mav_put_uint8_t(buf, 4, frame); |
||
226 | _mav_put_uint8_t(buf, 5, command); |
||
227 | _mav_put_uint8_t(buf, 6, current); |
||
228 | _mav_put_uint8_t(buf, 7, autocontinue); |
||
229 | _mav_put_float(buf, 8, param1); |
||
230 | _mav_put_float(buf, 12, param2); |
||
231 | _mav_put_float(buf, 16, param3); |
||
232 | _mav_put_float(buf, 20, param4); |
||
233 | _mav_put_float(buf, 24, x); |
||
234 | _mav_put_float(buf, 28, y); |
||
235 | _mav_put_float(buf, 32, z); |
||
236 | |||
237 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT, buf, 36); |
||
238 | #else |
||
239 | mavlink_waypoint_t packet; |
||
240 | packet.target_system = target_system; |
||
241 | packet.target_component = target_component; |
||
242 | packet.seq = seq; |
||
243 | packet.frame = frame; |
||
244 | packet.command = command; |
||
245 | packet.current = current; |
||
246 | packet.autocontinue = autocontinue; |
||
247 | packet.param1 = param1; |
||
248 | packet.param2 = param2; |
||
249 | packet.param3 = param3; |
||
250 | packet.param4 = param4; |
||
251 | packet.x = x; |
||
252 | packet.y = y; |
||
253 | packet.z = z; |
||
254 | |||
255 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT, (const char *)&packet, 36); |
||
256 | #endif |
||
257 | } |
||
258 | |||
259 | #endif |
||
260 | |||
261 | // MESSAGE WAYPOINT UNPACKING |
||
262 | |||
263 | |||
264 | /** |
||
265 | * @brief Get field target_system from waypoint message |
||
266 | * |
||
267 | * @return System ID |
||
268 | */ |
||
269 | static inline uint8_t mavlink_msg_waypoint_get_target_system(const mavlink_message_t* msg) |
||
270 | { |
||
271 | return _MAV_RETURN_uint8_t(msg, 0); |
||
272 | } |
||
273 | |||
274 | /** |
||
275 | * @brief Get field target_component from waypoint message |
||
276 | * |
||
277 | * @return Component ID |
||
278 | */ |
||
279 | static inline uint8_t mavlink_msg_waypoint_get_target_component(const mavlink_message_t* msg) |
||
280 | { |
||
281 | return _MAV_RETURN_uint8_t(msg, 1); |
||
282 | } |
||
283 | |||
284 | /** |
||
285 | * @brief Get field seq from waypoint message |
||
286 | * |
||
287 | * @return Sequence |
||
288 | */ |
||
289 | static inline uint16_t mavlink_msg_waypoint_get_seq(const mavlink_message_t* msg) |
||
290 | { |
||
291 | return _MAV_RETURN_uint16_t(msg, 2); |
||
292 | } |
||
293 | |||
294 | /** |
||
295 | * @brief Get field frame from waypoint message |
||
296 | * |
||
297 | * @return The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h |
||
298 | */ |
||
299 | static inline uint8_t mavlink_msg_waypoint_get_frame(const mavlink_message_t* msg) |
||
300 | { |
||
301 | return _MAV_RETURN_uint8_t(msg, 4); |
||
302 | } |
||
303 | |||
304 | /** |
||
305 | * @brief Get field command from waypoint message |
||
306 | * |
||
307 | * @return The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs |
||
308 | */ |
||
309 | static inline uint8_t mavlink_msg_waypoint_get_command(const mavlink_message_t* msg) |
||
310 | { |
||
311 | return _MAV_RETURN_uint8_t(msg, 5); |
||
312 | } |
||
313 | |||
314 | /** |
||
315 | * @brief Get field current from waypoint message |
||
316 | * |
||
317 | * @return false:0, true:1 |
||
318 | */ |
||
319 | static inline uint8_t mavlink_msg_waypoint_get_current(const mavlink_message_t* msg) |
||
320 | { |
||
321 | return _MAV_RETURN_uint8_t(msg, 6); |
||
322 | } |
||
323 | |||
324 | /** |
||
325 | * @brief Get field autocontinue from waypoint message |
||
326 | * |
||
327 | * @return autocontinue to next wp |
||
328 | */ |
||
329 | static inline uint8_t mavlink_msg_waypoint_get_autocontinue(const mavlink_message_t* msg) |
||
330 | { |
||
331 | return _MAV_RETURN_uint8_t(msg, 7); |
||
332 | } |
||
333 | |||
334 | /** |
||
335 | * @brief Get field param1 from waypoint message |
||
336 | * |
||
337 | * @return PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters |
||
338 | */ |
||
339 | static inline float mavlink_msg_waypoint_get_param1(const mavlink_message_t* msg) |
||
340 | { |
||
341 | return _MAV_RETURN_float(msg, 8); |
||
342 | } |
||
343 | |||
344 | /** |
||
345 | * @brief Get field param2 from waypoint message |
||
346 | * |
||
347 | * @return PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds |
||
348 | */ |
||
349 | static inline float mavlink_msg_waypoint_get_param2(const mavlink_message_t* msg) |
||
350 | { |
||
351 | return _MAV_RETURN_float(msg, 12); |
||
352 | } |
||
353 | |||
354 | /** |
||
355 | * @brief Get field param3 from waypoint message |
||
356 | * |
||
357 | * @return PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. |
||
358 | */ |
||
359 | static inline float mavlink_msg_waypoint_get_param3(const mavlink_message_t* msg) |
||
360 | { |
||
361 | return _MAV_RETURN_float(msg, 16); |
||
362 | } |
||
363 | |||
364 | /** |
||
365 | * @brief Get field param4 from waypoint message |
||
366 | * |
||
367 | * @return PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH |
||
368 | */ |
||
369 | static inline float mavlink_msg_waypoint_get_param4(const mavlink_message_t* msg) |
||
370 | { |
||
371 | return _MAV_RETURN_float(msg, 20); |
||
372 | } |
||
373 | |||
374 | /** |
||
375 | * @brief Get field x from waypoint message |
||
376 | * |
||
377 | * @return PARAM5 / local: x position, global: latitude |
||
378 | */ |
||
379 | static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg) |
||
380 | { |
||
381 | return _MAV_RETURN_float(msg, 24); |
||
382 | } |
||
383 | |||
384 | /** |
||
385 | * @brief Get field y from waypoint message |
||
386 | * |
||
387 | * @return PARAM6 / y position: global: longitude |
||
388 | */ |
||
389 | static inline float mavlink_msg_waypoint_get_y(const mavlink_message_t* msg) |
||
390 | { |
||
391 | return _MAV_RETURN_float(msg, 28); |
||
392 | } |
||
393 | |||
394 | /** |
||
395 | * @brief Get field z from waypoint message |
||
396 | * |
||
397 | * @return PARAM7 / z position: global: altitude |
||
398 | */ |
||
399 | static inline float mavlink_msg_waypoint_get_z(const mavlink_message_t* msg) |
||
400 | { |
||
401 | return _MAV_RETURN_float(msg, 32); |
||
402 | } |
||
403 | |||
404 | /** |
||
405 | * @brief Decode a waypoint message into a struct |
||
406 | * |
||
407 | * @param msg The message to decode |
||
408 | * @param waypoint C-struct to decode the message contents into |
||
409 | */ |
||
410 | static inline void mavlink_msg_waypoint_decode(const mavlink_message_t* msg, mavlink_waypoint_t* waypoint) |
||
411 | { |
||
412 | #if MAVLINK_NEED_BYTE_SWAP |
||
413 | waypoint->target_system = mavlink_msg_waypoint_get_target_system(msg); |
||
414 | waypoint->target_component = mavlink_msg_waypoint_get_target_component(msg); |
||
415 | waypoint->seq = mavlink_msg_waypoint_get_seq(msg); |
||
416 | waypoint->frame = mavlink_msg_waypoint_get_frame(msg); |
||
417 | waypoint->command = mavlink_msg_waypoint_get_command(msg); |
||
418 | waypoint->current = mavlink_msg_waypoint_get_current(msg); |
||
419 | waypoint->autocontinue = mavlink_msg_waypoint_get_autocontinue(msg); |
||
420 | waypoint->param1 = mavlink_msg_waypoint_get_param1(msg); |
||
421 | waypoint->param2 = mavlink_msg_waypoint_get_param2(msg); |
||
422 | waypoint->param3 = mavlink_msg_waypoint_get_param3(msg); |
||
423 | waypoint->param4 = mavlink_msg_waypoint_get_param4(msg); |
||
424 | waypoint->x = mavlink_msg_waypoint_get_x(msg); |
||
425 | waypoint->y = mavlink_msg_waypoint_get_y(msg); |
||
426 | waypoint->z = mavlink_msg_waypoint_get_z(msg); |
||
427 | #else |
||
428 | memcpy(waypoint, _MAV_PAYLOAD(msg), 36); |
||
429 | #endif |
||
430 | } |