mavlink_msg_distance_sensor.h 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480
  1. #pragma once
  2. // MESSAGE DISTANCE_SENSOR PACKING
  3. #define MAVLINK_MSG_ID_DISTANCE_SENSOR 132
  4. MAVPACKED(
  5. typedef struct __mavlink_distance_sensor_t {
  6. uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
  7. uint16_t min_distance; /*< [cm] Minimum distance the sensor can measure*/
  8. uint16_t max_distance; /*< [cm] Maximum distance the sensor can measure*/
  9. uint16_t current_distance; /*< [cm] Current distance reading*/
  10. uint8_t type; /*< Type of distance sensor.*/
  11. uint8_t id; /*< Onboard ID of the sensor*/
  12. uint8_t orientation; /*< Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270*/
  13. uint8_t covariance; /*< [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.*/
  14. float horizontal_fov; /*< [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.*/
  15. float vertical_fov; /*< [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.*/
  16. float quaternion[4]; /*< Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."*/
  17. uint8_t signal_quality; /*< [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.*/
  18. }) mavlink_distance_sensor_t;
  19. #define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 39
  20. #define MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN 14
  21. #define MAVLINK_MSG_ID_132_LEN 39
  22. #define MAVLINK_MSG_ID_132_MIN_LEN 14
  23. #define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85
  24. #define MAVLINK_MSG_ID_132_CRC 85
  25. #define MAVLINK_MSG_DISTANCE_SENSOR_FIELD_QUATERNION_LEN 4
  26. #if MAVLINK_COMMAND_24BIT
  27. #define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \
  28. 132, \
  29. "DISTANCE_SENSOR", \
  30. 12, \
  31. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \
  32. { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \
  33. { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \
  34. { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \
  35. { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \
  36. { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \
  37. { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \
  38. { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \
  39. { "horizontal_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_distance_sensor_t, horizontal_fov) }, \
  40. { "vertical_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_distance_sensor_t, vertical_fov) }, \
  41. { "quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 22, offsetof(mavlink_distance_sensor_t, quaternion) }, \
  42. { "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_distance_sensor_t, signal_quality) }, \
  43. } \
  44. }
  45. #else
  46. #define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \
  47. "DISTANCE_SENSOR", \
  48. 12, \
  49. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \
  50. { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \
  51. { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \
  52. { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \
  53. { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \
  54. { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \
  55. { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \
  56. { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \
  57. { "horizontal_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_distance_sensor_t, horizontal_fov) }, \
  58. { "vertical_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_distance_sensor_t, vertical_fov) }, \
  59. { "quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 22, offsetof(mavlink_distance_sensor_t, quaternion) }, \
  60. { "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_distance_sensor_t, signal_quality) }, \
  61. } \
  62. }
  63. #endif
  64. /**
  65. * @brief Pack a distance_sensor message
  66. * @param system_id ID of this system
  67. * @param component_id ID of this component (e.g. 200 for IMU)
  68. * @param msg The MAVLink message to compress the data into
  69. *
  70. * @param time_boot_ms [ms] Timestamp (time since system boot).
  71. * @param min_distance [cm] Minimum distance the sensor can measure
  72. * @param max_distance [cm] Maximum distance the sensor can measure
  73. * @param current_distance [cm] Current distance reading
  74. * @param type Type of distance sensor.
  75. * @param id Onboard ID of the sensor
  76. * @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
  77. * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
  78. * @param horizontal_fov [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
  79. * @param vertical_fov [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
  80. * @param quaternion Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."
  81. * @param signal_quality [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.
  82. * @return length of the message in bytes (excluding serial stream start sign)
  83. */
  84. static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  85. uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance, float horizontal_fov, float vertical_fov, const float *quaternion, uint8_t signal_quality)
  86. {
  87. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  88. char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
  89. _mav_put_uint32_t(buf, 0, time_boot_ms);
  90. _mav_put_uint16_t(buf, 4, min_distance);
  91. _mav_put_uint16_t(buf, 6, max_distance);
  92. _mav_put_uint16_t(buf, 8, current_distance);
  93. _mav_put_uint8_t(buf, 10, type);
  94. _mav_put_uint8_t(buf, 11, id);
  95. _mav_put_uint8_t(buf, 12, orientation);
  96. _mav_put_uint8_t(buf, 13, covariance);
  97. _mav_put_float(buf, 14, horizontal_fov);
  98. _mav_put_float(buf, 18, vertical_fov);
  99. _mav_put_uint8_t(buf, 38, signal_quality);
  100. _mav_put_float_array(buf, 22, quaternion, 4);
  101. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
  102. #else
  103. mavlink_distance_sensor_t packet;
  104. packet.time_boot_ms = time_boot_ms;
  105. packet.min_distance = min_distance;
  106. packet.max_distance = max_distance;
  107. packet.current_distance = current_distance;
  108. packet.type = type;
  109. packet.id = id;
  110. packet.orientation = orientation;
  111. packet.covariance = covariance;
  112. packet.horizontal_fov = horizontal_fov;
  113. packet.vertical_fov = vertical_fov;
  114. packet.signal_quality = signal_quality;
  115. mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
  116. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
  117. #endif
  118. msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR;
  119. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
  120. }
  121. /**
  122. * @brief Pack a distance_sensor message on a channel
  123. * @param system_id ID of this system
  124. * @param component_id ID of this component (e.g. 200 for IMU)
  125. * @param chan The MAVLink channel this message will be sent over
  126. * @param msg The MAVLink message to compress the data into
  127. * @param time_boot_ms [ms] Timestamp (time since system boot).
  128. * @param min_distance [cm] Minimum distance the sensor can measure
  129. * @param max_distance [cm] Maximum distance the sensor can measure
  130. * @param current_distance [cm] Current distance reading
  131. * @param type Type of distance sensor.
  132. * @param id Onboard ID of the sensor
  133. * @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
  134. * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
  135. * @param horizontal_fov [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
  136. * @param vertical_fov [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
  137. * @param quaternion Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."
  138. * @param signal_quality [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.
  139. * @return length of the message in bytes (excluding serial stream start sign)
  140. */
  141. static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  142. mavlink_message_t* msg,
  143. uint32_t time_boot_ms,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t type,uint8_t id,uint8_t orientation,uint8_t covariance,float horizontal_fov,float vertical_fov,const float *quaternion,uint8_t signal_quality)
  144. {
  145. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  146. char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
  147. _mav_put_uint32_t(buf, 0, time_boot_ms);
  148. _mav_put_uint16_t(buf, 4, min_distance);
  149. _mav_put_uint16_t(buf, 6, max_distance);
  150. _mav_put_uint16_t(buf, 8, current_distance);
  151. _mav_put_uint8_t(buf, 10, type);
  152. _mav_put_uint8_t(buf, 11, id);
  153. _mav_put_uint8_t(buf, 12, orientation);
  154. _mav_put_uint8_t(buf, 13, covariance);
  155. _mav_put_float(buf, 14, horizontal_fov);
  156. _mav_put_float(buf, 18, vertical_fov);
  157. _mav_put_uint8_t(buf, 38, signal_quality);
  158. _mav_put_float_array(buf, 22, quaternion, 4);
  159. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
  160. #else
  161. mavlink_distance_sensor_t packet;
  162. packet.time_boot_ms = time_boot_ms;
  163. packet.min_distance = min_distance;
  164. packet.max_distance = max_distance;
  165. packet.current_distance = current_distance;
  166. packet.type = type;
  167. packet.id = id;
  168. packet.orientation = orientation;
  169. packet.covariance = covariance;
  170. packet.horizontal_fov = horizontal_fov;
  171. packet.vertical_fov = vertical_fov;
  172. packet.signal_quality = signal_quality;
  173. mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
  174. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
  175. #endif
  176. msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR;
  177. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
  178. }
  179. /**
  180. * @brief Encode a distance_sensor struct
  181. *
  182. * @param system_id ID of this system
  183. * @param component_id ID of this component (e.g. 200 for IMU)
  184. * @param msg The MAVLink message to compress the data into
  185. * @param distance_sensor C-struct to read the message contents from
  186. */
  187. static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor)
  188. {
  189. return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance, distance_sensor->horizontal_fov, distance_sensor->vertical_fov, distance_sensor->quaternion, distance_sensor->signal_quality);
  190. }
  191. /**
  192. * @brief Encode a distance_sensor struct on a channel
  193. *
  194. * @param system_id ID of this system
  195. * @param component_id ID of this component (e.g. 200 for IMU)
  196. * @param chan The MAVLink channel this message will be sent over
  197. * @param msg The MAVLink message to compress the data into
  198. * @param distance_sensor C-struct to read the message contents from
  199. */
  200. static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor)
  201. {
  202. return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance, distance_sensor->horizontal_fov, distance_sensor->vertical_fov, distance_sensor->quaternion, distance_sensor->signal_quality);
  203. }
  204. /**
  205. * @brief Send a distance_sensor message
  206. * @param chan MAVLink channel to send the message
  207. *
  208. * @param time_boot_ms [ms] Timestamp (time since system boot).
  209. * @param min_distance [cm] Minimum distance the sensor can measure
  210. * @param max_distance [cm] Maximum distance the sensor can measure
  211. * @param current_distance [cm] Current distance reading
  212. * @param type Type of distance sensor.
  213. * @param id Onboard ID of the sensor
  214. * @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
  215. * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
  216. * @param horizontal_fov [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
  217. * @param vertical_fov [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
  218. * @param quaternion Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."
  219. * @param signal_quality [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.
  220. */
  221. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  222. static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance, float horizontal_fov, float vertical_fov, const float *quaternion, uint8_t signal_quality)
  223. {
  224. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  225. char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
  226. _mav_put_uint32_t(buf, 0, time_boot_ms);
  227. _mav_put_uint16_t(buf, 4, min_distance);
  228. _mav_put_uint16_t(buf, 6, max_distance);
  229. _mav_put_uint16_t(buf, 8, current_distance);
  230. _mav_put_uint8_t(buf, 10, type);
  231. _mav_put_uint8_t(buf, 11, id);
  232. _mav_put_uint8_t(buf, 12, orientation);
  233. _mav_put_uint8_t(buf, 13, covariance);
  234. _mav_put_float(buf, 14, horizontal_fov);
  235. _mav_put_float(buf, 18, vertical_fov);
  236. _mav_put_uint8_t(buf, 38, signal_quality);
  237. _mav_put_float_array(buf, 22, quaternion, 4);
  238. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
  239. #else
  240. mavlink_distance_sensor_t packet;
  241. packet.time_boot_ms = time_boot_ms;
  242. packet.min_distance = min_distance;
  243. packet.max_distance = max_distance;
  244. packet.current_distance = current_distance;
  245. packet.type = type;
  246. packet.id = id;
  247. packet.orientation = orientation;
  248. packet.covariance = covariance;
  249. packet.horizontal_fov = horizontal_fov;
  250. packet.vertical_fov = vertical_fov;
  251. packet.signal_quality = signal_quality;
  252. mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
  253. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
  254. #endif
  255. }
  256. /**
  257. * @brief Send a distance_sensor message
  258. * @param chan MAVLink channel to send the message
  259. * @param struct The MAVLink struct to serialize
  260. */
  261. static inline void mavlink_msg_distance_sensor_send_struct(mavlink_channel_t chan, const mavlink_distance_sensor_t* distance_sensor)
  262. {
  263. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  264. mavlink_msg_distance_sensor_send(chan, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance, distance_sensor->horizontal_fov, distance_sensor->vertical_fov, distance_sensor->quaternion, distance_sensor->signal_quality);
  265. #else
  266. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)distance_sensor, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
  267. #endif
  268. }
  269. #if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  270. /*
  271. This variant of _send() can be used to save stack space by re-using
  272. memory from the receive buffer. The caller provides a
  273. mavlink_message_t which is the size of a full mavlink message. This
  274. is usually the receive buffer for the channel, and allows a reply to an
  275. incoming message with minimum stack space usage.
  276. */
  277. static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance, float horizontal_fov, float vertical_fov, const float *quaternion, uint8_t signal_quality)
  278. {
  279. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  280. char *buf = (char *)msgbuf;
  281. _mav_put_uint32_t(buf, 0, time_boot_ms);
  282. _mav_put_uint16_t(buf, 4, min_distance);
  283. _mav_put_uint16_t(buf, 6, max_distance);
  284. _mav_put_uint16_t(buf, 8, current_distance);
  285. _mav_put_uint8_t(buf, 10, type);
  286. _mav_put_uint8_t(buf, 11, id);
  287. _mav_put_uint8_t(buf, 12, orientation);
  288. _mav_put_uint8_t(buf, 13, covariance);
  289. _mav_put_float(buf, 14, horizontal_fov);
  290. _mav_put_float(buf, 18, vertical_fov);
  291. _mav_put_uint8_t(buf, 38, signal_quality);
  292. _mav_put_float_array(buf, 22, quaternion, 4);
  293. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
  294. #else
  295. mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf;
  296. packet->time_boot_ms = time_boot_ms;
  297. packet->min_distance = min_distance;
  298. packet->max_distance = max_distance;
  299. packet->current_distance = current_distance;
  300. packet->type = type;
  301. packet->id = id;
  302. packet->orientation = orientation;
  303. packet->covariance = covariance;
  304. packet->horizontal_fov = horizontal_fov;
  305. packet->vertical_fov = vertical_fov;
  306. packet->signal_quality = signal_quality;
  307. mav_array_memcpy(packet->quaternion, quaternion, sizeof(float)*4);
  308. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
  309. #endif
  310. }
  311. #endif
  312. #endif
  313. // MESSAGE DISTANCE_SENSOR UNPACKING
  314. /**
  315. * @brief Get field time_boot_ms from distance_sensor message
  316. *
  317. * @return [ms] Timestamp (time since system boot).
  318. */
  319. static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg)
  320. {
  321. return _MAV_RETURN_uint32_t(msg, 0);
  322. }
  323. /**
  324. * @brief Get field min_distance from distance_sensor message
  325. *
  326. * @return [cm] Minimum distance the sensor can measure
  327. */
  328. static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg)
  329. {
  330. return _MAV_RETURN_uint16_t(msg, 4);
  331. }
  332. /**
  333. * @brief Get field max_distance from distance_sensor message
  334. *
  335. * @return [cm] Maximum distance the sensor can measure
  336. */
  337. static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg)
  338. {
  339. return _MAV_RETURN_uint16_t(msg, 6);
  340. }
  341. /**
  342. * @brief Get field current_distance from distance_sensor message
  343. *
  344. * @return [cm] Current distance reading
  345. */
  346. static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg)
  347. {
  348. return _MAV_RETURN_uint16_t(msg, 8);
  349. }
  350. /**
  351. * @brief Get field type from distance_sensor message
  352. *
  353. * @return Type of distance sensor.
  354. */
  355. static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg)
  356. {
  357. return _MAV_RETURN_uint8_t(msg, 10);
  358. }
  359. /**
  360. * @brief Get field id from distance_sensor message
  361. *
  362. * @return Onboard ID of the sensor
  363. */
  364. static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg)
  365. {
  366. return _MAV_RETURN_uint8_t(msg, 11);
  367. }
  368. /**
  369. * @brief Get field orientation from distance_sensor message
  370. *
  371. * @return Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
  372. */
  373. static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg)
  374. {
  375. return _MAV_RETURN_uint8_t(msg, 12);
  376. }
  377. /**
  378. * @brief Get field covariance from distance_sensor message
  379. *
  380. * @return [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
  381. */
  382. static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg)
  383. {
  384. return _MAV_RETURN_uint8_t(msg, 13);
  385. }
  386. /**
  387. * @brief Get field horizontal_fov from distance_sensor message
  388. *
  389. * @return [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
  390. */
  391. static inline float mavlink_msg_distance_sensor_get_horizontal_fov(const mavlink_message_t* msg)
  392. {
  393. return _MAV_RETURN_float(msg, 14);
  394. }
  395. /**
  396. * @brief Get field vertical_fov from distance_sensor message
  397. *
  398. * @return [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
  399. */
  400. static inline float mavlink_msg_distance_sensor_get_vertical_fov(const mavlink_message_t* msg)
  401. {
  402. return _MAV_RETURN_float(msg, 18);
  403. }
  404. /**
  405. * @brief Get field quaternion from distance_sensor message
  406. *
  407. * @return Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."
  408. */
  409. static inline uint16_t mavlink_msg_distance_sensor_get_quaternion(const mavlink_message_t* msg, float *quaternion)
  410. {
  411. return _MAV_RETURN_float_array(msg, quaternion, 4, 22);
  412. }
  413. /**
  414. * @brief Get field signal_quality from distance_sensor message
  415. *
  416. * @return [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.
  417. */
  418. static inline uint8_t mavlink_msg_distance_sensor_get_signal_quality(const mavlink_message_t* msg)
  419. {
  420. return _MAV_RETURN_uint8_t(msg, 38);
  421. }
  422. /**
  423. * @brief Decode a distance_sensor message into a struct
  424. *
  425. * @param msg The message to decode
  426. * @param distance_sensor C-struct to decode the message contents into
  427. */
  428. static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor)
  429. {
  430. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  431. distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg);
  432. distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg);
  433. distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg);
  434. distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg);
  435. distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg);
  436. distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg);
  437. distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg);
  438. distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg);
  439. distance_sensor->horizontal_fov = mavlink_msg_distance_sensor_get_horizontal_fov(msg);
  440. distance_sensor->vertical_fov = mavlink_msg_distance_sensor_get_vertical_fov(msg);
  441. mavlink_msg_distance_sensor_get_quaternion(msg, distance_sensor->quaternion);
  442. distance_sensor->signal_quality = mavlink_msg_distance_sensor_get_signal_quality(msg);
  443. #else
  444. uint8_t len = msg->len < MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN;
  445. memset(distance_sensor, 0, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
  446. memcpy(distance_sensor, _MAV_PAYLOAD(msg), len);
  447. #endif
  448. }