mavlink_msg_distance_sensor.h 32 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558
  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
  123. * @param system_id ID of this system
  124. * @param component_id ID of this component (e.g. 200 for IMU)
  125. * @param status MAVLink status structure
  126. * @param msg The MAVLink message to compress the data into
  127. *
  128. * @param time_boot_ms [ms] Timestamp (time since system boot).
  129. * @param min_distance [cm] Minimum distance the sensor can measure
  130. * @param max_distance [cm] Maximum distance the sensor can measure
  131. * @param current_distance [cm] Current distance reading
  132. * @param type Type of distance sensor.
  133. * @param id Onboard ID of the sensor
  134. * @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
  135. * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
  136. * @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.
  137. * @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.
  138. * @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."
  139. * @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.
  140. * @return length of the message in bytes (excluding serial stream start sign)
  141. */
  142. static inline uint16_t mavlink_msg_distance_sensor_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  178. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
  179. #else
  180. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
  181. #endif
  182. }
  183. /**
  184. * @brief Pack a distance_sensor message on a channel
  185. * @param system_id ID of this system
  186. * @param component_id ID of this component (e.g. 200 for IMU)
  187. * @param chan The MAVLink channel this message will be sent over
  188. * @param msg The MAVLink message to compress the data into
  189. * @param time_boot_ms [ms] Timestamp (time since system boot).
  190. * @param min_distance [cm] Minimum distance the sensor can measure
  191. * @param max_distance [cm] Maximum distance the sensor can measure
  192. * @param current_distance [cm] Current distance reading
  193. * @param type Type of distance sensor.
  194. * @param id Onboard ID of the sensor
  195. * @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
  196. * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
  197. * @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.
  198. * @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.
  199. * @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."
  200. * @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.
  201. * @return length of the message in bytes (excluding serial stream start sign)
  202. */
  203. static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  204. mavlink_message_t* msg,
  205. 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)
  206. {
  207. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  208. char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
  209. _mav_put_uint32_t(buf, 0, time_boot_ms);
  210. _mav_put_uint16_t(buf, 4, min_distance);
  211. _mav_put_uint16_t(buf, 6, max_distance);
  212. _mav_put_uint16_t(buf, 8, current_distance);
  213. _mav_put_uint8_t(buf, 10, type);
  214. _mav_put_uint8_t(buf, 11, id);
  215. _mav_put_uint8_t(buf, 12, orientation);
  216. _mav_put_uint8_t(buf, 13, covariance);
  217. _mav_put_float(buf, 14, horizontal_fov);
  218. _mav_put_float(buf, 18, vertical_fov);
  219. _mav_put_uint8_t(buf, 38, signal_quality);
  220. _mav_put_float_array(buf, 22, quaternion, 4);
  221. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
  222. #else
  223. mavlink_distance_sensor_t packet;
  224. packet.time_boot_ms = time_boot_ms;
  225. packet.min_distance = min_distance;
  226. packet.max_distance = max_distance;
  227. packet.current_distance = current_distance;
  228. packet.type = type;
  229. packet.id = id;
  230. packet.orientation = orientation;
  231. packet.covariance = covariance;
  232. packet.horizontal_fov = horizontal_fov;
  233. packet.vertical_fov = vertical_fov;
  234. packet.signal_quality = signal_quality;
  235. mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
  236. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
  237. #endif
  238. msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR;
  239. 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);
  240. }
  241. /**
  242. * @brief Encode a distance_sensor struct
  243. *
  244. * @param system_id ID of this system
  245. * @param component_id ID of this component (e.g. 200 for IMU)
  246. * @param msg The MAVLink message to compress the data into
  247. * @param distance_sensor C-struct to read the message contents from
  248. */
  249. 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)
  250. {
  251. 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);
  252. }
  253. /**
  254. * @brief Encode a distance_sensor struct on a channel
  255. *
  256. * @param system_id ID of this system
  257. * @param component_id ID of this component (e.g. 200 for IMU)
  258. * @param chan The MAVLink channel this message will be sent over
  259. * @param msg The MAVLink message to compress the data into
  260. * @param distance_sensor C-struct to read the message contents from
  261. */
  262. 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)
  263. {
  264. 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);
  265. }
  266. /**
  267. * @brief Encode a distance_sensor struct with provided status structure
  268. *
  269. * @param system_id ID of this system
  270. * @param component_id ID of this component (e.g. 200 for IMU)
  271. * @param status MAVLink status structure
  272. * @param msg The MAVLink message to compress the data into
  273. * @param distance_sensor C-struct to read the message contents from
  274. */
  275. static inline uint16_t mavlink_msg_distance_sensor_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor)
  276. {
  277. return mavlink_msg_distance_sensor_pack_status(system_id, component_id, _status, 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);
  278. }
  279. /**
  280. * @brief Send a distance_sensor message
  281. * @param chan MAVLink channel to send the message
  282. *
  283. * @param time_boot_ms [ms] Timestamp (time since system boot).
  284. * @param min_distance [cm] Minimum distance the sensor can measure
  285. * @param max_distance [cm] Maximum distance the sensor can measure
  286. * @param current_distance [cm] Current distance reading
  287. * @param type Type of distance sensor.
  288. * @param id Onboard ID of the sensor
  289. * @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
  290. * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
  291. * @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.
  292. * @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.
  293. * @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."
  294. * @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.
  295. */
  296. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  297. 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)
  298. {
  299. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  300. char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
  301. _mav_put_uint32_t(buf, 0, time_boot_ms);
  302. _mav_put_uint16_t(buf, 4, min_distance);
  303. _mav_put_uint16_t(buf, 6, max_distance);
  304. _mav_put_uint16_t(buf, 8, current_distance);
  305. _mav_put_uint8_t(buf, 10, type);
  306. _mav_put_uint8_t(buf, 11, id);
  307. _mav_put_uint8_t(buf, 12, orientation);
  308. _mav_put_uint8_t(buf, 13, covariance);
  309. _mav_put_float(buf, 14, horizontal_fov);
  310. _mav_put_float(buf, 18, vertical_fov);
  311. _mav_put_uint8_t(buf, 38, signal_quality);
  312. _mav_put_float_array(buf, 22, quaternion, 4);
  313. _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);
  314. #else
  315. mavlink_distance_sensor_t packet;
  316. packet.time_boot_ms = time_boot_ms;
  317. packet.min_distance = min_distance;
  318. packet.max_distance = max_distance;
  319. packet.current_distance = current_distance;
  320. packet.type = type;
  321. packet.id = id;
  322. packet.orientation = orientation;
  323. packet.covariance = covariance;
  324. packet.horizontal_fov = horizontal_fov;
  325. packet.vertical_fov = vertical_fov;
  326. packet.signal_quality = signal_quality;
  327. mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
  328. _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);
  329. #endif
  330. }
  331. /**
  332. * @brief Send a distance_sensor message
  333. * @param chan MAVLink channel to send the message
  334. * @param struct The MAVLink struct to serialize
  335. */
  336. static inline void mavlink_msg_distance_sensor_send_struct(mavlink_channel_t chan, const mavlink_distance_sensor_t* distance_sensor)
  337. {
  338. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  339. 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);
  340. #else
  341. _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);
  342. #endif
  343. }
  344. #if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  345. /*
  346. This variant of _send() can be used to save stack space by re-using
  347. memory from the receive buffer. The caller provides a
  348. mavlink_message_t which is the size of a full mavlink message. This
  349. is usually the receive buffer for the channel, and allows a reply to an
  350. incoming message with minimum stack space usage.
  351. */
  352. 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)
  353. {
  354. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  355. char *buf = (char *)msgbuf;
  356. _mav_put_uint32_t(buf, 0, time_boot_ms);
  357. _mav_put_uint16_t(buf, 4, min_distance);
  358. _mav_put_uint16_t(buf, 6, max_distance);
  359. _mav_put_uint16_t(buf, 8, current_distance);
  360. _mav_put_uint8_t(buf, 10, type);
  361. _mav_put_uint8_t(buf, 11, id);
  362. _mav_put_uint8_t(buf, 12, orientation);
  363. _mav_put_uint8_t(buf, 13, covariance);
  364. _mav_put_float(buf, 14, horizontal_fov);
  365. _mav_put_float(buf, 18, vertical_fov);
  366. _mav_put_uint8_t(buf, 38, signal_quality);
  367. _mav_put_float_array(buf, 22, quaternion, 4);
  368. _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);
  369. #else
  370. mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf;
  371. packet->time_boot_ms = time_boot_ms;
  372. packet->min_distance = min_distance;
  373. packet->max_distance = max_distance;
  374. packet->current_distance = current_distance;
  375. packet->type = type;
  376. packet->id = id;
  377. packet->orientation = orientation;
  378. packet->covariance = covariance;
  379. packet->horizontal_fov = horizontal_fov;
  380. packet->vertical_fov = vertical_fov;
  381. packet->signal_quality = signal_quality;
  382. mav_array_memcpy(packet->quaternion, quaternion, sizeof(float)*4);
  383. _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);
  384. #endif
  385. }
  386. #endif
  387. #endif
  388. // MESSAGE DISTANCE_SENSOR UNPACKING
  389. /**
  390. * @brief Get field time_boot_ms from distance_sensor message
  391. *
  392. * @return [ms] Timestamp (time since system boot).
  393. */
  394. static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg)
  395. {
  396. return _MAV_RETURN_uint32_t(msg, 0);
  397. }
  398. /**
  399. * @brief Get field min_distance from distance_sensor message
  400. *
  401. * @return [cm] Minimum distance the sensor can measure
  402. */
  403. static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg)
  404. {
  405. return _MAV_RETURN_uint16_t(msg, 4);
  406. }
  407. /**
  408. * @brief Get field max_distance from distance_sensor message
  409. *
  410. * @return [cm] Maximum distance the sensor can measure
  411. */
  412. static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg)
  413. {
  414. return _MAV_RETURN_uint16_t(msg, 6);
  415. }
  416. /**
  417. * @brief Get field current_distance from distance_sensor message
  418. *
  419. * @return [cm] Current distance reading
  420. */
  421. static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg)
  422. {
  423. return _MAV_RETURN_uint16_t(msg, 8);
  424. }
  425. /**
  426. * @brief Get field type from distance_sensor message
  427. *
  428. * @return Type of distance sensor.
  429. */
  430. static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg)
  431. {
  432. return _MAV_RETURN_uint8_t(msg, 10);
  433. }
  434. /**
  435. * @brief Get field id from distance_sensor message
  436. *
  437. * @return Onboard ID of the sensor
  438. */
  439. static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg)
  440. {
  441. return _MAV_RETURN_uint8_t(msg, 11);
  442. }
  443. /**
  444. * @brief Get field orientation from distance_sensor message
  445. *
  446. * @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
  447. */
  448. static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg)
  449. {
  450. return _MAV_RETURN_uint8_t(msg, 12);
  451. }
  452. /**
  453. * @brief Get field covariance from distance_sensor message
  454. *
  455. * @return [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
  456. */
  457. static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg)
  458. {
  459. return _MAV_RETURN_uint8_t(msg, 13);
  460. }
  461. /**
  462. * @brief Get field horizontal_fov from distance_sensor message
  463. *
  464. * @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.
  465. */
  466. static inline float mavlink_msg_distance_sensor_get_horizontal_fov(const mavlink_message_t* msg)
  467. {
  468. return _MAV_RETURN_float(msg, 14);
  469. }
  470. /**
  471. * @brief Get field vertical_fov from distance_sensor message
  472. *
  473. * @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.
  474. */
  475. static inline float mavlink_msg_distance_sensor_get_vertical_fov(const mavlink_message_t* msg)
  476. {
  477. return _MAV_RETURN_float(msg, 18);
  478. }
  479. /**
  480. * @brief Get field quaternion from distance_sensor message
  481. *
  482. * @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."
  483. */
  484. static inline uint16_t mavlink_msg_distance_sensor_get_quaternion(const mavlink_message_t* msg, float *quaternion)
  485. {
  486. return _MAV_RETURN_float_array(msg, quaternion, 4, 22);
  487. }
  488. /**
  489. * @brief Get field signal_quality from distance_sensor message
  490. *
  491. * @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.
  492. */
  493. static inline uint8_t mavlink_msg_distance_sensor_get_signal_quality(const mavlink_message_t* msg)
  494. {
  495. return _MAV_RETURN_uint8_t(msg, 38);
  496. }
  497. /**
  498. * @brief Decode a distance_sensor message into a struct
  499. *
  500. * @param msg The message to decode
  501. * @param distance_sensor C-struct to decode the message contents into
  502. */
  503. static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor)
  504. {
  505. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  506. distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg);
  507. distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg);
  508. distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg);
  509. distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg);
  510. distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg);
  511. distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg);
  512. distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg);
  513. distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg);
  514. distance_sensor->horizontal_fov = mavlink_msg_distance_sensor_get_horizontal_fov(msg);
  515. distance_sensor->vertical_fov = mavlink_msg_distance_sensor_get_vertical_fov(msg);
  516. mavlink_msg_distance_sensor_get_quaternion(msg, distance_sensor->quaternion);
  517. distance_sensor->signal_quality = mavlink_msg_distance_sensor_get_signal_quality(msg);
  518. #else
  519. uint8_t len = msg->len < MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN;
  520. memset(distance_sensor, 0, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
  521. memcpy(distance_sensor, _MAV_PAYLOAD(msg), len);
  522. #endif
  523. }