mavlink_msg_esc_status.h 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377
  1. #pragma once
  2. // MESSAGE ESC_STATUS PACKING
  3. #define MAVLINK_MSG_ID_ESC_STATUS 291
  4. typedef struct __mavlink_esc_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 the number.*/
  6. int32_t rpm[4]; /*< [rpm] Reported motor RPM from each ESC (negative for reverse rotation).*/
  7. float voltage[4]; /*< [V] Voltage measured from each ESC.*/
  8. float current[4]; /*< [A] Current measured from each ESC.*/
  9. uint8_t index; /*< Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.*/
  10. } mavlink_esc_status_t;
  11. #define MAVLINK_MSG_ID_ESC_STATUS_LEN 57
  12. #define MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN 57
  13. #define MAVLINK_MSG_ID_291_LEN 57
  14. #define MAVLINK_MSG_ID_291_MIN_LEN 57
  15. #define MAVLINK_MSG_ID_ESC_STATUS_CRC 10
  16. #define MAVLINK_MSG_ID_291_CRC 10
  17. #define MAVLINK_MSG_ESC_STATUS_FIELD_RPM_LEN 4
  18. #define MAVLINK_MSG_ESC_STATUS_FIELD_VOLTAGE_LEN 4
  19. #define MAVLINK_MSG_ESC_STATUS_FIELD_CURRENT_LEN 4
  20. #if MAVLINK_COMMAND_24BIT
  21. #define MAVLINK_MESSAGE_INFO_ESC_STATUS { \
  22. 291, \
  23. "ESC_STATUS", \
  24. 5, \
  25. { { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_esc_status_t, index) }, \
  26. { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_esc_status_t, time_usec) }, \
  27. { "rpm", NULL, MAVLINK_TYPE_INT32_T, 4, 8, offsetof(mavlink_esc_status_t, rpm) }, \
  28. { "voltage", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_esc_status_t, voltage) }, \
  29. { "current", NULL, MAVLINK_TYPE_FLOAT, 4, 40, offsetof(mavlink_esc_status_t, current) }, \
  30. } \
  31. }
  32. #else
  33. #define MAVLINK_MESSAGE_INFO_ESC_STATUS { \
  34. "ESC_STATUS", \
  35. 5, \
  36. { { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_esc_status_t, index) }, \
  37. { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_esc_status_t, time_usec) }, \
  38. { "rpm", NULL, MAVLINK_TYPE_INT32_T, 4, 8, offsetof(mavlink_esc_status_t, rpm) }, \
  39. { "voltage", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_esc_status_t, voltage) }, \
  40. { "current", NULL, MAVLINK_TYPE_FLOAT, 4, 40, offsetof(mavlink_esc_status_t, current) }, \
  41. } \
  42. }
  43. #endif
  44. /**
  45. * @brief Pack a esc_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 index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
  51. * @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 the number.
  52. * @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
  53. * @param voltage [V] Voltage measured from each ESC.
  54. * @param current [A] Current measured from each ESC.
  55. * @return length of the message in bytes (excluding serial stream start sign)
  56. */
  57. MAVLINK_WIP
  58. static inline uint16_t mavlink_msg_esc_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  59. uint8_t index, uint64_t time_usec, const int32_t *rpm, const float *voltage, const float *current)
  60. {
  61. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  62. char buf[MAVLINK_MSG_ID_ESC_STATUS_LEN];
  63. _mav_put_uint64_t(buf, 0, time_usec);
  64. _mav_put_uint8_t(buf, 56, index);
  65. _mav_put_int32_t_array(buf, 8, rpm, 4);
  66. _mav_put_float_array(buf, 24, voltage, 4);
  67. _mav_put_float_array(buf, 40, current, 4);
  68. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_STATUS_LEN);
  69. #else
  70. mavlink_esc_status_t packet;
  71. packet.time_usec = time_usec;
  72. packet.index = index;
  73. mav_array_assign_int32_t(packet.rpm, rpm, 4);
  74. mav_array_assign_float(packet.voltage, voltage, 4);
  75. mav_array_assign_float(packet.current, current, 4);
  76. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_STATUS_LEN);
  77. #endif
  78. msg->msgid = MAVLINK_MSG_ID_ESC_STATUS;
  79. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
  80. }
  81. /**
  82. * @brief Pack a esc_status message
  83. * @param system_id ID of this system
  84. * @param component_id ID of this component (e.g. 200 for IMU)
  85. * @param status MAVLink status structure
  86. * @param msg The MAVLink message to compress the data into
  87. *
  88. * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
  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 the number.
  90. * @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
  91. * @param voltage [V] Voltage measured from each ESC.
  92. * @param current [A] Current measured from each ESC.
  93. * @return length of the message in bytes (excluding serial stream start sign)
  94. */
  95. static inline uint16_t mavlink_msg_esc_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  96. uint8_t index, uint64_t time_usec, const int32_t *rpm, const float *voltage, const float *current)
  97. {
  98. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  99. char buf[MAVLINK_MSG_ID_ESC_STATUS_LEN];
  100. _mav_put_uint64_t(buf, 0, time_usec);
  101. _mav_put_uint8_t(buf, 56, index);
  102. _mav_put_int32_t_array(buf, 8, rpm, 4);
  103. _mav_put_float_array(buf, 24, voltage, 4);
  104. _mav_put_float_array(buf, 40, current, 4);
  105. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_STATUS_LEN);
  106. #else
  107. mavlink_esc_status_t packet;
  108. packet.time_usec = time_usec;
  109. packet.index = index;
  110. mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4);
  111. mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4);
  112. mav_array_memcpy(packet.current, current, sizeof(float)*4);
  113. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_STATUS_LEN);
  114. #endif
  115. msg->msgid = MAVLINK_MSG_ID_ESC_STATUS;
  116. #if MAVLINK_CRC_EXTRA
  117. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
  118. #else
  119. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN);
  120. #endif
  121. }
  122. /**
  123. * @brief Pack a esc_status message on a channel
  124. * @param system_id ID of this system
  125. * @param component_id ID of this component (e.g. 200 for IMU)
  126. * @param chan The MAVLink channel this message will be sent over
  127. * @param msg The MAVLink message to compress the data into
  128. * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
  129. * @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 the number.
  130. * @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
  131. * @param voltage [V] Voltage measured from each ESC.
  132. * @param current [A] Current measured from each ESC.
  133. * @return length of the message in bytes (excluding serial stream start sign)
  134. */
  135. MAVLINK_WIP
  136. static inline uint16_t mavlink_msg_esc_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  137. mavlink_message_t* msg,
  138. uint8_t index,uint64_t time_usec,const int32_t *rpm,const float *voltage,const float *current)
  139. {
  140. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  141. char buf[MAVLINK_MSG_ID_ESC_STATUS_LEN];
  142. _mav_put_uint64_t(buf, 0, time_usec);
  143. _mav_put_uint8_t(buf, 56, index);
  144. _mav_put_int32_t_array(buf, 8, rpm, 4);
  145. _mav_put_float_array(buf, 24, voltage, 4);
  146. _mav_put_float_array(buf, 40, current, 4);
  147. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_STATUS_LEN);
  148. #else
  149. mavlink_esc_status_t packet;
  150. packet.time_usec = time_usec;
  151. packet.index = index;
  152. mav_array_assign_int32_t(packet.rpm, rpm, 4);
  153. mav_array_assign_float(packet.voltage, voltage, 4);
  154. mav_array_assign_float(packet.current, current, 4);
  155. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_STATUS_LEN);
  156. #endif
  157. msg->msgid = MAVLINK_MSG_ID_ESC_STATUS;
  158. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
  159. }
  160. /**
  161. * @brief Encode a esc_status struct
  162. *
  163. * @param system_id ID of this system
  164. * @param component_id ID of this component (e.g. 200 for IMU)
  165. * @param msg The MAVLink message to compress the data into
  166. * @param esc_status C-struct to read the message contents from
  167. */
  168. MAVLINK_WIP
  169. static inline uint16_t mavlink_msg_esc_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_status_t* esc_status)
  170. {
  171. return mavlink_msg_esc_status_pack(system_id, component_id, msg, esc_status->index, esc_status->time_usec, esc_status->rpm, esc_status->voltage, esc_status->current);
  172. }
  173. /**
  174. * @brief Encode a esc_status struct on a channel
  175. *
  176. * @param system_id ID of this system
  177. * @param component_id ID of this component (e.g. 200 for IMU)
  178. * @param chan The MAVLink channel this message will be sent over
  179. * @param msg The MAVLink message to compress the data into
  180. * @param esc_status C-struct to read the message contents from
  181. */
  182. MAVLINK_WIP
  183. static inline uint16_t mavlink_msg_esc_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_status_t* esc_status)
  184. {
  185. return mavlink_msg_esc_status_pack_chan(system_id, component_id, chan, msg, esc_status->index, esc_status->time_usec, esc_status->rpm, esc_status->voltage, esc_status->current);
  186. }
  187. /**
  188. * @brief Encode a esc_status struct with provided status structure
  189. *
  190. * @param system_id ID of this system
  191. * @param component_id ID of this component (e.g. 200 for IMU)
  192. * @param status MAVLink status structure
  193. * @param msg The MAVLink message to compress the data into
  194. * @param esc_status C-struct to read the message contents from
  195. */
  196. static inline uint16_t mavlink_msg_esc_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_esc_status_t* esc_status)
  197. {
  198. return mavlink_msg_esc_status_pack_status(system_id, component_id, _status, msg, esc_status->index, esc_status->time_usec, esc_status->rpm, esc_status->voltage, esc_status->current);
  199. }
  200. /**
  201. * @brief Send a esc_status message
  202. * @param chan MAVLink channel to send the message
  203. *
  204. * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
  205. * @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 the number.
  206. * @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
  207. * @param voltage [V] Voltage measured from each ESC.
  208. * @param current [A] Current measured from each ESC.
  209. */
  210. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  211. MAVLINK_WIP
  212. static inline void mavlink_msg_esc_status_send(mavlink_channel_t chan, uint8_t index, uint64_t time_usec, const int32_t *rpm, const float *voltage, const float *current)
  213. {
  214. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  215. char buf[MAVLINK_MSG_ID_ESC_STATUS_LEN];
  216. _mav_put_uint64_t(buf, 0, time_usec);
  217. _mav_put_uint8_t(buf, 56, index);
  218. _mav_put_int32_t_array(buf, 8, rpm, 4);
  219. _mav_put_float_array(buf, 24, voltage, 4);
  220. _mav_put_float_array(buf, 40, current, 4);
  221. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, buf, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
  222. #else
  223. mavlink_esc_status_t packet;
  224. packet.time_usec = time_usec;
  225. packet.index = index;
  226. mav_array_assign_int32_t(packet.rpm, rpm, 4);
  227. mav_array_assign_float(packet.voltage, voltage, 4);
  228. mav_array_assign_float(packet.current, current, 4);
  229. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
  230. #endif
  231. }
  232. /**
  233. * @brief Send a esc_status message
  234. * @param chan MAVLink channel to send the message
  235. * @param struct The MAVLink struct to serialize
  236. */
  237. MAVLINK_WIP
  238. static inline void mavlink_msg_esc_status_send_struct(mavlink_channel_t chan, const mavlink_esc_status_t* esc_status)
  239. {
  240. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  241. mavlink_msg_esc_status_send(chan, esc_status->index, esc_status->time_usec, esc_status->rpm, esc_status->voltage, esc_status->current);
  242. #else
  243. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, (const char *)esc_status, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
  244. #endif
  245. }
  246. #if MAVLINK_MSG_ID_ESC_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  247. /*
  248. This variant of _send() can be used to save stack space by reusing
  249. memory from the receive buffer. The caller provides a
  250. mavlink_message_t which is the size of a full mavlink message. This
  251. is usually the receive buffer for the channel, and allows a reply to an
  252. incoming message with minimum stack space usage.
  253. */
  254. MAVLINK_WIP
  255. static inline void mavlink_msg_esc_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t index, uint64_t time_usec, const int32_t *rpm, const float *voltage, const float *current)
  256. {
  257. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  258. char *buf = (char *)msgbuf;
  259. _mav_put_uint64_t(buf, 0, time_usec);
  260. _mav_put_uint8_t(buf, 56, index);
  261. _mav_put_int32_t_array(buf, 8, rpm, 4);
  262. _mav_put_float_array(buf, 24, voltage, 4);
  263. _mav_put_float_array(buf, 40, current, 4);
  264. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, buf, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
  265. #else
  266. mavlink_esc_status_t *packet = (mavlink_esc_status_t *)msgbuf;
  267. packet->time_usec = time_usec;
  268. packet->index = index;
  269. mav_array_assign_int32_t(packet->rpm, rpm, 4);
  270. mav_array_assign_float(packet->voltage, voltage, 4);
  271. mav_array_assign_float(packet->current, current, 4);
  272. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, (const char *)packet, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
  273. #endif
  274. }
  275. #endif
  276. #endif
  277. // MESSAGE ESC_STATUS UNPACKING
  278. /**
  279. * @brief Get field index from esc_status message
  280. *
  281. * @return Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
  282. */
  283. MAVLINK_WIP
  284. static inline uint8_t mavlink_msg_esc_status_get_index(const mavlink_message_t* msg)
  285. {
  286. return _MAV_RETURN_uint8_t(msg, 56);
  287. }
  288. /**
  289. * @brief Get field time_usec from esc_status message
  290. *
  291. * @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 the number.
  292. */
  293. MAVLINK_WIP
  294. static inline uint64_t mavlink_msg_esc_status_get_time_usec(const mavlink_message_t* msg)
  295. {
  296. return _MAV_RETURN_uint64_t(msg, 0);
  297. }
  298. /**
  299. * @brief Get field rpm from esc_status message
  300. *
  301. * @return [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
  302. */
  303. MAVLINK_WIP
  304. static inline uint16_t mavlink_msg_esc_status_get_rpm(const mavlink_message_t* msg, int32_t *rpm)
  305. {
  306. return _MAV_RETURN_int32_t_array(msg, rpm, 4, 8);
  307. }
  308. /**
  309. * @brief Get field voltage from esc_status message
  310. *
  311. * @return [V] Voltage measured from each ESC.
  312. */
  313. MAVLINK_WIP
  314. static inline uint16_t mavlink_msg_esc_status_get_voltage(const mavlink_message_t* msg, float *voltage)
  315. {
  316. return _MAV_RETURN_float_array(msg, voltage, 4, 24);
  317. }
  318. /**
  319. * @brief Get field current from esc_status message
  320. *
  321. * @return [A] Current measured from each ESC.
  322. */
  323. MAVLINK_WIP
  324. static inline uint16_t mavlink_msg_esc_status_get_current(const mavlink_message_t* msg, float *current)
  325. {
  326. return _MAV_RETURN_float_array(msg, current, 4, 40);
  327. }
  328. /**
  329. * @brief Decode a esc_status message into a struct
  330. *
  331. * @param msg The message to decode
  332. * @param esc_status C-struct to decode the message contents into
  333. */
  334. MAVLINK_WIP
  335. static inline void mavlink_msg_esc_status_decode(const mavlink_message_t* msg, mavlink_esc_status_t* esc_status)
  336. {
  337. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  338. esc_status->time_usec = mavlink_msg_esc_status_get_time_usec(msg);
  339. mavlink_msg_esc_status_get_rpm(msg, esc_status->rpm);
  340. mavlink_msg_esc_status_get_voltage(msg, esc_status->voltage);
  341. mavlink_msg_esc_status_get_current(msg, esc_status->current);
  342. esc_status->index = mavlink_msg_esc_status_get_index(msg);
  343. #else
  344. uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ESC_STATUS_LEN;
  345. memset(esc_status, 0, MAVLINK_MSG_ID_ESC_STATUS_LEN);
  346. memcpy(esc_status, _MAV_PAYLOAD(msg), len);
  347. #endif
  348. }