mavlink_msg_set_position_target_global_int.h
Go to the documentation of this file.
1 // MESSAGE SET_POSITION_TARGET_GLOBAL_INT PACKING
2 
3 #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT 86
4 
6 {
7  uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/
8  int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/
9  int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/
10  float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/
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 target_system; /*< System ID*/
21  uint8_t target_component; /*< Component ID*/
22  uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/
24 
25 #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53
26 #define MAVLINK_MSG_ID_86_LEN 53
27 
28 #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5
29 #define MAVLINK_MSG_ID_86_CRC 5
30 
31 
32 
33 #define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \
34  "SET_POSITION_TARGET_GLOBAL_INT", \
35  16, \
36  { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \
37  { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \
38  { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \
39  { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \
40  { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \
41  { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \
42  { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \
43  { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \
44  { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \
45  { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \
46  { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \
47  { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \
48  { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \
49  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \
50  { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \
51  { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \
52  } \
53 }
54 
55 
80 static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
81  uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
82 {
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
85  _mav_put_uint32_t(buf, 0, time_boot_ms);
86  _mav_put_int32_t(buf, 4, lat_int);
87  _mav_put_int32_t(buf, 8, lon_int);
88  _mav_put_float(buf, 12, alt);
89  _mav_put_float(buf, 16, vx);
90  _mav_put_float(buf, 20, vy);
91  _mav_put_float(buf, 24, vz);
92  _mav_put_float(buf, 28, afx);
93  _mav_put_float(buf, 32, afy);
94  _mav_put_float(buf, 36, afz);
95  _mav_put_float(buf, 40, yaw);
96  _mav_put_float(buf, 44, yaw_rate);
97  _mav_put_uint16_t(buf, 48, type_mask);
98  _mav_put_uint8_t(buf, 50, target_system);
99  _mav_put_uint8_t(buf, 51, target_component);
100  _mav_put_uint8_t(buf, 52, coordinate_frame);
101 
103 #else
105  packet.time_boot_ms = time_boot_ms;
106  packet.lat_int = lat_int;
107  packet.lon_int = lon_int;
108  packet.alt = alt;
109  packet.vx = vx;
110  packet.vy = vy;
111  packet.vz = vz;
112  packet.afx = afx;
113  packet.afy = afy;
114  packet.afz = afz;
115  packet.yaw = yaw;
116  packet.yaw_rate = yaw_rate;
117  packet.type_mask = type_mask;
118  packet.target_system = target_system;
121 
123 #endif
124 
126 #if MAVLINK_CRC_EXTRA
128 #else
130 #endif
131 }
132 
157 static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
158  mavlink_message_t* msg,
159  uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
160 {
161 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
163  _mav_put_uint32_t(buf, 0, time_boot_ms);
164  _mav_put_int32_t(buf, 4, lat_int);
165  _mav_put_int32_t(buf, 8, lon_int);
166  _mav_put_float(buf, 12, alt);
167  _mav_put_float(buf, 16, vx);
168  _mav_put_float(buf, 20, vy);
169  _mav_put_float(buf, 24, vz);
170  _mav_put_float(buf, 28, afx);
171  _mav_put_float(buf, 32, afy);
172  _mav_put_float(buf, 36, afz);
173  _mav_put_float(buf, 40, yaw);
174  _mav_put_float(buf, 44, yaw_rate);
175  _mav_put_uint16_t(buf, 48, type_mask);
176  _mav_put_uint8_t(buf, 50, target_system);
177  _mav_put_uint8_t(buf, 51, target_component);
178  _mav_put_uint8_t(buf, 52, coordinate_frame);
179 
181 #else
183  packet.time_boot_ms = time_boot_ms;
184  packet.lat_int = lat_int;
185  packet.lon_int = lon_int;
186  packet.alt = alt;
187  packet.vx = vx;
188  packet.vy = vy;
189  packet.vz = vz;
190  packet.afx = afx;
191  packet.afy = afy;
192  packet.afz = afz;
193  packet.yaw = yaw;
194  packet.yaw_rate = yaw_rate;
195  packet.type_mask = type_mask;
196  packet.target_system = target_system;
199 
201 #endif
202 
204 #if MAVLINK_CRC_EXTRA
206 #else
207  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
208 #endif
209 }
210 
219 static inline uint16_t mavlink_msg_set_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int)
220 {
221  return mavlink_msg_set_position_target_global_int_pack(system_id, component_id, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate);
222 }
223 
233 static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int)
234 {
235  return mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, chan, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate);
236 }
237 
259 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
260 
261 static inline void mavlink_msg_set_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
262 {
263 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
266  _mav_put_int32_t(buf, 4, lat_int);
267  _mav_put_int32_t(buf, 8, lon_int);
268  _mav_put_float(buf, 12, alt);
269  _mav_put_float(buf, 16, vx);
270  _mav_put_float(buf, 20, vy);
271  _mav_put_float(buf, 24, vz);
272  _mav_put_float(buf, 28, afx);
273  _mav_put_float(buf, 32, afy);
274  _mav_put_float(buf, 36, afz);
275  _mav_put_float(buf, 40, yaw);
276  _mav_put_float(buf, 44, yaw_rate);
277  _mav_put_uint16_t(buf, 48, type_mask);
281 
282 #if MAVLINK_CRC_EXTRA
284 #else
286 #endif
287 #else
289  packet.time_boot_ms = time_boot_ms;
290  packet.lat_int = lat_int;
291  packet.lon_int = lon_int;
292  packet.alt = alt;
293  packet.vx = vx;
294  packet.vy = vy;
295  packet.vz = vz;
296  packet.afx = afx;
297  packet.afy = afy;
298  packet.afz = afz;
299  packet.yaw = yaw;
300  packet.yaw_rate = yaw_rate;
301  packet.type_mask = type_mask;
302  packet.target_system = target_system;
305 
306 #if MAVLINK_CRC_EXTRA
308 #else
309  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
310 #endif
311 #endif
312 }
313 
314 #if MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
315 /*
316  This varient of _send() can be used to save stack space by re-using
317  memory from the receive buffer. The caller provides a
318  mavlink_message_t which is the size of a full mavlink message. This
319  is usually the receive buffer for the channel, and allows a reply to an
320  incoming message with minimum stack space usage.
321  */
322 static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
323 {
324 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
325  char *buf = (char *)msgbuf;
327  _mav_put_int32_t(buf, 4, lat_int);
328  _mav_put_int32_t(buf, 8, lon_int);
329  _mav_put_float(buf, 12, alt);
330  _mav_put_float(buf, 16, vx);
331  _mav_put_float(buf, 20, vy);
332  _mav_put_float(buf, 24, vz);
333  _mav_put_float(buf, 28, afx);
334  _mav_put_float(buf, 32, afy);
335  _mav_put_float(buf, 36, afz);
336  _mav_put_float(buf, 40, yaw);
337  _mav_put_float(buf, 44, yaw_rate);
338  _mav_put_uint16_t(buf, 48, type_mask);
342 
343 #if MAVLINK_CRC_EXTRA
345 #else
347 #endif
348 #else
350  packet->time_boot_ms = time_boot_ms;
351  packet->lat_int = lat_int;
352  packet->lon_int = lon_int;
353  packet->alt = alt;
354  packet->vx = vx;
355  packet->vy = vy;
356  packet->vz = vz;
357  packet->afx = afx;
358  packet->afy = afy;
359  packet->afz = afz;
360  packet->yaw = yaw;
361  packet->yaw_rate = yaw_rate;
362  packet->type_mask = type_mask;
363  packet->target_system = target_system;
366 
367 #if MAVLINK_CRC_EXTRA
369 #else
370  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
371 #endif
372 #endif
373 }
374 #endif
375 
376 #endif
377 
378 // MESSAGE SET_POSITION_TARGET_GLOBAL_INT UNPACKING
379 
380 
386 static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg)
387 {
388  return _MAV_RETURN_uint32_t(msg, 0);
389 }
390 
396 static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg)
397 {
398  return _MAV_RETURN_uint8_t(msg, 50);
399 }
400 
406 static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg)
407 {
408  return _MAV_RETURN_uint8_t(msg, 51);
409 }
410 
416 static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg)
417 {
418  return _MAV_RETURN_uint8_t(msg, 52);
419 }
420 
426 static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg)
427 {
428  return _MAV_RETURN_uint16_t(msg, 48);
429 }
430 
436 static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(const mavlink_message_t* msg)
437 {
438  return _MAV_RETURN_int32_t(msg, 4);
439 }
440 
446 static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(const mavlink_message_t* msg)
447 {
448  return _MAV_RETURN_int32_t(msg, 8);
449 }
450 
456 static inline float mavlink_msg_set_position_target_global_int_get_alt(const mavlink_message_t* msg)
457 {
458  return _MAV_RETURN_float(msg, 12);
459 }
460 
466 static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavlink_message_t* msg)
467 {
468  return _MAV_RETURN_float(msg, 16);
469 }
470 
476 static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavlink_message_t* msg)
477 {
478  return _MAV_RETURN_float(msg, 20);
479 }
480 
486 static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavlink_message_t* msg)
487 {
488  return _MAV_RETURN_float(msg, 24);
489 }
490 
496 static inline float mavlink_msg_set_position_target_global_int_get_afx(const mavlink_message_t* msg)
497 {
498  return _MAV_RETURN_float(msg, 28);
499 }
500 
506 static inline float mavlink_msg_set_position_target_global_int_get_afy(const mavlink_message_t* msg)
507 {
508  return _MAV_RETURN_float(msg, 32);
509 }
510 
516 static inline float mavlink_msg_set_position_target_global_int_get_afz(const mavlink_message_t* msg)
517 {
518  return _MAV_RETURN_float(msg, 36);
519 }
520 
526 static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg)
527 {
528  return _MAV_RETURN_float(msg, 40);
529 }
530 
536 static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg)
537 {
538  return _MAV_RETURN_float(msg, 44);
539 }
540 
547 static inline void mavlink_msg_set_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_set_position_target_global_int_t* set_position_target_global_int)
548 {
549 #if MAVLINK_NEED_BYTE_SWAP
550  set_position_target_global_int->time_boot_ms = mavlink_msg_set_position_target_global_int_get_time_boot_ms(msg);
551  set_position_target_global_int->lat_int = mavlink_msg_set_position_target_global_int_get_lat_int(msg);
552  set_position_target_global_int->lon_int = mavlink_msg_set_position_target_global_int_get_lon_int(msg);
553  set_position_target_global_int->alt = mavlink_msg_set_position_target_global_int_get_alt(msg);
554  set_position_target_global_int->vx = mavlink_msg_set_position_target_global_int_get_vx(msg);
555  set_position_target_global_int->vy = mavlink_msg_set_position_target_global_int_get_vy(msg);
556  set_position_target_global_int->vz = mavlink_msg_set_position_target_global_int_get_vz(msg);
557  set_position_target_global_int->afx = mavlink_msg_set_position_target_global_int_get_afx(msg);
558  set_position_target_global_int->afy = mavlink_msg_set_position_target_global_int_get_afy(msg);
559  set_position_target_global_int->afz = mavlink_msg_set_position_target_global_int_get_afz(msg);
560  set_position_target_global_int->yaw = mavlink_msg_set_position_target_global_int_get_yaw(msg);
561  set_position_target_global_int->yaw_rate = mavlink_msg_set_position_target_global_int_get_yaw_rate(msg);
562  set_position_target_global_int->type_mask = mavlink_msg_set_position_target_global_int_get_type_mask(msg);
566 #else
567  memcpy(set_position_target_global_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
568 #endif
569 }
#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_int32_t(buf, wire_offset, b)
Definition: protocol.h:148
#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