mavlink_msg_hil_actuator_controls.h 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280
  1. #pragma once
  2. // MESSAGE HIL_ACTUATOR_CONTROLS PACKING
  3. #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS 93
  4. typedef struct __mavlink_hil_actuator_controls_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. uint64_t flags; /*< Flags as bitfield, 1: indicate simulation using lockstep.*/
  7. float controls[16]; /*< Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.*/
  8. uint8_t mode; /*< System mode. Includes arming state.*/
  9. } mavlink_hil_actuator_controls_t;
  10. #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN 81
  11. #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN 81
  12. #define MAVLINK_MSG_ID_93_LEN 81
  13. #define MAVLINK_MSG_ID_93_MIN_LEN 81
  14. #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC 47
  15. #define MAVLINK_MSG_ID_93_CRC 47
  16. #define MAVLINK_MSG_HIL_ACTUATOR_CONTROLS_FIELD_CONTROLS_LEN 16
  17. #if MAVLINK_COMMAND_24BIT
  18. #define MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS { \
  19. 93, \
  20. "HIL_ACTUATOR_CONTROLS", \
  21. 4, \
  22. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \
  23. { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \
  24. { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \
  25. { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \
  26. } \
  27. }
  28. #else
  29. #define MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS { \
  30. "HIL_ACTUATOR_CONTROLS", \
  31. 4, \
  32. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \
  33. { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \
  34. { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \
  35. { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \
  36. } \
  37. }
  38. #endif
  39. /**
  40. * @brief Pack a hil_actuator_controls message
  41. * @param system_id ID of this system
  42. * @param component_id ID of this component (e.g. 200 for IMU)
  43. * @param msg The MAVLink message to compress the data into
  44. *
  45. * @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.
  46. * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
  47. * @param mode System mode. Includes arming state.
  48. * @param flags Flags as bitfield, 1: indicate simulation using lockstep.
  49. * @return length of the message in bytes (excluding serial stream start sign)
  50. */
  51. static inline uint16_t mavlink_msg_hil_actuator_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  52. uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags)
  53. {
  54. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  55. char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN];
  56. _mav_put_uint64_t(buf, 0, time_usec);
  57. _mav_put_uint64_t(buf, 8, flags);
  58. _mav_put_uint8_t(buf, 80, mode);
  59. _mav_put_float_array(buf, 16, controls, 16);
  60. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN);
  61. #else
  62. mavlink_hil_actuator_controls_t packet;
  63. packet.time_usec = time_usec;
  64. packet.flags = flags;
  65. packet.mode = mode;
  66. mav_array_memcpy(packet.controls, controls, sizeof(float)*16);
  67. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN);
  68. #endif
  69. msg->msgid = MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS;
  70. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC);
  71. }
  72. /**
  73. * @brief Pack a hil_actuator_controls message on a channel
  74. * @param system_id ID of this system
  75. * @param component_id ID of this component (e.g. 200 for IMU)
  76. * @param chan The MAVLink channel this message will be sent over
  77. * @param msg The MAVLink message to compress the data into
  78. * @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.
  79. * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
  80. * @param mode System mode. Includes arming state.
  81. * @param flags Flags as bitfield, 1: indicate simulation using lockstep.
  82. * @return length of the message in bytes (excluding serial stream start sign)
  83. */
  84. static inline uint16_t mavlink_msg_hil_actuator_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  85. mavlink_message_t* msg,
  86. uint64_t time_usec,const float *controls,uint8_t mode,uint64_t flags)
  87. {
  88. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  89. char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN];
  90. _mav_put_uint64_t(buf, 0, time_usec);
  91. _mav_put_uint64_t(buf, 8, flags);
  92. _mav_put_uint8_t(buf, 80, mode);
  93. _mav_put_float_array(buf, 16, controls, 16);
  94. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN);
  95. #else
  96. mavlink_hil_actuator_controls_t packet;
  97. packet.time_usec = time_usec;
  98. packet.flags = flags;
  99. packet.mode = mode;
  100. mav_array_memcpy(packet.controls, controls, sizeof(float)*16);
  101. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN);
  102. #endif
  103. msg->msgid = MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS;
  104. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC);
  105. }
  106. /**
  107. * @brief Encode a hil_actuator_controls struct
  108. *
  109. * @param system_id ID of this system
  110. * @param component_id ID of this component (e.g. 200 for IMU)
  111. * @param msg The MAVLink message to compress the data into
  112. * @param hil_actuator_controls C-struct to read the message contents from
  113. */
  114. static inline uint16_t mavlink_msg_hil_actuator_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_actuator_controls_t* hil_actuator_controls)
  115. {
  116. return mavlink_msg_hil_actuator_controls_pack(system_id, component_id, msg, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags);
  117. }
  118. /**
  119. * @brief Encode a hil_actuator_controls struct on a channel
  120. *
  121. * @param system_id ID of this system
  122. * @param component_id ID of this component (e.g. 200 for IMU)
  123. * @param chan The MAVLink channel this message will be sent over
  124. * @param msg The MAVLink message to compress the data into
  125. * @param hil_actuator_controls C-struct to read the message contents from
  126. */
  127. static inline uint16_t mavlink_msg_hil_actuator_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_actuator_controls_t* hil_actuator_controls)
  128. {
  129. return mavlink_msg_hil_actuator_controls_pack_chan(system_id, component_id, chan, msg, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags);
  130. }
  131. /**
  132. * @brief Send a hil_actuator_controls message
  133. * @param chan MAVLink channel to send the message
  134. *
  135. * @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.
  136. * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
  137. * @param mode System mode. Includes arming state.
  138. * @param flags Flags as bitfield, 1: indicate simulation using lockstep.
  139. */
  140. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  141. static inline void mavlink_msg_hil_actuator_controls_send(mavlink_channel_t chan, uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags)
  142. {
  143. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  144. char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN];
  145. _mav_put_uint64_t(buf, 0, time_usec);
  146. _mav_put_uint64_t(buf, 8, flags);
  147. _mav_put_uint8_t(buf, 80, mode);
  148. _mav_put_float_array(buf, 16, controls, 16);
  149. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC);
  150. #else
  151. mavlink_hil_actuator_controls_t packet;
  152. packet.time_usec = time_usec;
  153. packet.flags = flags;
  154. packet.mode = mode;
  155. mav_array_memcpy(packet.controls, controls, sizeof(float)*16);
  156. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC);
  157. #endif
  158. }
  159. /**
  160. * @brief Send a hil_actuator_controls message
  161. * @param chan MAVLink channel to send the message
  162. * @param struct The MAVLink struct to serialize
  163. */
  164. static inline void mavlink_msg_hil_actuator_controls_send_struct(mavlink_channel_t chan, const mavlink_hil_actuator_controls_t* hil_actuator_controls)
  165. {
  166. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  167. mavlink_msg_hil_actuator_controls_send(chan, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags);
  168. #else
  169. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)hil_actuator_controls, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC);
  170. #endif
  171. }
  172. #if MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  173. /*
  174. This variant of _send() can be used to save stack space by re-using
  175. memory from the receive buffer. The caller provides a
  176. mavlink_message_t which is the size of a full mavlink message. This
  177. is usually the receive buffer for the channel, and allows a reply to an
  178. incoming message with minimum stack space usage.
  179. */
  180. static inline void mavlink_msg_hil_actuator_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags)
  181. {
  182. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  183. char *buf = (char *)msgbuf;
  184. _mav_put_uint64_t(buf, 0, time_usec);
  185. _mav_put_uint64_t(buf, 8, flags);
  186. _mav_put_uint8_t(buf, 80, mode);
  187. _mav_put_float_array(buf, 16, controls, 16);
  188. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC);
  189. #else
  190. mavlink_hil_actuator_controls_t *packet = (mavlink_hil_actuator_controls_t *)msgbuf;
  191. packet->time_usec = time_usec;
  192. packet->flags = flags;
  193. packet->mode = mode;
  194. mav_array_memcpy(packet->controls, controls, sizeof(float)*16);
  195. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC);
  196. #endif
  197. }
  198. #endif
  199. #endif
  200. // MESSAGE HIL_ACTUATOR_CONTROLS UNPACKING
  201. /**
  202. * @brief Get field time_usec from hil_actuator_controls message
  203. *
  204. * @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.
  205. */
  206. static inline uint64_t mavlink_msg_hil_actuator_controls_get_time_usec(const mavlink_message_t* msg)
  207. {
  208. return _MAV_RETURN_uint64_t(msg, 0);
  209. }
  210. /**
  211. * @brief Get field controls from hil_actuator_controls message
  212. *
  213. * @return Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
  214. */
  215. static inline uint16_t mavlink_msg_hil_actuator_controls_get_controls(const mavlink_message_t* msg, float *controls)
  216. {
  217. return _MAV_RETURN_float_array(msg, controls, 16, 16);
  218. }
  219. /**
  220. * @brief Get field mode from hil_actuator_controls message
  221. *
  222. * @return System mode. Includes arming state.
  223. */
  224. static inline uint8_t mavlink_msg_hil_actuator_controls_get_mode(const mavlink_message_t* msg)
  225. {
  226. return _MAV_RETURN_uint8_t(msg, 80);
  227. }
  228. /**
  229. * @brief Get field flags from hil_actuator_controls message
  230. *
  231. * @return Flags as bitfield, 1: indicate simulation using lockstep.
  232. */
  233. static inline uint64_t mavlink_msg_hil_actuator_controls_get_flags(const mavlink_message_t* msg)
  234. {
  235. return _MAV_RETURN_uint64_t(msg, 8);
  236. }
  237. /**
  238. * @brief Decode a hil_actuator_controls message into a struct
  239. *
  240. * @param msg The message to decode
  241. * @param hil_actuator_controls C-struct to decode the message contents into
  242. */
  243. static inline void mavlink_msg_hil_actuator_controls_decode(const mavlink_message_t* msg, mavlink_hil_actuator_controls_t* hil_actuator_controls)
  244. {
  245. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  246. hil_actuator_controls->time_usec = mavlink_msg_hil_actuator_controls_get_time_usec(msg);
  247. hil_actuator_controls->flags = mavlink_msg_hil_actuator_controls_get_flags(msg);
  248. mavlink_msg_hil_actuator_controls_get_controls(msg, hil_actuator_controls->controls);
  249. hil_actuator_controls->mode = mavlink_msg_hil_actuator_controls_get_mode(msg);
  250. #else
  251. uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN? msg->len : MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN;
  252. memset(hil_actuator_controls, 0, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN);
  253. memcpy(hil_actuator_controls, _MAV_PAYLOAD(msg), len);
  254. #endif
  255. }