mavlink_msg_orbit_execution_status.h 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414
  1. #pragma once
  2. // MESSAGE ORBIT_EXECUTION_STATUS PACKING
  3. #define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS 360
  4. typedef struct __mavlink_orbit_execution_status_t {
  5. uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
  6. float radius; /*< [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.*/
  7. int32_t x; /*< X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.*/
  8. int32_t y; /*< Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.*/
  9. float z; /*< [m] Altitude of center point. Coordinate system depends on frame field.*/
  10. uint8_t frame; /*< The coordinate system of the fields: x, y, z.*/
  11. } mavlink_orbit_execution_status_t;
  12. #define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN 25
  13. #define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN 25
  14. #define MAVLINK_MSG_ID_360_LEN 25
  15. #define MAVLINK_MSG_ID_360_MIN_LEN 25
  16. #define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC 11
  17. #define MAVLINK_MSG_ID_360_CRC 11
  18. #if MAVLINK_COMMAND_24BIT
  19. #define MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS { \
  20. 360, \
  21. "ORBIT_EXECUTION_STATUS", \
  22. 6, \
  23. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_orbit_execution_status_t, time_usec) }, \
  24. { "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_orbit_execution_status_t, radius) }, \
  25. { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_orbit_execution_status_t, frame) }, \
  26. { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_orbit_execution_status_t, x) }, \
  27. { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_orbit_execution_status_t, y) }, \
  28. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_orbit_execution_status_t, z) }, \
  29. } \
  30. }
  31. #else
  32. #define MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS { \
  33. "ORBIT_EXECUTION_STATUS", \
  34. 6, \
  35. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_orbit_execution_status_t, time_usec) }, \
  36. { "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_orbit_execution_status_t, radius) }, \
  37. { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_orbit_execution_status_t, frame) }, \
  38. { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_orbit_execution_status_t, x) }, \
  39. { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_orbit_execution_status_t, y) }, \
  40. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_orbit_execution_status_t, z) }, \
  41. } \
  42. }
  43. #endif
  44. /**
  45. * @brief Pack a orbit_execution_status message
  46. * @param system_id ID of this system
  47. * @param component_id ID of this component (e.g. 200 for IMU)
  48. * @param msg The MAVLink message to compress the data into
  49. *
  50. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  51. * @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
  52. * @param frame The coordinate system of the fields: x, y, z.
  53. * @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  54. * @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  55. * @param z [m] Altitude of center point. Coordinate system depends on frame field.
  56. * @return length of the message in bytes (excluding serial stream start sign)
  57. */
  58. MAVLINK_WIP
  59. static inline uint16_t mavlink_msg_orbit_execution_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  60. uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t y, float z)
  61. {
  62. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  63. char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN];
  64. _mav_put_uint64_t(buf, 0, time_usec);
  65. _mav_put_float(buf, 8, radius);
  66. _mav_put_int32_t(buf, 12, x);
  67. _mav_put_int32_t(buf, 16, y);
  68. _mav_put_float(buf, 20, z);
  69. _mav_put_uint8_t(buf, 24, frame);
  70. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  71. #else
  72. mavlink_orbit_execution_status_t packet;
  73. packet.time_usec = time_usec;
  74. packet.radius = radius;
  75. packet.x = x;
  76. packet.y = y;
  77. packet.z = z;
  78. packet.frame = frame;
  79. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  80. #endif
  81. msg->msgid = MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS;
  82. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
  83. }
  84. /**
  85. * @brief Pack a orbit_execution_status message
  86. * @param system_id ID of this system
  87. * @param component_id ID of this component (e.g. 200 for IMU)
  88. * @param status MAVLink status structure
  89. * @param msg The MAVLink message to compress the data into
  90. *
  91. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  92. * @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
  93. * @param frame The coordinate system of the fields: x, y, z.
  94. * @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  95. * @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  96. * @param z [m] Altitude of center point. Coordinate system depends on frame field.
  97. * @return length of the message in bytes (excluding serial stream start sign)
  98. */
  99. static inline uint16_t mavlink_msg_orbit_execution_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  100. uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t y, float z)
  101. {
  102. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  103. char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN];
  104. _mav_put_uint64_t(buf, 0, time_usec);
  105. _mav_put_float(buf, 8, radius);
  106. _mav_put_int32_t(buf, 12, x);
  107. _mav_put_int32_t(buf, 16, y);
  108. _mav_put_float(buf, 20, z);
  109. _mav_put_uint8_t(buf, 24, frame);
  110. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  111. #else
  112. mavlink_orbit_execution_status_t packet;
  113. packet.time_usec = time_usec;
  114. packet.radius = radius;
  115. packet.x = x;
  116. packet.y = y;
  117. packet.z = z;
  118. packet.frame = frame;
  119. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  120. #endif
  121. msg->msgid = MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS;
  122. #if MAVLINK_CRC_EXTRA
  123. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
  124. #else
  125. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  126. #endif
  127. }
  128. /**
  129. * @brief Pack a orbit_execution_status message on a channel
  130. * @param system_id ID of this system
  131. * @param component_id ID of this component (e.g. 200 for IMU)
  132. * @param chan The MAVLink channel this message will be sent over
  133. * @param msg The MAVLink message to compress the data into
  134. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  135. * @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
  136. * @param frame The coordinate system of the fields: x, y, z.
  137. * @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  138. * @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  139. * @param z [m] Altitude of center point. Coordinate system depends on frame field.
  140. * @return length of the message in bytes (excluding serial stream start sign)
  141. */
  142. MAVLINK_WIP
  143. static inline uint16_t mavlink_msg_orbit_execution_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  144. mavlink_message_t* msg,
  145. uint64_t time_usec,float radius,uint8_t frame,int32_t x,int32_t y,float z)
  146. {
  147. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  148. char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN];
  149. _mav_put_uint64_t(buf, 0, time_usec);
  150. _mav_put_float(buf, 8, radius);
  151. _mav_put_int32_t(buf, 12, x);
  152. _mav_put_int32_t(buf, 16, y);
  153. _mav_put_float(buf, 20, z);
  154. _mav_put_uint8_t(buf, 24, frame);
  155. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  156. #else
  157. mavlink_orbit_execution_status_t packet;
  158. packet.time_usec = time_usec;
  159. packet.radius = radius;
  160. packet.x = x;
  161. packet.y = y;
  162. packet.z = z;
  163. packet.frame = frame;
  164. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  165. #endif
  166. msg->msgid = MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS;
  167. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
  168. }
  169. /**
  170. * @brief Encode a orbit_execution_status struct
  171. *
  172. * @param system_id ID of this system
  173. * @param component_id ID of this component (e.g. 200 for IMU)
  174. * @param msg The MAVLink message to compress the data into
  175. * @param orbit_execution_status C-struct to read the message contents from
  176. */
  177. MAVLINK_WIP
  178. static inline uint16_t mavlink_msg_orbit_execution_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_orbit_execution_status_t* orbit_execution_status)
  179. {
  180. return mavlink_msg_orbit_execution_status_pack(system_id, component_id, msg, orbit_execution_status->time_usec, orbit_execution_status->radius, orbit_execution_status->frame, orbit_execution_status->x, orbit_execution_status->y, orbit_execution_status->z);
  181. }
  182. /**
  183. * @brief Encode a orbit_execution_status struct on a channel
  184. *
  185. * @param system_id ID of this system
  186. * @param component_id ID of this component (e.g. 200 for IMU)
  187. * @param chan The MAVLink channel this message will be sent over
  188. * @param msg The MAVLink message to compress the data into
  189. * @param orbit_execution_status C-struct to read the message contents from
  190. */
  191. MAVLINK_WIP
  192. static inline uint16_t mavlink_msg_orbit_execution_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_orbit_execution_status_t* orbit_execution_status)
  193. {
  194. return mavlink_msg_orbit_execution_status_pack_chan(system_id, component_id, chan, msg, orbit_execution_status->time_usec, orbit_execution_status->radius, orbit_execution_status->frame, orbit_execution_status->x, orbit_execution_status->y, orbit_execution_status->z);
  195. }
  196. /**
  197. * @brief Encode a orbit_execution_status struct with provided status structure
  198. *
  199. * @param system_id ID of this system
  200. * @param component_id ID of this component (e.g. 200 for IMU)
  201. * @param status MAVLink status structure
  202. * @param msg The MAVLink message to compress the data into
  203. * @param orbit_execution_status C-struct to read the message contents from
  204. */
  205. static inline uint16_t mavlink_msg_orbit_execution_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_orbit_execution_status_t* orbit_execution_status)
  206. {
  207. return mavlink_msg_orbit_execution_status_pack_status(system_id, component_id, _status, msg, orbit_execution_status->time_usec, orbit_execution_status->radius, orbit_execution_status->frame, orbit_execution_status->x, orbit_execution_status->y, orbit_execution_status->z);
  208. }
  209. /**
  210. * @brief Send a orbit_execution_status message
  211. * @param chan MAVLink channel to send the message
  212. *
  213. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  214. * @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
  215. * @param frame The coordinate system of the fields: x, y, z.
  216. * @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  217. * @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  218. * @param z [m] Altitude of center point. Coordinate system depends on frame field.
  219. */
  220. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  221. MAVLINK_WIP
  222. static inline void mavlink_msg_orbit_execution_status_send(mavlink_channel_t chan, uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t y, float z)
  223. {
  224. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  225. char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN];
  226. _mav_put_uint64_t(buf, 0, time_usec);
  227. _mav_put_float(buf, 8, radius);
  228. _mav_put_int32_t(buf, 12, x);
  229. _mav_put_int32_t(buf, 16, y);
  230. _mav_put_float(buf, 20, z);
  231. _mav_put_uint8_t(buf, 24, frame);
  232. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
  233. #else
  234. mavlink_orbit_execution_status_t packet;
  235. packet.time_usec = time_usec;
  236. packet.radius = radius;
  237. packet.x = x;
  238. packet.y = y;
  239. packet.z = z;
  240. packet.frame = frame;
  241. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
  242. #endif
  243. }
  244. /**
  245. * @brief Send a orbit_execution_status message
  246. * @param chan MAVLink channel to send the message
  247. * @param struct The MAVLink struct to serialize
  248. */
  249. MAVLINK_WIP
  250. static inline void mavlink_msg_orbit_execution_status_send_struct(mavlink_channel_t chan, const mavlink_orbit_execution_status_t* orbit_execution_status)
  251. {
  252. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  253. mavlink_msg_orbit_execution_status_send(chan, orbit_execution_status->time_usec, orbit_execution_status->radius, orbit_execution_status->frame, orbit_execution_status->x, orbit_execution_status->y, orbit_execution_status->z);
  254. #else
  255. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, (const char *)orbit_execution_status, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
  256. #endif
  257. }
  258. #if MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  259. /*
  260. This variant of _send() can be used to save stack space by reusing
  261. memory from the receive buffer. The caller provides a
  262. mavlink_message_t which is the size of a full mavlink message. This
  263. is usually the receive buffer for the channel, and allows a reply to an
  264. incoming message with minimum stack space usage.
  265. */
  266. MAVLINK_WIP
  267. static inline void mavlink_msg_orbit_execution_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t y, float z)
  268. {
  269. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  270. char *buf = (char *)msgbuf;
  271. _mav_put_uint64_t(buf, 0, time_usec);
  272. _mav_put_float(buf, 8, radius);
  273. _mav_put_int32_t(buf, 12, x);
  274. _mav_put_int32_t(buf, 16, y);
  275. _mav_put_float(buf, 20, z);
  276. _mav_put_uint8_t(buf, 24, frame);
  277. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
  278. #else
  279. mavlink_orbit_execution_status_t *packet = (mavlink_orbit_execution_status_t *)msgbuf;
  280. packet->time_usec = time_usec;
  281. packet->radius = radius;
  282. packet->x = x;
  283. packet->y = y;
  284. packet->z = z;
  285. packet->frame = frame;
  286. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, (const char *)packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
  287. #endif
  288. }
  289. #endif
  290. #endif
  291. // MESSAGE ORBIT_EXECUTION_STATUS UNPACKING
  292. /**
  293. * @brief Get field time_usec from orbit_execution_status message
  294. *
  295. * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  296. */
  297. MAVLINK_WIP
  298. static inline uint64_t mavlink_msg_orbit_execution_status_get_time_usec(const mavlink_message_t* msg)
  299. {
  300. return _MAV_RETURN_uint64_t(msg, 0);
  301. }
  302. /**
  303. * @brief Get field radius from orbit_execution_status message
  304. *
  305. * @return [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
  306. */
  307. MAVLINK_WIP
  308. static inline float mavlink_msg_orbit_execution_status_get_radius(const mavlink_message_t* msg)
  309. {
  310. return _MAV_RETURN_float(msg, 8);
  311. }
  312. /**
  313. * @brief Get field frame from orbit_execution_status message
  314. *
  315. * @return The coordinate system of the fields: x, y, z.
  316. */
  317. MAVLINK_WIP
  318. static inline uint8_t mavlink_msg_orbit_execution_status_get_frame(const mavlink_message_t* msg)
  319. {
  320. return _MAV_RETURN_uint8_t(msg, 24);
  321. }
  322. /**
  323. * @brief Get field x from orbit_execution_status message
  324. *
  325. * @return X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  326. */
  327. MAVLINK_WIP
  328. static inline int32_t mavlink_msg_orbit_execution_status_get_x(const mavlink_message_t* msg)
  329. {
  330. return _MAV_RETURN_int32_t(msg, 12);
  331. }
  332. /**
  333. * @brief Get field y from orbit_execution_status message
  334. *
  335. * @return Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  336. */
  337. MAVLINK_WIP
  338. static inline int32_t mavlink_msg_orbit_execution_status_get_y(const mavlink_message_t* msg)
  339. {
  340. return _MAV_RETURN_int32_t(msg, 16);
  341. }
  342. /**
  343. * @brief Get field z from orbit_execution_status message
  344. *
  345. * @return [m] Altitude of center point. Coordinate system depends on frame field.
  346. */
  347. MAVLINK_WIP
  348. static inline float mavlink_msg_orbit_execution_status_get_z(const mavlink_message_t* msg)
  349. {
  350. return _MAV_RETURN_float(msg, 20);
  351. }
  352. /**
  353. * @brief Decode a orbit_execution_status message into a struct
  354. *
  355. * @param msg The message to decode
  356. * @param orbit_execution_status C-struct to decode the message contents into
  357. */
  358. MAVLINK_WIP
  359. static inline void mavlink_msg_orbit_execution_status_decode(const mavlink_message_t* msg, mavlink_orbit_execution_status_t* orbit_execution_status)
  360. {
  361. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  362. orbit_execution_status->time_usec = mavlink_msg_orbit_execution_status_get_time_usec(msg);
  363. orbit_execution_status->radius = mavlink_msg_orbit_execution_status_get_radius(msg);
  364. orbit_execution_status->x = mavlink_msg_orbit_execution_status_get_x(msg);
  365. orbit_execution_status->y = mavlink_msg_orbit_execution_status_get_y(msg);
  366. orbit_execution_status->z = mavlink_msg_orbit_execution_status_get_z(msg);
  367. orbit_execution_status->frame = mavlink_msg_orbit_execution_status_get_frame(msg);
  368. #else
  369. uint8_t len = msg->len < MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN;
  370. memset(orbit_execution_status, 0, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  371. memcpy(orbit_execution_status, _MAV_PAYLOAD(msg), len);
  372. #endif
  373. }