mavlink_msg_position_target_local_ned.h
Go to the documentation of this file.
1 // MESSAGE POSITION_TARGET_LOCAL_NED PACKING
2 
3 #define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED 85
4 
6 {
7  uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/
8  float x; /*< X Position in NED frame in meters*/
9  float y; /*< Y Position in NED frame in meters*/
10  float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/
11  float vx; /*< X velocity in NED frame in meter / s*/
12  float vy; /*< Y velocity in NED frame in meter / s*/
13  float vz; /*< Z velocity in NED frame in meter / s*/
14  float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
15  float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
16  float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
17  float yaw; /*< yaw setpoint in rad*/
18  float yaw_rate; /*< yaw rate setpoint in rad/s*/
19  uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/
20  uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/
22 
23 #define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51
24 #define MAVLINK_MSG_ID_85_LEN 51
25 
26 #define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140
27 #define MAVLINK_MSG_ID_85_CRC 140
28 
29 
30 
31 #define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \
32  "POSITION_TARGET_LOCAL_NED", \
33  14, \
34  { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \
35  { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \
36  { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \
37  { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \
38  { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \
39  { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \
40  { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \
41  { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \
42  { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \
43  { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \
44  { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \
45  { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \
46  { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \
47  { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \
48  } \
49 }
50 
51 
74 static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
75  uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
76 {
77 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
79  _mav_put_uint32_t(buf, 0, time_boot_ms);
80  _mav_put_float(buf, 4, x);
81  _mav_put_float(buf, 8, y);
82  _mav_put_float(buf, 12, z);
83  _mav_put_float(buf, 16, vx);
84  _mav_put_float(buf, 20, vy);
85  _mav_put_float(buf, 24, vz);
86  _mav_put_float(buf, 28, afx);
87  _mav_put_float(buf, 32, afy);
88  _mav_put_float(buf, 36, afz);
89  _mav_put_float(buf, 40, yaw);
90  _mav_put_float(buf, 44, yaw_rate);
91  _mav_put_uint16_t(buf, 48, type_mask);
92  _mav_put_uint8_t(buf, 50, coordinate_frame);
93 
95 #else
97  packet.time_boot_ms = time_boot_ms;
98  packet.x = x;
99  packet.y = y;
100  packet.z = z;
101  packet.vx = vx;
102  packet.vy = vy;
103  packet.vz = vz;
104  packet.afx = afx;
105  packet.afy = afy;
106  packet.afz = afz;
107  packet.yaw = yaw;
108  packet.yaw_rate = yaw_rate;
109  packet.type_mask = type_mask;
111 
113 #endif
114 
116 #if MAVLINK_CRC_EXTRA
118 #else
119  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
120 #endif
121 }
122 
145 static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
146  mavlink_message_t* msg,
147  uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
148 {
149 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
151  _mav_put_uint32_t(buf, 0, time_boot_ms);
152  _mav_put_float(buf, 4, x);
153  _mav_put_float(buf, 8, y);
154  _mav_put_float(buf, 12, z);
155  _mav_put_float(buf, 16, vx);
156  _mav_put_float(buf, 20, vy);
157  _mav_put_float(buf, 24, vz);
158  _mav_put_float(buf, 28, afx);
159  _mav_put_float(buf, 32, afy);
160  _mav_put_float(buf, 36, afz);
161  _mav_put_float(buf, 40, yaw);
162  _mav_put_float(buf, 44, yaw_rate);
163  _mav_put_uint16_t(buf, 48, type_mask);
164  _mav_put_uint8_t(buf, 50, coordinate_frame);
165 
167 #else
169  packet.time_boot_ms = time_boot_ms;
170  packet.x = x;
171  packet.y = y;
172  packet.z = z;
173  packet.vx = vx;
174  packet.vy = vy;
175  packet.vz = vz;
176  packet.afx = afx;
177  packet.afy = afy;
178  packet.afz = afz;
179  packet.yaw = yaw;
180  packet.yaw_rate = yaw_rate;
181  packet.type_mask = type_mask;
183 
185 #endif
186 
188 #if MAVLINK_CRC_EXTRA
190 #else
191  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
192 #endif
193 }
194 
203 static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned)
204 {
205  return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate);
206 }
207 
217 static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned)
218 {
219  return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate);
220 }
221 
241 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
242 
243 static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
244 {
245 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
248  _mav_put_float(buf, 4, x);
249  _mav_put_float(buf, 8, y);
250  _mav_put_float(buf, 12, z);
251  _mav_put_float(buf, 16, vx);
252  _mav_put_float(buf, 20, vy);
253  _mav_put_float(buf, 24, vz);
254  _mav_put_float(buf, 28, afx);
255  _mav_put_float(buf, 32, afy);
256  _mav_put_float(buf, 36, afz);
257  _mav_put_float(buf, 40, yaw);
258  _mav_put_float(buf, 44, yaw_rate);
259  _mav_put_uint16_t(buf, 48, type_mask);
261 
262 #if MAVLINK_CRC_EXTRA
264 #else
266 #endif
267 #else
269  packet.time_boot_ms = time_boot_ms;
270  packet.x = x;
271  packet.y = y;
272  packet.z = z;
273  packet.vx = vx;
274  packet.vy = vy;
275  packet.vz = vz;
276  packet.afx = afx;
277  packet.afy = afy;
278  packet.afz = afz;
279  packet.yaw = yaw;
280  packet.yaw_rate = yaw_rate;
281  packet.type_mask = type_mask;
283 
284 #if MAVLINK_CRC_EXTRA
286 #else
287  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
288 #endif
289 #endif
290 }
291 
292 #if MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
293 /*
294  This varient of _send() can be used to save stack space by re-using
295  memory from the receive buffer. The caller provides a
296  mavlink_message_t which is the size of a full mavlink message. This
297  is usually the receive buffer for the channel, and allows a reply to an
298  incoming message with minimum stack space usage.
299  */
300 static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
301 {
302 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
303  char *buf = (char *)msgbuf;
305  _mav_put_float(buf, 4, x);
306  _mav_put_float(buf, 8, y);
307  _mav_put_float(buf, 12, z);
308  _mav_put_float(buf, 16, vx);
309  _mav_put_float(buf, 20, vy);
310  _mav_put_float(buf, 24, vz);
311  _mav_put_float(buf, 28, afx);
312  _mav_put_float(buf, 32, afy);
313  _mav_put_float(buf, 36, afz);
314  _mav_put_float(buf, 40, yaw);
315  _mav_put_float(buf, 44, yaw_rate);
316  _mav_put_uint16_t(buf, 48, type_mask);
318 
319 #if MAVLINK_CRC_EXTRA
321 #else
323 #endif
324 #else
326  packet->time_boot_ms = time_boot_ms;
327  packet->x = x;
328  packet->y = y;
329  packet->z = z;
330  packet->vx = vx;
331  packet->vy = vy;
332  packet->vz = vz;
333  packet->afx = afx;
334  packet->afy = afy;
335  packet->afz = afz;
336  packet->yaw = yaw;
337  packet->yaw_rate = yaw_rate;
338  packet->type_mask = type_mask;
340 
341 #if MAVLINK_CRC_EXTRA
343 #else
344  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
345 #endif
346 #endif
347 }
348 #endif
349 
350 #endif
351 
352 // MESSAGE POSITION_TARGET_LOCAL_NED UNPACKING
353 
354 
360 static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg)
361 {
362  return _MAV_RETURN_uint32_t(msg, 0);
363 }
364 
370 static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg)
371 {
372  return _MAV_RETURN_uint8_t(msg, 50);
373 }
374 
380 static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg)
381 {
382  return _MAV_RETURN_uint16_t(msg, 48);
383 }
384 
390 static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_message_t* msg)
391 {
392  return _MAV_RETURN_float(msg, 4);
393 }
394 
400 static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_message_t* msg)
401 {
402  return _MAV_RETURN_float(msg, 8);
403 }
404 
410 static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_message_t* msg)
411 {
412  return _MAV_RETURN_float(msg, 12);
413 }
414 
420 static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_message_t* msg)
421 {
422  return _MAV_RETURN_float(msg, 16);
423 }
424 
430 static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_message_t* msg)
431 {
432  return _MAV_RETURN_float(msg, 20);
433 }
434 
440 static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_message_t* msg)
441 {
442  return _MAV_RETURN_float(msg, 24);
443 }
444 
450 static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_message_t* msg)
451 {
452  return _MAV_RETURN_float(msg, 28);
453 }
454 
460 static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_message_t* msg)
461 {
462  return _MAV_RETURN_float(msg, 32);
463 }
464 
470 static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_message_t* msg)
471 {
472  return _MAV_RETURN_float(msg, 36);
473 }
474 
480 static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg)
481 {
482  return _MAV_RETURN_float(msg, 40);
483 }
484 
490 static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg)
491 {
492  return _MAV_RETURN_float(msg, 44);
493 }
494 
501 static inline void mavlink_msg_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_position_target_local_ned_t* position_target_local_ned)
502 {
503 #if MAVLINK_NEED_BYTE_SWAP
505  position_target_local_ned->x = mavlink_msg_position_target_local_ned_get_x(msg);
506  position_target_local_ned->y = mavlink_msg_position_target_local_ned_get_y(msg);
507  position_target_local_ned->z = mavlink_msg_position_target_local_ned_get_z(msg);
508  position_target_local_ned->vx = mavlink_msg_position_target_local_ned_get_vx(msg);
509  position_target_local_ned->vy = mavlink_msg_position_target_local_ned_get_vy(msg);
510  position_target_local_ned->vz = mavlink_msg_position_target_local_ned_get_vz(msg);
511  position_target_local_ned->afx = mavlink_msg_position_target_local_ned_get_afx(msg);
512  position_target_local_ned->afy = mavlink_msg_position_target_local_ned_get_afy(msg);
513  position_target_local_ned->afz = mavlink_msg_position_target_local_ned_get_afz(msg);
514  position_target_local_ned->yaw = mavlink_msg_position_target_local_ned_get_yaw(msg);
515  position_target_local_ned->yaw_rate = mavlink_msg_position_target_local_ned_get_yaw_rate(msg);
516  position_target_local_ned->type_mask = mavlink_msg_position_target_local_ned_get_type_mask(msg);
518 #else
519  memcpy(position_target_local_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
520 #endif
521 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:145
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:47