mavlink_msg_video_stream_status.h 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388
  1. #pragma once
  2. // MESSAGE VIDEO_STREAM_STATUS PACKING
  3. #define MAVLINK_MSG_ID_VIDEO_STREAM_STATUS 270
  4. typedef struct __mavlink_video_stream_status_t {
  5. float framerate; /*< [Hz] Frame rate*/
  6. uint32_t bitrate; /*< [bits/s] Bit rate*/
  7. uint16_t flags; /*< Bitmap of stream status flags*/
  8. uint16_t resolution_h; /*< [pix] Horizontal resolution*/
  9. uint16_t resolution_v; /*< [pix] Vertical resolution*/
  10. uint16_t rotation; /*< [deg] Video image rotation clockwise*/
  11. uint16_t hfov; /*< [deg] Horizontal Field of view*/
  12. uint8_t stream_id; /*< Video Stream ID (1 for first, 2 for second, etc.)*/
  13. } mavlink_video_stream_status_t;
  14. #define MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN 19
  15. #define MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN 19
  16. #define MAVLINK_MSG_ID_270_LEN 19
  17. #define MAVLINK_MSG_ID_270_MIN_LEN 19
  18. #define MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC 59
  19. #define MAVLINK_MSG_ID_270_CRC 59
  20. #if MAVLINK_COMMAND_24BIT
  21. #define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_STATUS { \
  22. 270, \
  23. "VIDEO_STREAM_STATUS", \
  24. 8, \
  25. { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_video_stream_status_t, stream_id) }, \
  26. { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_status_t, flags) }, \
  27. { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_status_t, framerate) }, \
  28. { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_status_t, resolution_h) }, \
  29. { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_status_t, resolution_v) }, \
  30. { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_status_t, bitrate) }, \
  31. { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_video_stream_status_t, rotation) }, \
  32. { "hfov", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_video_stream_status_t, hfov) }, \
  33. } \
  34. }
  35. #else
  36. #define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_STATUS { \
  37. "VIDEO_STREAM_STATUS", \
  38. 8, \
  39. { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_video_stream_status_t, stream_id) }, \
  40. { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_status_t, flags) }, \
  41. { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_status_t, framerate) }, \
  42. { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_status_t, resolution_h) }, \
  43. { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_status_t, resolution_v) }, \
  44. { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_status_t, bitrate) }, \
  45. { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_video_stream_status_t, rotation) }, \
  46. { "hfov", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_video_stream_status_t, hfov) }, \
  47. } \
  48. }
  49. #endif
  50. /**
  51. * @brief Pack a video_stream_status message
  52. * @param system_id ID of this system
  53. * @param component_id ID of this component (e.g. 200 for IMU)
  54. * @param msg The MAVLink message to compress the data into
  55. *
  56. * @param stream_id Video Stream ID (1 for first, 2 for second, etc.)
  57. * @param flags Bitmap of stream status flags
  58. * @param framerate [Hz] Frame rate
  59. * @param resolution_h [pix] Horizontal resolution
  60. * @param resolution_v [pix] Vertical resolution
  61. * @param bitrate [bits/s] Bit rate
  62. * @param rotation [deg] Video image rotation clockwise
  63. * @param hfov [deg] Horizontal Field of view
  64. * @return length of the message in bytes (excluding serial stream start sign)
  65. */
  66. static inline uint16_t mavlink_msg_video_stream_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  67. uint8_t stream_id, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov)
  68. {
  69. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  70. char buf[MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN];
  71. _mav_put_float(buf, 0, framerate);
  72. _mav_put_uint32_t(buf, 4, bitrate);
  73. _mav_put_uint16_t(buf, 8, flags);
  74. _mav_put_uint16_t(buf, 10, resolution_h);
  75. _mav_put_uint16_t(buf, 12, resolution_v);
  76. _mav_put_uint16_t(buf, 14, rotation);
  77. _mav_put_uint16_t(buf, 16, hfov);
  78. _mav_put_uint8_t(buf, 18, stream_id);
  79. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN);
  80. #else
  81. mavlink_video_stream_status_t packet;
  82. packet.framerate = framerate;
  83. packet.bitrate = bitrate;
  84. packet.flags = flags;
  85. packet.resolution_h = resolution_h;
  86. packet.resolution_v = resolution_v;
  87. packet.rotation = rotation;
  88. packet.hfov = hfov;
  89. packet.stream_id = stream_id;
  90. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN);
  91. #endif
  92. msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_STATUS;
  93. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC);
  94. }
  95. /**
  96. * @brief Pack a video_stream_status message on a channel
  97. * @param system_id ID of this system
  98. * @param component_id ID of this component (e.g. 200 for IMU)
  99. * @param chan The MAVLink channel this message will be sent over
  100. * @param msg The MAVLink message to compress the data into
  101. * @param stream_id Video Stream ID (1 for first, 2 for second, etc.)
  102. * @param flags Bitmap of stream status flags
  103. * @param framerate [Hz] Frame rate
  104. * @param resolution_h [pix] Horizontal resolution
  105. * @param resolution_v [pix] Vertical resolution
  106. * @param bitrate [bits/s] Bit rate
  107. * @param rotation [deg] Video image rotation clockwise
  108. * @param hfov [deg] Horizontal Field of view
  109. * @return length of the message in bytes (excluding serial stream start sign)
  110. */
  111. static inline uint16_t mavlink_msg_video_stream_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  112. mavlink_message_t* msg,
  113. uint8_t stream_id,uint16_t flags,float framerate,uint16_t resolution_h,uint16_t resolution_v,uint32_t bitrate,uint16_t rotation,uint16_t hfov)
  114. {
  115. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  116. char buf[MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN];
  117. _mav_put_float(buf, 0, framerate);
  118. _mav_put_uint32_t(buf, 4, bitrate);
  119. _mav_put_uint16_t(buf, 8, flags);
  120. _mav_put_uint16_t(buf, 10, resolution_h);
  121. _mav_put_uint16_t(buf, 12, resolution_v);
  122. _mav_put_uint16_t(buf, 14, rotation);
  123. _mav_put_uint16_t(buf, 16, hfov);
  124. _mav_put_uint8_t(buf, 18, stream_id);
  125. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN);
  126. #else
  127. mavlink_video_stream_status_t packet;
  128. packet.framerate = framerate;
  129. packet.bitrate = bitrate;
  130. packet.flags = flags;
  131. packet.resolution_h = resolution_h;
  132. packet.resolution_v = resolution_v;
  133. packet.rotation = rotation;
  134. packet.hfov = hfov;
  135. packet.stream_id = stream_id;
  136. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN);
  137. #endif
  138. msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_STATUS;
  139. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC);
  140. }
  141. /**
  142. * @brief Encode a video_stream_status struct
  143. *
  144. * @param system_id ID of this system
  145. * @param component_id ID of this component (e.g. 200 for IMU)
  146. * @param msg The MAVLink message to compress the data into
  147. * @param video_stream_status C-struct to read the message contents from
  148. */
  149. static inline uint16_t mavlink_msg_video_stream_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_video_stream_status_t* video_stream_status)
  150. {
  151. return mavlink_msg_video_stream_status_pack(system_id, component_id, msg, video_stream_status->stream_id, video_stream_status->flags, video_stream_status->framerate, video_stream_status->resolution_h, video_stream_status->resolution_v, video_stream_status->bitrate, video_stream_status->rotation, video_stream_status->hfov);
  152. }
  153. /**
  154. * @brief Encode a video_stream_status struct on a channel
  155. *
  156. * @param system_id ID of this system
  157. * @param component_id ID of this component (e.g. 200 for IMU)
  158. * @param chan The MAVLink channel this message will be sent over
  159. * @param msg The MAVLink message to compress the data into
  160. * @param video_stream_status C-struct to read the message contents from
  161. */
  162. static inline uint16_t mavlink_msg_video_stream_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_video_stream_status_t* video_stream_status)
  163. {
  164. return mavlink_msg_video_stream_status_pack_chan(system_id, component_id, chan, msg, video_stream_status->stream_id, video_stream_status->flags, video_stream_status->framerate, video_stream_status->resolution_h, video_stream_status->resolution_v, video_stream_status->bitrate, video_stream_status->rotation, video_stream_status->hfov);
  165. }
  166. /**
  167. * @brief Send a video_stream_status message
  168. * @param chan MAVLink channel to send the message
  169. *
  170. * @param stream_id Video Stream ID (1 for first, 2 for second, etc.)
  171. * @param flags Bitmap of stream status flags
  172. * @param framerate [Hz] Frame rate
  173. * @param resolution_h [pix] Horizontal resolution
  174. * @param resolution_v [pix] Vertical resolution
  175. * @param bitrate [bits/s] Bit rate
  176. * @param rotation [deg] Video image rotation clockwise
  177. * @param hfov [deg] Horizontal Field of view
  178. */
  179. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  180. static inline void mavlink_msg_video_stream_status_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov)
  181. {
  182. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  183. char buf[MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN];
  184. _mav_put_float(buf, 0, framerate);
  185. _mav_put_uint32_t(buf, 4, bitrate);
  186. _mav_put_uint16_t(buf, 8, flags);
  187. _mav_put_uint16_t(buf, 10, resolution_h);
  188. _mav_put_uint16_t(buf, 12, resolution_v);
  189. _mav_put_uint16_t(buf, 14, rotation);
  190. _mav_put_uint16_t(buf, 16, hfov);
  191. _mav_put_uint8_t(buf, 18, stream_id);
  192. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, buf, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC);
  193. #else
  194. mavlink_video_stream_status_t packet;
  195. packet.framerate = framerate;
  196. packet.bitrate = bitrate;
  197. packet.flags = flags;
  198. packet.resolution_h = resolution_h;
  199. packet.resolution_v = resolution_v;
  200. packet.rotation = rotation;
  201. packet.hfov = hfov;
  202. packet.stream_id = stream_id;
  203. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, (const char *)&packet, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC);
  204. #endif
  205. }
  206. /**
  207. * @brief Send a video_stream_status message
  208. * @param chan MAVLink channel to send the message
  209. * @param struct The MAVLink struct to serialize
  210. */
  211. static inline void mavlink_msg_video_stream_status_send_struct(mavlink_channel_t chan, const mavlink_video_stream_status_t* video_stream_status)
  212. {
  213. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  214. mavlink_msg_video_stream_status_send(chan, video_stream_status->stream_id, video_stream_status->flags, video_stream_status->framerate, video_stream_status->resolution_h, video_stream_status->resolution_v, video_stream_status->bitrate, video_stream_status->rotation, video_stream_status->hfov);
  215. #else
  216. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, (const char *)video_stream_status, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC);
  217. #endif
  218. }
  219. #if MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  220. /*
  221. This variant of _send() can be used to save stack space by re-using
  222. memory from the receive buffer. The caller provides a
  223. mavlink_message_t which is the size of a full mavlink message. This
  224. is usually the receive buffer for the channel, and allows a reply to an
  225. incoming message with minimum stack space usage.
  226. */
  227. static inline void mavlink_msg_video_stream_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stream_id, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov)
  228. {
  229. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  230. char *buf = (char *)msgbuf;
  231. _mav_put_float(buf, 0, framerate);
  232. _mav_put_uint32_t(buf, 4, bitrate);
  233. _mav_put_uint16_t(buf, 8, flags);
  234. _mav_put_uint16_t(buf, 10, resolution_h);
  235. _mav_put_uint16_t(buf, 12, resolution_v);
  236. _mav_put_uint16_t(buf, 14, rotation);
  237. _mav_put_uint16_t(buf, 16, hfov);
  238. _mav_put_uint8_t(buf, 18, stream_id);
  239. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, buf, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC);
  240. #else
  241. mavlink_video_stream_status_t *packet = (mavlink_video_stream_status_t *)msgbuf;
  242. packet->framerate = framerate;
  243. packet->bitrate = bitrate;
  244. packet->flags = flags;
  245. packet->resolution_h = resolution_h;
  246. packet->resolution_v = resolution_v;
  247. packet->rotation = rotation;
  248. packet->hfov = hfov;
  249. packet->stream_id = stream_id;
  250. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, (const char *)packet, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC);
  251. #endif
  252. }
  253. #endif
  254. #endif
  255. // MESSAGE VIDEO_STREAM_STATUS UNPACKING
  256. /**
  257. * @brief Get field stream_id from video_stream_status message
  258. *
  259. * @return Video Stream ID (1 for first, 2 for second, etc.)
  260. */
  261. static inline uint8_t mavlink_msg_video_stream_status_get_stream_id(const mavlink_message_t* msg)
  262. {
  263. return _MAV_RETURN_uint8_t(msg, 18);
  264. }
  265. /**
  266. * @brief Get field flags from video_stream_status message
  267. *
  268. * @return Bitmap of stream status flags
  269. */
  270. static inline uint16_t mavlink_msg_video_stream_status_get_flags(const mavlink_message_t* msg)
  271. {
  272. return _MAV_RETURN_uint16_t(msg, 8);
  273. }
  274. /**
  275. * @brief Get field framerate from video_stream_status message
  276. *
  277. * @return [Hz] Frame rate
  278. */
  279. static inline float mavlink_msg_video_stream_status_get_framerate(const mavlink_message_t* msg)
  280. {
  281. return _MAV_RETURN_float(msg, 0);
  282. }
  283. /**
  284. * @brief Get field resolution_h from video_stream_status message
  285. *
  286. * @return [pix] Horizontal resolution
  287. */
  288. static inline uint16_t mavlink_msg_video_stream_status_get_resolution_h(const mavlink_message_t* msg)
  289. {
  290. return _MAV_RETURN_uint16_t(msg, 10);
  291. }
  292. /**
  293. * @brief Get field resolution_v from video_stream_status message
  294. *
  295. * @return [pix] Vertical resolution
  296. */
  297. static inline uint16_t mavlink_msg_video_stream_status_get_resolution_v(const mavlink_message_t* msg)
  298. {
  299. return _MAV_RETURN_uint16_t(msg, 12);
  300. }
  301. /**
  302. * @brief Get field bitrate from video_stream_status message
  303. *
  304. * @return [bits/s] Bit rate
  305. */
  306. static inline uint32_t mavlink_msg_video_stream_status_get_bitrate(const mavlink_message_t* msg)
  307. {
  308. return _MAV_RETURN_uint32_t(msg, 4);
  309. }
  310. /**
  311. * @brief Get field rotation from video_stream_status message
  312. *
  313. * @return [deg] Video image rotation clockwise
  314. */
  315. static inline uint16_t mavlink_msg_video_stream_status_get_rotation(const mavlink_message_t* msg)
  316. {
  317. return _MAV_RETURN_uint16_t(msg, 14);
  318. }
  319. /**
  320. * @brief Get field hfov from video_stream_status message
  321. *
  322. * @return [deg] Horizontal Field of view
  323. */
  324. static inline uint16_t mavlink_msg_video_stream_status_get_hfov(const mavlink_message_t* msg)
  325. {
  326. return _MAV_RETURN_uint16_t(msg, 16);
  327. }
  328. /**
  329. * @brief Decode a video_stream_status message into a struct
  330. *
  331. * @param msg The message to decode
  332. * @param video_stream_status C-struct to decode the message contents into
  333. */
  334. static inline void mavlink_msg_video_stream_status_decode(const mavlink_message_t* msg, mavlink_video_stream_status_t* video_stream_status)
  335. {
  336. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  337. video_stream_status->framerate = mavlink_msg_video_stream_status_get_framerate(msg);
  338. video_stream_status->bitrate = mavlink_msg_video_stream_status_get_bitrate(msg);
  339. video_stream_status->flags = mavlink_msg_video_stream_status_get_flags(msg);
  340. video_stream_status->resolution_h = mavlink_msg_video_stream_status_get_resolution_h(msg);
  341. video_stream_status->resolution_v = mavlink_msg_video_stream_status_get_resolution_v(msg);
  342. video_stream_status->rotation = mavlink_msg_video_stream_status_get_rotation(msg);
  343. video_stream_status->hfov = mavlink_msg_video_stream_status_get_hfov(msg);
  344. video_stream_status->stream_id = mavlink_msg_video_stream_status_get_stream_id(msg);
  345. #else
  346. uint8_t len = msg->len < MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN? msg->len : MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN;
  347. memset(video_stream_status, 0, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN);
  348. memcpy(video_stream_status, _MAV_PAYLOAD(msg), len);
  349. #endif
  350. }