mavlink_msg_set_position_target_global_int.h 36 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680
  1. #pragma once
  2. // MESSAGE SET_POSITION_TARGET_GLOBAL_INT PACKING
  3. #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT 86
  4. typedef struct __mavlink_set_position_target_global_int_t {
  5. uint32_t time_boot_ms; /*< [ms] Timestamp (time 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.*/
  6. int32_t lat_int; /*< [degE7] X Position in WGS84 frame*/
  7. int32_t lon_int; /*< [degE7] Y Position in WGS84 frame*/
  8. float alt; /*< [m] Altitude (MSL, Relative to home, or AGL - depending on frame)*/
  9. float vx; /*< [m/s] X velocity in NED frame*/
  10. float vy; /*< [m/s] Y velocity in NED frame*/
  11. float vz; /*< [m/s] Z velocity in NED frame*/
  12. float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
  13. float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
  14. float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
  15. float yaw; /*< [rad] yaw setpoint*/
  16. float yaw_rate; /*< [rad/s] yaw rate setpoint*/
  17. uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/
  18. uint8_t target_system; /*< System ID*/
  19. uint8_t target_component; /*< Component ID*/
  20. 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*/
  21. } mavlink_set_position_target_global_int_t;
  22. #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53
  23. #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN 53
  24. #define MAVLINK_MSG_ID_86_LEN 53
  25. #define MAVLINK_MSG_ID_86_MIN_LEN 53
  26. #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5
  27. #define MAVLINK_MSG_ID_86_CRC 5
  28. #if MAVLINK_COMMAND_24BIT
  29. #define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \
  30. 86, \
  31. "SET_POSITION_TARGET_GLOBAL_INT", \
  32. 16, \
  33. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \
  34. { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \
  35. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \
  36. { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \
  37. { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \
  38. { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \
  39. { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \
  40. { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \
  41. { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \
  42. { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \
  43. { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \
  44. { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \
  45. { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \
  46. { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \
  47. { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \
  48. { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \
  49. } \
  50. }
  51. #else
  52. #define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \
  53. "SET_POSITION_TARGET_GLOBAL_INT", \
  54. 16, \
  55. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \
  56. { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \
  57. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \
  58. { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \
  59. { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \
  60. { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \
  61. { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \
  62. { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \
  63. { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \
  64. { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \
  65. { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \
  66. { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \
  67. { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \
  68. { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \
  69. { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \
  70. { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \
  71. } \
  72. }
  73. #endif
  74. /**
  75. * @brief Pack a set_position_target_global_int message
  76. * @param system_id ID of this system
  77. * @param component_id ID of this component (e.g. 200 for IMU)
  78. * @param msg The MAVLink message to compress the data into
  79. *
  80. * @param time_boot_ms [ms] Timestamp (time 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.
  81. * @param target_system System ID
  82. * @param target_component Component ID
  83. * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
  84. * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
  85. * @param lat_int [degE7] X Position in WGS84 frame
  86. * @param lon_int [degE7] Y Position in WGS84 frame
  87. * @param alt [m] Altitude (MSL, Relative to home, or AGL - depending on frame)
  88. * @param vx [m/s] X velocity in NED frame
  89. * @param vy [m/s] Y velocity in NED frame
  90. * @param vz [m/s] Z velocity in NED frame
  91. * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  92. * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  93. * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  94. * @param yaw [rad] yaw setpoint
  95. * @param yaw_rate [rad/s] yaw rate setpoint
  96. * @return length of the message in bytes (excluding serial stream start sign)
  97. */
  98. static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  99. 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)
  100. {
  101. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  102. char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
  103. _mav_put_uint32_t(buf, 0, time_boot_ms);
  104. _mav_put_int32_t(buf, 4, lat_int);
  105. _mav_put_int32_t(buf, 8, lon_int);
  106. _mav_put_float(buf, 12, alt);
  107. _mav_put_float(buf, 16, vx);
  108. _mav_put_float(buf, 20, vy);
  109. _mav_put_float(buf, 24, vz);
  110. _mav_put_float(buf, 28, afx);
  111. _mav_put_float(buf, 32, afy);
  112. _mav_put_float(buf, 36, afz);
  113. _mav_put_float(buf, 40, yaw);
  114. _mav_put_float(buf, 44, yaw_rate);
  115. _mav_put_uint16_t(buf, 48, type_mask);
  116. _mav_put_uint8_t(buf, 50, target_system);
  117. _mav_put_uint8_t(buf, 51, target_component);
  118. _mav_put_uint8_t(buf, 52, coordinate_frame);
  119. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
  120. #else
  121. mavlink_set_position_target_global_int_t packet;
  122. packet.time_boot_ms = time_boot_ms;
  123. packet.lat_int = lat_int;
  124. packet.lon_int = lon_int;
  125. packet.alt = alt;
  126. packet.vx = vx;
  127. packet.vy = vy;
  128. packet.vz = vz;
  129. packet.afx = afx;
  130. packet.afy = afy;
  131. packet.afz = afz;
  132. packet.yaw = yaw;
  133. packet.yaw_rate = yaw_rate;
  134. packet.type_mask = type_mask;
  135. packet.target_system = target_system;
  136. packet.target_component = target_component;
  137. packet.coordinate_frame = coordinate_frame;
  138. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
  139. #endif
  140. msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT;
  141. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
  142. }
  143. /**
  144. * @brief Pack a set_position_target_global_int message
  145. * @param system_id ID of this system
  146. * @param component_id ID of this component (e.g. 200 for IMU)
  147. * @param status MAVLink status structure
  148. * @param msg The MAVLink message to compress the data into
  149. *
  150. * @param time_boot_ms [ms] Timestamp (time 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.
  151. * @param target_system System ID
  152. * @param target_component Component ID
  153. * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
  154. * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
  155. * @param lat_int [degE7] X Position in WGS84 frame
  156. * @param lon_int [degE7] Y Position in WGS84 frame
  157. * @param alt [m] Altitude (MSL, Relative to home, or AGL - depending on frame)
  158. * @param vx [m/s] X velocity in NED frame
  159. * @param vy [m/s] Y velocity in NED frame
  160. * @param vz [m/s] Z velocity in NED frame
  161. * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  162. * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  163. * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  164. * @param yaw [rad] yaw setpoint
  165. * @param yaw_rate [rad/s] yaw rate setpoint
  166. * @return length of the message in bytes (excluding serial stream start sign)
  167. */
  168. static inline uint16_t mavlink_msg_set_position_target_global_int_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  169. 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)
  170. {
  171. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  172. char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
  173. _mav_put_uint32_t(buf, 0, time_boot_ms);
  174. _mav_put_int32_t(buf, 4, lat_int);
  175. _mav_put_int32_t(buf, 8, lon_int);
  176. _mav_put_float(buf, 12, alt);
  177. _mav_put_float(buf, 16, vx);
  178. _mav_put_float(buf, 20, vy);
  179. _mav_put_float(buf, 24, vz);
  180. _mav_put_float(buf, 28, afx);
  181. _mav_put_float(buf, 32, afy);
  182. _mav_put_float(buf, 36, afz);
  183. _mav_put_float(buf, 40, yaw);
  184. _mav_put_float(buf, 44, yaw_rate);
  185. _mav_put_uint16_t(buf, 48, type_mask);
  186. _mav_put_uint8_t(buf, 50, target_system);
  187. _mav_put_uint8_t(buf, 51, target_component);
  188. _mav_put_uint8_t(buf, 52, coordinate_frame);
  189. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
  190. #else
  191. mavlink_set_position_target_global_int_t packet;
  192. packet.time_boot_ms = time_boot_ms;
  193. packet.lat_int = lat_int;
  194. packet.lon_int = lon_int;
  195. packet.alt = alt;
  196. packet.vx = vx;
  197. packet.vy = vy;
  198. packet.vz = vz;
  199. packet.afx = afx;
  200. packet.afy = afy;
  201. packet.afz = afz;
  202. packet.yaw = yaw;
  203. packet.yaw_rate = yaw_rate;
  204. packet.type_mask = type_mask;
  205. packet.target_system = target_system;
  206. packet.target_component = target_component;
  207. packet.coordinate_frame = coordinate_frame;
  208. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
  209. #endif
  210. msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT;
  211. #if MAVLINK_CRC_EXTRA
  212. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
  213. #else
  214. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
  215. #endif
  216. }
  217. /**
  218. * @brief Pack a set_position_target_global_int message on a channel
  219. * @param system_id ID of this system
  220. * @param component_id ID of this component (e.g. 200 for IMU)
  221. * @param chan The MAVLink channel this message will be sent over
  222. * @param msg The MAVLink message to compress the data into
  223. * @param time_boot_ms [ms] Timestamp (time 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.
  224. * @param target_system System ID
  225. * @param target_component Component ID
  226. * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
  227. * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
  228. * @param lat_int [degE7] X Position in WGS84 frame
  229. * @param lon_int [degE7] Y Position in WGS84 frame
  230. * @param alt [m] Altitude (MSL, Relative to home, or AGL - depending on frame)
  231. * @param vx [m/s] X velocity in NED frame
  232. * @param vy [m/s] Y velocity in NED frame
  233. * @param vz [m/s] Z velocity in NED frame
  234. * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  235. * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  236. * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  237. * @param yaw [rad] yaw setpoint
  238. * @param yaw_rate [rad/s] yaw rate setpoint
  239. * @return length of the message in bytes (excluding serial stream start sign)
  240. */
  241. static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  242. mavlink_message_t* msg,
  243. 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)
  244. {
  245. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  246. char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
  247. _mav_put_uint32_t(buf, 0, time_boot_ms);
  248. _mav_put_int32_t(buf, 4, lat_int);
  249. _mav_put_int32_t(buf, 8, lon_int);
  250. _mav_put_float(buf, 12, alt);
  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);
  260. _mav_put_uint8_t(buf, 50, target_system);
  261. _mav_put_uint8_t(buf, 51, target_component);
  262. _mav_put_uint8_t(buf, 52, coordinate_frame);
  263. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
  264. #else
  265. mavlink_set_position_target_global_int_t packet;
  266. packet.time_boot_ms = time_boot_ms;
  267. packet.lat_int = lat_int;
  268. packet.lon_int = lon_int;
  269. packet.alt = alt;
  270. packet.vx = vx;
  271. packet.vy = vy;
  272. packet.vz = vz;
  273. packet.afx = afx;
  274. packet.afy = afy;
  275. packet.afz = afz;
  276. packet.yaw = yaw;
  277. packet.yaw_rate = yaw_rate;
  278. packet.type_mask = type_mask;
  279. packet.target_system = target_system;
  280. packet.target_component = target_component;
  281. packet.coordinate_frame = coordinate_frame;
  282. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
  283. #endif
  284. msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT;
  285. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
  286. }
  287. /**
  288. * @brief Encode a set_position_target_global_int struct
  289. *
  290. * @param system_id ID of this system
  291. * @param component_id ID of this component (e.g. 200 for IMU)
  292. * @param msg The MAVLink message to compress the data into
  293. * @param set_position_target_global_int C-struct to read the message contents from
  294. */
  295. 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)
  296. {
  297. 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);
  298. }
  299. /**
  300. * @brief Encode a set_position_target_global_int struct on a channel
  301. *
  302. * @param system_id ID of this system
  303. * @param component_id ID of this component (e.g. 200 for IMU)
  304. * @param chan The MAVLink channel this message will be sent over
  305. * @param msg The MAVLink message to compress the data into
  306. * @param set_position_target_global_int C-struct to read the message contents from
  307. */
  308. 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)
  309. {
  310. 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);
  311. }
  312. /**
  313. * @brief Encode a set_position_target_global_int struct with provided status structure
  314. *
  315. * @param system_id ID of this system
  316. * @param component_id ID of this component (e.g. 200 for IMU)
  317. * @param status MAVLink status structure
  318. * @param msg The MAVLink message to compress the data into
  319. * @param set_position_target_global_int C-struct to read the message contents from
  320. */
  321. static inline uint16_t mavlink_msg_set_position_target_global_int_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int)
  322. {
  323. return mavlink_msg_set_position_target_global_int_pack_status(system_id, component_id, _status, 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);
  324. }
  325. /**
  326. * @brief Send a set_position_target_global_int message
  327. * @param chan MAVLink channel to send the message
  328. *
  329. * @param time_boot_ms [ms] Timestamp (time 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.
  330. * @param target_system System ID
  331. * @param target_component Component ID
  332. * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
  333. * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
  334. * @param lat_int [degE7] X Position in WGS84 frame
  335. * @param lon_int [degE7] Y Position in WGS84 frame
  336. * @param alt [m] Altitude (MSL, Relative to home, or AGL - depending on frame)
  337. * @param vx [m/s] X velocity in NED frame
  338. * @param vy [m/s] Y velocity in NED frame
  339. * @param vz [m/s] Z velocity in NED frame
  340. * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  341. * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  342. * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  343. * @param yaw [rad] yaw setpoint
  344. * @param yaw_rate [rad/s] yaw rate setpoint
  345. */
  346. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  347. 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)
  348. {
  349. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  350. char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
  351. _mav_put_uint32_t(buf, 0, time_boot_ms);
  352. _mav_put_int32_t(buf, 4, lat_int);
  353. _mav_put_int32_t(buf, 8, lon_int);
  354. _mav_put_float(buf, 12, alt);
  355. _mav_put_float(buf, 16, vx);
  356. _mav_put_float(buf, 20, vy);
  357. _mav_put_float(buf, 24, vz);
  358. _mav_put_float(buf, 28, afx);
  359. _mav_put_float(buf, 32, afy);
  360. _mav_put_float(buf, 36, afz);
  361. _mav_put_float(buf, 40, yaw);
  362. _mav_put_float(buf, 44, yaw_rate);
  363. _mav_put_uint16_t(buf, 48, type_mask);
  364. _mav_put_uint8_t(buf, 50, target_system);
  365. _mav_put_uint8_t(buf, 51, target_component);
  366. _mav_put_uint8_t(buf, 52, coordinate_frame);
  367. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
  368. #else
  369. mavlink_set_position_target_global_int_t packet;
  370. packet.time_boot_ms = time_boot_ms;
  371. packet.lat_int = lat_int;
  372. packet.lon_int = lon_int;
  373. packet.alt = alt;
  374. packet.vx = vx;
  375. packet.vy = vy;
  376. packet.vz = vz;
  377. packet.afx = afx;
  378. packet.afy = afy;
  379. packet.afz = afz;
  380. packet.yaw = yaw;
  381. packet.yaw_rate = yaw_rate;
  382. packet.type_mask = type_mask;
  383. packet.target_system = target_system;
  384. packet.target_component = target_component;
  385. packet.coordinate_frame = coordinate_frame;
  386. _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_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
  387. #endif
  388. }
  389. /**
  390. * @brief Send a set_position_target_global_int message
  391. * @param chan MAVLink channel to send the message
  392. * @param struct The MAVLink struct to serialize
  393. */
  394. static inline void mavlink_msg_set_position_target_global_int_send_struct(mavlink_channel_t chan, const mavlink_set_position_target_global_int_t* set_position_target_global_int)
  395. {
  396. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  397. mavlink_msg_set_position_target_global_int_send(chan, 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);
  398. #else
  399. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)set_position_target_global_int, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
  400. #endif
  401. }
  402. #if MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  403. /*
  404. This variant of _send() can be used to save stack space by reusing
  405. memory from the receive buffer. The caller provides a
  406. mavlink_message_t which is the size of a full mavlink message. This
  407. is usually the receive buffer for the channel, and allows a reply to an
  408. incoming message with minimum stack space usage.
  409. */
  410. 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)
  411. {
  412. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  413. char *buf = (char *)msgbuf;
  414. _mav_put_uint32_t(buf, 0, time_boot_ms);
  415. _mav_put_int32_t(buf, 4, lat_int);
  416. _mav_put_int32_t(buf, 8, lon_int);
  417. _mav_put_float(buf, 12, alt);
  418. _mav_put_float(buf, 16, vx);
  419. _mav_put_float(buf, 20, vy);
  420. _mav_put_float(buf, 24, vz);
  421. _mav_put_float(buf, 28, afx);
  422. _mav_put_float(buf, 32, afy);
  423. _mav_put_float(buf, 36, afz);
  424. _mav_put_float(buf, 40, yaw);
  425. _mav_put_float(buf, 44, yaw_rate);
  426. _mav_put_uint16_t(buf, 48, type_mask);
  427. _mav_put_uint8_t(buf, 50, target_system);
  428. _mav_put_uint8_t(buf, 51, target_component);
  429. _mav_put_uint8_t(buf, 52, coordinate_frame);
  430. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
  431. #else
  432. mavlink_set_position_target_global_int_t *packet = (mavlink_set_position_target_global_int_t *)msgbuf;
  433. packet->time_boot_ms = time_boot_ms;
  434. packet->lat_int = lat_int;
  435. packet->lon_int = lon_int;
  436. packet->alt = alt;
  437. packet->vx = vx;
  438. packet->vy = vy;
  439. packet->vz = vz;
  440. packet->afx = afx;
  441. packet->afy = afy;
  442. packet->afz = afz;
  443. packet->yaw = yaw;
  444. packet->yaw_rate = yaw_rate;
  445. packet->type_mask = type_mask;
  446. packet->target_system = target_system;
  447. packet->target_component = target_component;
  448. packet->coordinate_frame = coordinate_frame;
  449. _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_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
  450. #endif
  451. }
  452. #endif
  453. #endif
  454. // MESSAGE SET_POSITION_TARGET_GLOBAL_INT UNPACKING
  455. /**
  456. * @brief Get field time_boot_ms from set_position_target_global_int message
  457. *
  458. * @return [ms] Timestamp (time 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.
  459. */
  460. static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg)
  461. {
  462. return _MAV_RETURN_uint32_t(msg, 0);
  463. }
  464. /**
  465. * @brief Get field target_system from set_position_target_global_int message
  466. *
  467. * @return System ID
  468. */
  469. static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg)
  470. {
  471. return _MAV_RETURN_uint8_t(msg, 50);
  472. }
  473. /**
  474. * @brief Get field target_component from set_position_target_global_int message
  475. *
  476. * @return Component ID
  477. */
  478. static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg)
  479. {
  480. return _MAV_RETURN_uint8_t(msg, 51);
  481. }
  482. /**
  483. * @brief Get field coordinate_frame from set_position_target_global_int message
  484. *
  485. * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
  486. */
  487. static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg)
  488. {
  489. return _MAV_RETURN_uint8_t(msg, 52);
  490. }
  491. /**
  492. * @brief Get field type_mask from set_position_target_global_int message
  493. *
  494. * @return Bitmap to indicate which dimensions should be ignored by the vehicle.
  495. */
  496. static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg)
  497. {
  498. return _MAV_RETURN_uint16_t(msg, 48);
  499. }
  500. /**
  501. * @brief Get field lat_int from set_position_target_global_int message
  502. *
  503. * @return [degE7] X Position in WGS84 frame
  504. */
  505. static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(const mavlink_message_t* msg)
  506. {
  507. return _MAV_RETURN_int32_t(msg, 4);
  508. }
  509. /**
  510. * @brief Get field lon_int from set_position_target_global_int message
  511. *
  512. * @return [degE7] Y Position in WGS84 frame
  513. */
  514. static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(const mavlink_message_t* msg)
  515. {
  516. return _MAV_RETURN_int32_t(msg, 8);
  517. }
  518. /**
  519. * @brief Get field alt from set_position_target_global_int message
  520. *
  521. * @return [m] Altitude (MSL, Relative to home, or AGL - depending on frame)
  522. */
  523. static inline float mavlink_msg_set_position_target_global_int_get_alt(const mavlink_message_t* msg)
  524. {
  525. return _MAV_RETURN_float(msg, 12);
  526. }
  527. /**
  528. * @brief Get field vx from set_position_target_global_int message
  529. *
  530. * @return [m/s] X velocity in NED frame
  531. */
  532. static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavlink_message_t* msg)
  533. {
  534. return _MAV_RETURN_float(msg, 16);
  535. }
  536. /**
  537. * @brief Get field vy from set_position_target_global_int message
  538. *
  539. * @return [m/s] Y velocity in NED frame
  540. */
  541. static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavlink_message_t* msg)
  542. {
  543. return _MAV_RETURN_float(msg, 20);
  544. }
  545. /**
  546. * @brief Get field vz from set_position_target_global_int message
  547. *
  548. * @return [m/s] Z velocity in NED frame
  549. */
  550. static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavlink_message_t* msg)
  551. {
  552. return _MAV_RETURN_float(msg, 24);
  553. }
  554. /**
  555. * @brief Get field afx from set_position_target_global_int message
  556. *
  557. * @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  558. */
  559. static inline float mavlink_msg_set_position_target_global_int_get_afx(const mavlink_message_t* msg)
  560. {
  561. return _MAV_RETURN_float(msg, 28);
  562. }
  563. /**
  564. * @brief Get field afy from set_position_target_global_int message
  565. *
  566. * @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  567. */
  568. static inline float mavlink_msg_set_position_target_global_int_get_afy(const mavlink_message_t* msg)
  569. {
  570. return _MAV_RETURN_float(msg, 32);
  571. }
  572. /**
  573. * @brief Get field afz from set_position_target_global_int message
  574. *
  575. * @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  576. */
  577. static inline float mavlink_msg_set_position_target_global_int_get_afz(const mavlink_message_t* msg)
  578. {
  579. return _MAV_RETURN_float(msg, 36);
  580. }
  581. /**
  582. * @brief Get field yaw from set_position_target_global_int message
  583. *
  584. * @return [rad] yaw setpoint
  585. */
  586. static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg)
  587. {
  588. return _MAV_RETURN_float(msg, 40);
  589. }
  590. /**
  591. * @brief Get field yaw_rate from set_position_target_global_int message
  592. *
  593. * @return [rad/s] yaw rate setpoint
  594. */
  595. static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg)
  596. {
  597. return _MAV_RETURN_float(msg, 44);
  598. }
  599. /**
  600. * @brief Decode a set_position_target_global_int message into a struct
  601. *
  602. * @param msg The message to decode
  603. * @param set_position_target_global_int C-struct to decode the message contents into
  604. */
  605. 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)
  606. {
  607. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  608. set_position_target_global_int->time_boot_ms = mavlink_msg_set_position_target_global_int_get_time_boot_ms(msg);
  609. set_position_target_global_int->lat_int = mavlink_msg_set_position_target_global_int_get_lat_int(msg);
  610. set_position_target_global_int->lon_int = mavlink_msg_set_position_target_global_int_get_lon_int(msg);
  611. set_position_target_global_int->alt = mavlink_msg_set_position_target_global_int_get_alt(msg);
  612. set_position_target_global_int->vx = mavlink_msg_set_position_target_global_int_get_vx(msg);
  613. set_position_target_global_int->vy = mavlink_msg_set_position_target_global_int_get_vy(msg);
  614. set_position_target_global_int->vz = mavlink_msg_set_position_target_global_int_get_vz(msg);
  615. set_position_target_global_int->afx = mavlink_msg_set_position_target_global_int_get_afx(msg);
  616. set_position_target_global_int->afy = mavlink_msg_set_position_target_global_int_get_afy(msg);
  617. set_position_target_global_int->afz = mavlink_msg_set_position_target_global_int_get_afz(msg);
  618. set_position_target_global_int->yaw = mavlink_msg_set_position_target_global_int_get_yaw(msg);
  619. set_position_target_global_int->yaw_rate = mavlink_msg_set_position_target_global_int_get_yaw_rate(msg);
  620. set_position_target_global_int->type_mask = mavlink_msg_set_position_target_global_int_get_type_mask(msg);
  621. set_position_target_global_int->target_system = mavlink_msg_set_position_target_global_int_get_target_system(msg);
  622. set_position_target_global_int->target_component = mavlink_msg_set_position_target_global_int_get_target_component(msg);
  623. set_position_target_global_int->coordinate_frame = mavlink_msg_set_position_target_global_int_get_coordinate_frame(msg);
  624. #else
  625. uint8_t len = msg->len < MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN? msg->len : MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN;
  626. memset(set_position_target_global_int, 0, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
  627. memcpy(set_position_target_global_int, _MAV_PAYLOAD(msg), len);
  628. #endif
  629. }