mavlink_msg_orbit_execution_status.h 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338
  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. static inline uint16_t mavlink_msg_orbit_execution_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  59. uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t y, float z)
  60. {
  61. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  62. char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN];
  63. _mav_put_uint64_t(buf, 0, time_usec);
  64. _mav_put_float(buf, 8, radius);
  65. _mav_put_int32_t(buf, 12, x);
  66. _mav_put_int32_t(buf, 16, y);
  67. _mav_put_float(buf, 20, z);
  68. _mav_put_uint8_t(buf, 24, frame);
  69. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  70. #else
  71. mavlink_orbit_execution_status_t packet;
  72. packet.time_usec = time_usec;
  73. packet.radius = radius;
  74. packet.x = x;
  75. packet.y = y;
  76. packet.z = z;
  77. packet.frame = frame;
  78. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  79. #endif
  80. msg->msgid = MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS;
  81. 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);
  82. }
  83. /**
  84. * @brief Pack a orbit_execution_status message on a channel
  85. * @param system_id ID of this system
  86. * @param component_id ID of this component (e.g. 200 for IMU)
  87. * @param chan The MAVLink channel this message will be sent over
  88. * @param msg The MAVLink message to compress the data into
  89. * @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.
  90. * @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
  91. * @param frame The coordinate system of the fields: x, y, z.
  92. * @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  93. * @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  94. * @param z [m] Altitude of center point. Coordinate system depends on frame field.
  95. * @return length of the message in bytes (excluding serial stream start sign)
  96. */
  97. static inline uint16_t mavlink_msg_orbit_execution_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  98. mavlink_message_t* msg,
  99. uint64_t time_usec,float radius,uint8_t frame,int32_t x,int32_t y,float z)
  100. {
  101. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  102. char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN];
  103. _mav_put_uint64_t(buf, 0, time_usec);
  104. _mav_put_float(buf, 8, radius);
  105. _mav_put_int32_t(buf, 12, x);
  106. _mav_put_int32_t(buf, 16, y);
  107. _mav_put_float(buf, 20, z);
  108. _mav_put_uint8_t(buf, 24, frame);
  109. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  110. #else
  111. mavlink_orbit_execution_status_t packet;
  112. packet.time_usec = time_usec;
  113. packet.radius = radius;
  114. packet.x = x;
  115. packet.y = y;
  116. packet.z = z;
  117. packet.frame = frame;
  118. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  119. #endif
  120. msg->msgid = MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS;
  121. 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);
  122. }
  123. /**
  124. * @brief Encode a orbit_execution_status struct
  125. *
  126. * @param system_id ID of this system
  127. * @param component_id ID of this component (e.g. 200 for IMU)
  128. * @param msg The MAVLink message to compress the data into
  129. * @param orbit_execution_status C-struct to read the message contents from
  130. */
  131. 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)
  132. {
  133. 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);
  134. }
  135. /**
  136. * @brief Encode a orbit_execution_status struct on a channel
  137. *
  138. * @param system_id ID of this system
  139. * @param component_id ID of this component (e.g. 200 for IMU)
  140. * @param chan The MAVLink channel this message will be sent over
  141. * @param msg The MAVLink message to compress the data into
  142. * @param orbit_execution_status C-struct to read the message contents from
  143. */
  144. 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)
  145. {
  146. 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);
  147. }
  148. /**
  149. * @brief Send a orbit_execution_status message
  150. * @param chan MAVLink channel to send the message
  151. *
  152. * @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.
  153. * @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
  154. * @param frame The coordinate system of the fields: x, y, z.
  155. * @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  156. * @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  157. * @param z [m] Altitude of center point. Coordinate system depends on frame field.
  158. */
  159. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  160. 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)
  161. {
  162. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  163. char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN];
  164. _mav_put_uint64_t(buf, 0, time_usec);
  165. _mav_put_float(buf, 8, radius);
  166. _mav_put_int32_t(buf, 12, x);
  167. _mav_put_int32_t(buf, 16, y);
  168. _mav_put_float(buf, 20, z);
  169. _mav_put_uint8_t(buf, 24, frame);
  170. _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);
  171. #else
  172. mavlink_orbit_execution_status_t packet;
  173. packet.time_usec = time_usec;
  174. packet.radius = radius;
  175. packet.x = x;
  176. packet.y = y;
  177. packet.z = z;
  178. packet.frame = frame;
  179. _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);
  180. #endif
  181. }
  182. /**
  183. * @brief Send a orbit_execution_status message
  184. * @param chan MAVLink channel to send the message
  185. * @param struct The MAVLink struct to serialize
  186. */
  187. static inline void mavlink_msg_orbit_execution_status_send_struct(mavlink_channel_t chan, const mavlink_orbit_execution_status_t* orbit_execution_status)
  188. {
  189. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  190. 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);
  191. #else
  192. _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);
  193. #endif
  194. }
  195. #if MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  196. /*
  197. This variant of _send() can be used to save stack space by re-using
  198. memory from the receive buffer. The caller provides a
  199. mavlink_message_t which is the size of a full mavlink message. This
  200. is usually the receive buffer for the channel, and allows a reply to an
  201. incoming message with minimum stack space usage.
  202. */
  203. 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)
  204. {
  205. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  206. char *buf = (char *)msgbuf;
  207. _mav_put_uint64_t(buf, 0, time_usec);
  208. _mav_put_float(buf, 8, radius);
  209. _mav_put_int32_t(buf, 12, x);
  210. _mav_put_int32_t(buf, 16, y);
  211. _mav_put_float(buf, 20, z);
  212. _mav_put_uint8_t(buf, 24, frame);
  213. _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);
  214. #else
  215. mavlink_orbit_execution_status_t *packet = (mavlink_orbit_execution_status_t *)msgbuf;
  216. packet->time_usec = time_usec;
  217. packet->radius = radius;
  218. packet->x = x;
  219. packet->y = y;
  220. packet->z = z;
  221. packet->frame = frame;
  222. _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);
  223. #endif
  224. }
  225. #endif
  226. #endif
  227. // MESSAGE ORBIT_EXECUTION_STATUS UNPACKING
  228. /**
  229. * @brief Get field time_usec from orbit_execution_status message
  230. *
  231. * @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.
  232. */
  233. static inline uint64_t mavlink_msg_orbit_execution_status_get_time_usec(const mavlink_message_t* msg)
  234. {
  235. return _MAV_RETURN_uint64_t(msg, 0);
  236. }
  237. /**
  238. * @brief Get field radius from orbit_execution_status message
  239. *
  240. * @return [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
  241. */
  242. static inline float mavlink_msg_orbit_execution_status_get_radius(const mavlink_message_t* msg)
  243. {
  244. return _MAV_RETURN_float(msg, 8);
  245. }
  246. /**
  247. * @brief Get field frame from orbit_execution_status message
  248. *
  249. * @return The coordinate system of the fields: x, y, z.
  250. */
  251. static inline uint8_t mavlink_msg_orbit_execution_status_get_frame(const mavlink_message_t* msg)
  252. {
  253. return _MAV_RETURN_uint8_t(msg, 24);
  254. }
  255. /**
  256. * @brief Get field x from orbit_execution_status message
  257. *
  258. * @return X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  259. */
  260. static inline int32_t mavlink_msg_orbit_execution_status_get_x(const mavlink_message_t* msg)
  261. {
  262. return _MAV_RETURN_int32_t(msg, 12);
  263. }
  264. /**
  265. * @brief Get field y from orbit_execution_status message
  266. *
  267. * @return Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
  268. */
  269. static inline int32_t mavlink_msg_orbit_execution_status_get_y(const mavlink_message_t* msg)
  270. {
  271. return _MAV_RETURN_int32_t(msg, 16);
  272. }
  273. /**
  274. * @brief Get field z from orbit_execution_status message
  275. *
  276. * @return [m] Altitude of center point. Coordinate system depends on frame field.
  277. */
  278. static inline float mavlink_msg_orbit_execution_status_get_z(const mavlink_message_t* msg)
  279. {
  280. return _MAV_RETURN_float(msg, 20);
  281. }
  282. /**
  283. * @brief Decode a orbit_execution_status message into a struct
  284. *
  285. * @param msg The message to decode
  286. * @param orbit_execution_status C-struct to decode the message contents into
  287. */
  288. static inline void mavlink_msg_orbit_execution_status_decode(const mavlink_message_t* msg, mavlink_orbit_execution_status_t* orbit_execution_status)
  289. {
  290. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  291. orbit_execution_status->time_usec = mavlink_msg_orbit_execution_status_get_time_usec(msg);
  292. orbit_execution_status->radius = mavlink_msg_orbit_execution_status_get_radius(msg);
  293. orbit_execution_status->x = mavlink_msg_orbit_execution_status_get_x(msg);
  294. orbit_execution_status->y = mavlink_msg_orbit_execution_status_get_y(msg);
  295. orbit_execution_status->z = mavlink_msg_orbit_execution_status_get_z(msg);
  296. orbit_execution_status->frame = mavlink_msg_orbit_execution_status_get_frame(msg);
  297. #else
  298. uint8_t len = msg->len < MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN;
  299. memset(orbit_execution_status, 0, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
  300. memcpy(orbit_execution_status, _MAV_PAYLOAD(msg), len);
  301. #endif
  302. }