mavlink_msg_wheel_distance.h 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255
  1. #pragma once
  2. // MESSAGE WHEEL_DISTANCE PACKING
  3. #define MAVLINK_MSG_ID_WHEEL_DISTANCE 9000
  4. typedef struct __mavlink_wheel_distance_t {
  5. uint64_t time_usec; /*< [us] Timestamp (synced to UNIX time or since system boot).*/
  6. double distance[16]; /*< [m] Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.*/
  7. uint8_t count; /*< Number of wheels reported.*/
  8. } mavlink_wheel_distance_t;
  9. #define MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN 137
  10. #define MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN 137
  11. #define MAVLINK_MSG_ID_9000_LEN 137
  12. #define MAVLINK_MSG_ID_9000_MIN_LEN 137
  13. #define MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC 113
  14. #define MAVLINK_MSG_ID_9000_CRC 113
  15. #define MAVLINK_MSG_WHEEL_DISTANCE_FIELD_DISTANCE_LEN 16
  16. #if MAVLINK_COMMAND_24BIT
  17. #define MAVLINK_MESSAGE_INFO_WHEEL_DISTANCE { \
  18. 9000, \
  19. "WHEEL_DISTANCE", \
  20. 3, \
  21. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wheel_distance_t, time_usec) }, \
  22. { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 136, offsetof(mavlink_wheel_distance_t, count) }, \
  23. { "distance", NULL, MAVLINK_TYPE_DOUBLE, 16, 8, offsetof(mavlink_wheel_distance_t, distance) }, \
  24. } \
  25. }
  26. #else
  27. #define MAVLINK_MESSAGE_INFO_WHEEL_DISTANCE { \
  28. "WHEEL_DISTANCE", \
  29. 3, \
  30. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wheel_distance_t, time_usec) }, \
  31. { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 136, offsetof(mavlink_wheel_distance_t, count) }, \
  32. { "distance", NULL, MAVLINK_TYPE_DOUBLE, 16, 8, offsetof(mavlink_wheel_distance_t, distance) }, \
  33. } \
  34. }
  35. #endif
  36. /**
  37. * @brief Pack a wheel_distance message
  38. * @param system_id ID of this system
  39. * @param component_id ID of this component (e.g. 200 for IMU)
  40. * @param msg The MAVLink message to compress the data into
  41. *
  42. * @param time_usec [us] Timestamp (synced to UNIX time or since system boot).
  43. * @param count Number of wheels reported.
  44. * @param distance [m] Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.
  45. * @return length of the message in bytes (excluding serial stream start sign)
  46. */
  47. static inline uint16_t mavlink_msg_wheel_distance_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  48. uint64_t time_usec, uint8_t count, const double *distance)
  49. {
  50. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  51. char buf[MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN];
  52. _mav_put_uint64_t(buf, 0, time_usec);
  53. _mav_put_uint8_t(buf, 136, count);
  54. _mav_put_double_array(buf, 8, distance, 16);
  55. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN);
  56. #else
  57. mavlink_wheel_distance_t packet;
  58. packet.time_usec = time_usec;
  59. packet.count = count;
  60. mav_array_memcpy(packet.distance, distance, sizeof(double)*16);
  61. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN);
  62. #endif
  63. msg->msgid = MAVLINK_MSG_ID_WHEEL_DISTANCE;
  64. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC);
  65. }
  66. /**
  67. * @brief Pack a wheel_distance message on a channel
  68. * @param system_id ID of this system
  69. * @param component_id ID of this component (e.g. 200 for IMU)
  70. * @param chan The MAVLink channel this message will be sent over
  71. * @param msg The MAVLink message to compress the data into
  72. * @param time_usec [us] Timestamp (synced to UNIX time or since system boot).
  73. * @param count Number of wheels reported.
  74. * @param distance [m] Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.
  75. * @return length of the message in bytes (excluding serial stream start sign)
  76. */
  77. static inline uint16_t mavlink_msg_wheel_distance_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  78. mavlink_message_t* msg,
  79. uint64_t time_usec,uint8_t count,const double *distance)
  80. {
  81. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  82. char buf[MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN];
  83. _mav_put_uint64_t(buf, 0, time_usec);
  84. _mav_put_uint8_t(buf, 136, count);
  85. _mav_put_double_array(buf, 8, distance, 16);
  86. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN);
  87. #else
  88. mavlink_wheel_distance_t packet;
  89. packet.time_usec = time_usec;
  90. packet.count = count;
  91. mav_array_memcpy(packet.distance, distance, sizeof(double)*16);
  92. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN);
  93. #endif
  94. msg->msgid = MAVLINK_MSG_ID_WHEEL_DISTANCE;
  95. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC);
  96. }
  97. /**
  98. * @brief Encode a wheel_distance struct
  99. *
  100. * @param system_id ID of this system
  101. * @param component_id ID of this component (e.g. 200 for IMU)
  102. * @param msg The MAVLink message to compress the data into
  103. * @param wheel_distance C-struct to read the message contents from
  104. */
  105. static inline uint16_t mavlink_msg_wheel_distance_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wheel_distance_t* wheel_distance)
  106. {
  107. return mavlink_msg_wheel_distance_pack(system_id, component_id, msg, wheel_distance->time_usec, wheel_distance->count, wheel_distance->distance);
  108. }
  109. /**
  110. * @brief Encode a wheel_distance struct on a channel
  111. *
  112. * @param system_id ID of this system
  113. * @param component_id ID of this component (e.g. 200 for IMU)
  114. * @param chan The MAVLink channel this message will be sent over
  115. * @param msg The MAVLink message to compress the data into
  116. * @param wheel_distance C-struct to read the message contents from
  117. */
  118. static inline uint16_t mavlink_msg_wheel_distance_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wheel_distance_t* wheel_distance)
  119. {
  120. return mavlink_msg_wheel_distance_pack_chan(system_id, component_id, chan, msg, wheel_distance->time_usec, wheel_distance->count, wheel_distance->distance);
  121. }
  122. /**
  123. * @brief Send a wheel_distance message
  124. * @param chan MAVLink channel to send the message
  125. *
  126. * @param time_usec [us] Timestamp (synced to UNIX time or since system boot).
  127. * @param count Number of wheels reported.
  128. * @param distance [m] Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.
  129. */
  130. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  131. static inline void mavlink_msg_wheel_distance_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t count, const double *distance)
  132. {
  133. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  134. char buf[MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN];
  135. _mav_put_uint64_t(buf, 0, time_usec);
  136. _mav_put_uint8_t(buf, 136, count);
  137. _mav_put_double_array(buf, 8, distance, 16);
  138. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WHEEL_DISTANCE, buf, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC);
  139. #else
  140. mavlink_wheel_distance_t packet;
  141. packet.time_usec = time_usec;
  142. packet.count = count;
  143. mav_array_memcpy(packet.distance, distance, sizeof(double)*16);
  144. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WHEEL_DISTANCE, (const char *)&packet, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC);
  145. #endif
  146. }
  147. /**
  148. * @brief Send a wheel_distance message
  149. * @param chan MAVLink channel to send the message
  150. * @param struct The MAVLink struct to serialize
  151. */
  152. static inline void mavlink_msg_wheel_distance_send_struct(mavlink_channel_t chan, const mavlink_wheel_distance_t* wheel_distance)
  153. {
  154. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  155. mavlink_msg_wheel_distance_send(chan, wheel_distance->time_usec, wheel_distance->count, wheel_distance->distance);
  156. #else
  157. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WHEEL_DISTANCE, (const char *)wheel_distance, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC);
  158. #endif
  159. }
  160. #if MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  161. /*
  162. This variant of _send() can be used to save stack space by re-using
  163. memory from the receive buffer. The caller provides a
  164. mavlink_message_t which is the size of a full mavlink message. This
  165. is usually the receive buffer for the channel, and allows a reply to an
  166. incoming message with minimum stack space usage.
  167. */
  168. static inline void mavlink_msg_wheel_distance_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t count, const double *distance)
  169. {
  170. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  171. char *buf = (char *)msgbuf;
  172. _mav_put_uint64_t(buf, 0, time_usec);
  173. _mav_put_uint8_t(buf, 136, count);
  174. _mav_put_double_array(buf, 8, distance, 16);
  175. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WHEEL_DISTANCE, buf, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC);
  176. #else
  177. mavlink_wheel_distance_t *packet = (mavlink_wheel_distance_t *)msgbuf;
  178. packet->time_usec = time_usec;
  179. packet->count = count;
  180. mav_array_memcpy(packet->distance, distance, sizeof(double)*16);
  181. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WHEEL_DISTANCE, (const char *)packet, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC);
  182. #endif
  183. }
  184. #endif
  185. #endif
  186. // MESSAGE WHEEL_DISTANCE UNPACKING
  187. /**
  188. * @brief Get field time_usec from wheel_distance message
  189. *
  190. * @return [us] Timestamp (synced to UNIX time or since system boot).
  191. */
  192. static inline uint64_t mavlink_msg_wheel_distance_get_time_usec(const mavlink_message_t* msg)
  193. {
  194. return _MAV_RETURN_uint64_t(msg, 0);
  195. }
  196. /**
  197. * @brief Get field count from wheel_distance message
  198. *
  199. * @return Number of wheels reported.
  200. */
  201. static inline uint8_t mavlink_msg_wheel_distance_get_count(const mavlink_message_t* msg)
  202. {
  203. return _MAV_RETURN_uint8_t(msg, 136);
  204. }
  205. /**
  206. * @brief Get field distance from wheel_distance message
  207. *
  208. * @return [m] Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.
  209. */
  210. static inline uint16_t mavlink_msg_wheel_distance_get_distance(const mavlink_message_t* msg, double *distance)
  211. {
  212. return _MAV_RETURN_double_array(msg, distance, 16, 8);
  213. }
  214. /**
  215. * @brief Decode a wheel_distance message into a struct
  216. *
  217. * @param msg The message to decode
  218. * @param wheel_distance C-struct to decode the message contents into
  219. */
  220. static inline void mavlink_msg_wheel_distance_decode(const mavlink_message_t* msg, mavlink_wheel_distance_t* wheel_distance)
  221. {
  222. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  223. wheel_distance->time_usec = mavlink_msg_wheel_distance_get_time_usec(msg);
  224. mavlink_msg_wheel_distance_get_distance(msg, wheel_distance->distance);
  225. wheel_distance->count = mavlink_msg_wheel_distance_get_count(msg);
  226. #else
  227. uint8_t len = msg->len < MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN? msg->len : MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN;
  228. memset(wheel_distance, 0, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN);
  229. memcpy(wheel_distance, _MAV_PAYLOAD(msg), len);
  230. #endif
  231. }