mavlink_msg_optical_flow.h 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438
  1. #pragma once
  2. // MESSAGE OPTICAL_FLOW PACKING
  3. #define MAVLINK_MSG_ID_OPTICAL_FLOW 100
  4. MAVPACKED(
  5. typedef struct __mavlink_optical_flow_t {
  6. uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
  7. float flow_comp_m_x; /*< [m/s] Flow in x-sensor direction, angular-speed compensated*/
  8. float flow_comp_m_y; /*< [m/s] Flow in y-sensor direction, angular-speed compensated*/
  9. float ground_distance; /*< [m] Ground distance. Positive value: distance known. Negative value: Unknown distance*/
  10. int16_t flow_x; /*< [dpix] Flow in x-sensor direction*/
  11. int16_t flow_y; /*< [dpix] Flow in y-sensor direction*/
  12. uint8_t sensor_id; /*< Sensor ID*/
  13. uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/
  14. float flow_rate_x; /*< [rad/s] Flow rate about X axis*/
  15. float flow_rate_y; /*< [rad/s] Flow rate about Y axis*/
  16. }) mavlink_optical_flow_t;
  17. #define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 34
  18. #define MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN 26
  19. #define MAVLINK_MSG_ID_100_LEN 34
  20. #define MAVLINK_MSG_ID_100_MIN_LEN 26
  21. #define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175
  22. #define MAVLINK_MSG_ID_100_CRC 175
  23. #if MAVLINK_COMMAND_24BIT
  24. #define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
  25. 100, \
  26. "OPTICAL_FLOW", \
  27. 10, \
  28. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
  29. { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
  30. { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \
  31. { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \
  32. { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \
  33. { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
  34. { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \
  35. { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \
  36. { "flow_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_optical_flow_t, flow_rate_x) }, \
  37. { "flow_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_optical_flow_t, flow_rate_y) }, \
  38. } \
  39. }
  40. #else
  41. #define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
  42. "OPTICAL_FLOW", \
  43. 10, \
  44. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
  45. { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
  46. { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \
  47. { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \
  48. { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \
  49. { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
  50. { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \
  51. { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \
  52. { "flow_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_optical_flow_t, flow_rate_x) }, \
  53. { "flow_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_optical_flow_t, flow_rate_y) }, \
  54. } \
  55. }
  56. #endif
  57. /**
  58. * @brief Pack a optical_flow message
  59. * @param system_id ID of this system
  60. * @param component_id ID of this component (e.g. 200 for IMU)
  61. * @param msg The MAVLink message to compress the data into
  62. *
  63. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  64. * @param sensor_id Sensor ID
  65. * @param flow_x [dpix] Flow in x-sensor direction
  66. * @param flow_y [dpix] Flow in y-sensor direction
  67. * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated
  68. * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
  69. * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
  70. * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
  71. * @param flow_rate_x [rad/s] Flow rate about X axis
  72. * @param flow_rate_y [rad/s] Flow rate about Y axis
  73. * @return length of the message in bytes (excluding serial stream start sign)
  74. */
  75. static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  76. uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance, float flow_rate_x, float flow_rate_y)
  77. {
  78. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  79. char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
  80. _mav_put_uint64_t(buf, 0, time_usec);
  81. _mav_put_float(buf, 8, flow_comp_m_x);
  82. _mav_put_float(buf, 12, flow_comp_m_y);
  83. _mav_put_float(buf, 16, ground_distance);
  84. _mav_put_int16_t(buf, 20, flow_x);
  85. _mav_put_int16_t(buf, 22, flow_y);
  86. _mav_put_uint8_t(buf, 24, sensor_id);
  87. _mav_put_uint8_t(buf, 25, quality);
  88. _mav_put_float(buf, 26, flow_rate_x);
  89. _mav_put_float(buf, 30, flow_rate_y);
  90. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
  91. #else
  92. mavlink_optical_flow_t packet;
  93. packet.time_usec = time_usec;
  94. packet.flow_comp_m_x = flow_comp_m_x;
  95. packet.flow_comp_m_y = flow_comp_m_y;
  96. packet.ground_distance = ground_distance;
  97. packet.flow_x = flow_x;
  98. packet.flow_y = flow_y;
  99. packet.sensor_id = sensor_id;
  100. packet.quality = quality;
  101. packet.flow_rate_x = flow_rate_x;
  102. packet.flow_rate_y = flow_rate_y;
  103. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
  104. #endif
  105. msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
  106. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
  107. }
  108. /**
  109. * @brief Pack a optical_flow message on a channel
  110. * @param system_id ID of this system
  111. * @param component_id ID of this component (e.g. 200 for IMU)
  112. * @param chan The MAVLink channel this message will be sent over
  113. * @param msg The MAVLink message to compress the data into
  114. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  115. * @param sensor_id Sensor ID
  116. * @param flow_x [dpix] Flow in x-sensor direction
  117. * @param flow_y [dpix] Flow in y-sensor direction
  118. * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated
  119. * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
  120. * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
  121. * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
  122. * @param flow_rate_x [rad/s] Flow rate about X axis
  123. * @param flow_rate_y [rad/s] Flow rate about Y axis
  124. * @return length of the message in bytes (excluding serial stream start sign)
  125. */
  126. static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  127. mavlink_message_t* msg,
  128. uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance,float flow_rate_x,float flow_rate_y)
  129. {
  130. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  131. char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
  132. _mav_put_uint64_t(buf, 0, time_usec);
  133. _mav_put_float(buf, 8, flow_comp_m_x);
  134. _mav_put_float(buf, 12, flow_comp_m_y);
  135. _mav_put_float(buf, 16, ground_distance);
  136. _mav_put_int16_t(buf, 20, flow_x);
  137. _mav_put_int16_t(buf, 22, flow_y);
  138. _mav_put_uint8_t(buf, 24, sensor_id);
  139. _mav_put_uint8_t(buf, 25, quality);
  140. _mav_put_float(buf, 26, flow_rate_x);
  141. _mav_put_float(buf, 30, flow_rate_y);
  142. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
  143. #else
  144. mavlink_optical_flow_t packet;
  145. packet.time_usec = time_usec;
  146. packet.flow_comp_m_x = flow_comp_m_x;
  147. packet.flow_comp_m_y = flow_comp_m_y;
  148. packet.ground_distance = ground_distance;
  149. packet.flow_x = flow_x;
  150. packet.flow_y = flow_y;
  151. packet.sensor_id = sensor_id;
  152. packet.quality = quality;
  153. packet.flow_rate_x = flow_rate_x;
  154. packet.flow_rate_y = flow_rate_y;
  155. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
  156. #endif
  157. msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
  158. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
  159. }
  160. /**
  161. * @brief Encode a optical_flow 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 optical_flow C-struct to read the message contents from
  167. */
  168. static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
  169. {
  170. return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y);
  171. }
  172. /**
  173. * @brief Encode a optical_flow struct on a channel
  174. *
  175. * @param system_id ID of this system
  176. * @param component_id ID of this component (e.g. 200 for IMU)
  177. * @param chan The MAVLink channel this message will be sent over
  178. * @param msg The MAVLink message to compress the data into
  179. * @param optical_flow C-struct to read the message contents from
  180. */
  181. static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
  182. {
  183. return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y);
  184. }
  185. /**
  186. * @brief Send a optical_flow message
  187. * @param chan MAVLink channel to send the message
  188. *
  189. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  190. * @param sensor_id Sensor ID
  191. * @param flow_x [dpix] Flow in x-sensor direction
  192. * @param flow_y [dpix] Flow in y-sensor direction
  193. * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated
  194. * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
  195. * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
  196. * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
  197. * @param flow_rate_x [rad/s] Flow rate about X axis
  198. * @param flow_rate_y [rad/s] Flow rate about Y axis
  199. */
  200. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  201. static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance, float flow_rate_x, float flow_rate_y)
  202. {
  203. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  204. char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
  205. _mav_put_uint64_t(buf, 0, time_usec);
  206. _mav_put_float(buf, 8, flow_comp_m_x);
  207. _mav_put_float(buf, 12, flow_comp_m_y);
  208. _mav_put_float(buf, 16, ground_distance);
  209. _mav_put_int16_t(buf, 20, flow_x);
  210. _mav_put_int16_t(buf, 22, flow_y);
  211. _mav_put_uint8_t(buf, 24, sensor_id);
  212. _mav_put_uint8_t(buf, 25, quality);
  213. _mav_put_float(buf, 26, flow_rate_x);
  214. _mav_put_float(buf, 30, flow_rate_y);
  215. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
  216. #else
  217. mavlink_optical_flow_t packet;
  218. packet.time_usec = time_usec;
  219. packet.flow_comp_m_x = flow_comp_m_x;
  220. packet.flow_comp_m_y = flow_comp_m_y;
  221. packet.ground_distance = ground_distance;
  222. packet.flow_x = flow_x;
  223. packet.flow_y = flow_y;
  224. packet.sensor_id = sensor_id;
  225. packet.quality = quality;
  226. packet.flow_rate_x = flow_rate_x;
  227. packet.flow_rate_y = flow_rate_y;
  228. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
  229. #endif
  230. }
  231. /**
  232. * @brief Send a optical_flow message
  233. * @param chan MAVLink channel to send the message
  234. * @param struct The MAVLink struct to serialize
  235. */
  236. static inline void mavlink_msg_optical_flow_send_struct(mavlink_channel_t chan, const mavlink_optical_flow_t* optical_flow)
  237. {
  238. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  239. mavlink_msg_optical_flow_send(chan, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y);
  240. #else
  241. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)optical_flow, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
  242. #endif
  243. }
  244. #if MAVLINK_MSG_ID_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  245. /*
  246. This variant of _send() can be used to save stack space by re-using
  247. memory from the receive buffer. The caller provides a
  248. mavlink_message_t which is the size of a full mavlink message. This
  249. is usually the receive buffer for the channel, and allows a reply to an
  250. incoming message with minimum stack space usage.
  251. */
  252. static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance, float flow_rate_x, float flow_rate_y)
  253. {
  254. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  255. char *buf = (char *)msgbuf;
  256. _mav_put_uint64_t(buf, 0, time_usec);
  257. _mav_put_float(buf, 8, flow_comp_m_x);
  258. _mav_put_float(buf, 12, flow_comp_m_y);
  259. _mav_put_float(buf, 16, ground_distance);
  260. _mav_put_int16_t(buf, 20, flow_x);
  261. _mav_put_int16_t(buf, 22, flow_y);
  262. _mav_put_uint8_t(buf, 24, sensor_id);
  263. _mav_put_uint8_t(buf, 25, quality);
  264. _mav_put_float(buf, 26, flow_rate_x);
  265. _mav_put_float(buf, 30, flow_rate_y);
  266. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
  267. #else
  268. mavlink_optical_flow_t *packet = (mavlink_optical_flow_t *)msgbuf;
  269. packet->time_usec = time_usec;
  270. packet->flow_comp_m_x = flow_comp_m_x;
  271. packet->flow_comp_m_y = flow_comp_m_y;
  272. packet->ground_distance = ground_distance;
  273. packet->flow_x = flow_x;
  274. packet->flow_y = flow_y;
  275. packet->sensor_id = sensor_id;
  276. packet->quality = quality;
  277. packet->flow_rate_x = flow_rate_x;
  278. packet->flow_rate_y = flow_rate_y;
  279. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
  280. #endif
  281. }
  282. #endif
  283. #endif
  284. // MESSAGE OPTICAL_FLOW UNPACKING
  285. /**
  286. * @brief Get field time_usec from optical_flow message
  287. *
  288. * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  289. */
  290. static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg)
  291. {
  292. return _MAV_RETURN_uint64_t(msg, 0);
  293. }
  294. /**
  295. * @brief Get field sensor_id from optical_flow message
  296. *
  297. * @return Sensor ID
  298. */
  299. static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg)
  300. {
  301. return _MAV_RETURN_uint8_t(msg, 24);
  302. }
  303. /**
  304. * @brief Get field flow_x from optical_flow message
  305. *
  306. * @return [dpix] Flow in x-sensor direction
  307. */
  308. static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg)
  309. {
  310. return _MAV_RETURN_int16_t(msg, 20);
  311. }
  312. /**
  313. * @brief Get field flow_y from optical_flow message
  314. *
  315. * @return [dpix] Flow in y-sensor direction
  316. */
  317. static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg)
  318. {
  319. return _MAV_RETURN_int16_t(msg, 22);
  320. }
  321. /**
  322. * @brief Get field flow_comp_m_x from optical_flow message
  323. *
  324. * @return [m/s] Flow in x-sensor direction, angular-speed compensated
  325. */
  326. static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg)
  327. {
  328. return _MAV_RETURN_float(msg, 8);
  329. }
  330. /**
  331. * @brief Get field flow_comp_m_y from optical_flow message
  332. *
  333. * @return [m/s] Flow in y-sensor direction, angular-speed compensated
  334. */
  335. static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg)
  336. {
  337. return _MAV_RETURN_float(msg, 12);
  338. }
  339. /**
  340. * @brief Get field quality from optical_flow message
  341. *
  342. * @return Optical flow quality / confidence. 0: bad, 255: maximum quality
  343. */
  344. static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg)
  345. {
  346. return _MAV_RETURN_uint8_t(msg, 25);
  347. }
  348. /**
  349. * @brief Get field ground_distance from optical_flow message
  350. *
  351. * @return [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
  352. */
  353. static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg)
  354. {
  355. return _MAV_RETURN_float(msg, 16);
  356. }
  357. /**
  358. * @brief Get field flow_rate_x from optical_flow message
  359. *
  360. * @return [rad/s] Flow rate about X axis
  361. */
  362. static inline float mavlink_msg_optical_flow_get_flow_rate_x(const mavlink_message_t* msg)
  363. {
  364. return _MAV_RETURN_float(msg, 26);
  365. }
  366. /**
  367. * @brief Get field flow_rate_y from optical_flow message
  368. *
  369. * @return [rad/s] Flow rate about Y axis
  370. */
  371. static inline float mavlink_msg_optical_flow_get_flow_rate_y(const mavlink_message_t* msg)
  372. {
  373. return _MAV_RETURN_float(msg, 30);
  374. }
  375. /**
  376. * @brief Decode a optical_flow message into a struct
  377. *
  378. * @param msg The message to decode
  379. * @param optical_flow C-struct to decode the message contents into
  380. */
  381. static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow)
  382. {
  383. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  384. optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg);
  385. optical_flow->flow_comp_m_x = mavlink_msg_optical_flow_get_flow_comp_m_x(msg);
  386. optical_flow->flow_comp_m_y = mavlink_msg_optical_flow_get_flow_comp_m_y(msg);
  387. optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg);
  388. optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg);
  389. optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg);
  390. optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg);
  391. optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg);
  392. optical_flow->flow_rate_x = mavlink_msg_optical_flow_get_flow_rate_x(msg);
  393. optical_flow->flow_rate_y = mavlink_msg_optical_flow_get_flow_rate_y(msg);
  394. #else
  395. uint8_t len = msg->len < MAVLINK_MSG_ID_OPTICAL_FLOW_LEN? msg->len : MAVLINK_MSG_ID_OPTICAL_FLOW_LEN;
  396. memset(optical_flow, 0, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
  397. memcpy(optical_flow, _MAV_PAYLOAD(msg), len);
  398. #endif
  399. }