mavlink_msg_video_stream_status.h 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456
  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
  97. * @param system_id ID of this system
  98. * @param component_id ID of this component (e.g. 200 for IMU)
  99. * @param status MAVLink status structure
  100. * @param msg The MAVLink message to compress the data into
  101. *
  102. * @param stream_id Video Stream ID (1 for first, 2 for second, etc.)
  103. * @param flags Bitmap of stream status flags
  104. * @param framerate [Hz] Frame rate
  105. * @param resolution_h [pix] Horizontal resolution
  106. * @param resolution_v [pix] Vertical resolution
  107. * @param bitrate [bits/s] Bit rate
  108. * @param rotation [deg] Video image rotation clockwise
  109. * @param hfov [deg] Horizontal Field of view
  110. * @return length of the message in bytes (excluding serial stream start sign)
  111. */
  112. static inline uint16_t mavlink_msg_video_stream_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  140. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC);
  141. #else
  142. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN);
  143. #endif
  144. }
  145. /**
  146. * @brief Pack a video_stream_status message on a channel
  147. * @param system_id ID of this system
  148. * @param component_id ID of this component (e.g. 200 for IMU)
  149. * @param chan The MAVLink channel this message will be sent over
  150. * @param msg The MAVLink message to compress the data into
  151. * @param stream_id Video Stream ID (1 for first, 2 for second, etc.)
  152. * @param flags Bitmap of stream status flags
  153. * @param framerate [Hz] Frame rate
  154. * @param resolution_h [pix] Horizontal resolution
  155. * @param resolution_v [pix] Vertical resolution
  156. * @param bitrate [bits/s] Bit rate
  157. * @param rotation [deg] Video image rotation clockwise
  158. * @param hfov [deg] Horizontal Field of view
  159. * @return length of the message in bytes (excluding serial stream start sign)
  160. */
  161. static inline uint16_t mavlink_msg_video_stream_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  162. mavlink_message_t* msg,
  163. 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)
  164. {
  165. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  166. char buf[MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN];
  167. _mav_put_float(buf, 0, framerate);
  168. _mav_put_uint32_t(buf, 4, bitrate);
  169. _mav_put_uint16_t(buf, 8, flags);
  170. _mav_put_uint16_t(buf, 10, resolution_h);
  171. _mav_put_uint16_t(buf, 12, resolution_v);
  172. _mav_put_uint16_t(buf, 14, rotation);
  173. _mav_put_uint16_t(buf, 16, hfov);
  174. _mav_put_uint8_t(buf, 18, stream_id);
  175. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN);
  176. #else
  177. mavlink_video_stream_status_t packet;
  178. packet.framerate = framerate;
  179. packet.bitrate = bitrate;
  180. packet.flags = flags;
  181. packet.resolution_h = resolution_h;
  182. packet.resolution_v = resolution_v;
  183. packet.rotation = rotation;
  184. packet.hfov = hfov;
  185. packet.stream_id = stream_id;
  186. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN);
  187. #endif
  188. msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_STATUS;
  189. 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);
  190. }
  191. /**
  192. * @brief Encode a video_stream_status struct
  193. *
  194. * @param system_id ID of this system
  195. * @param component_id ID of this component (e.g. 200 for IMU)
  196. * @param msg The MAVLink message to compress the data into
  197. * @param video_stream_status C-struct to read the message contents from
  198. */
  199. 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)
  200. {
  201. 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);
  202. }
  203. /**
  204. * @brief Encode a video_stream_status struct on a channel
  205. *
  206. * @param system_id ID of this system
  207. * @param component_id ID of this component (e.g. 200 for IMU)
  208. * @param chan The MAVLink channel this message will be sent over
  209. * @param msg The MAVLink message to compress the data into
  210. * @param video_stream_status C-struct to read the message contents from
  211. */
  212. 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)
  213. {
  214. 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);
  215. }
  216. /**
  217. * @brief Encode a video_stream_status struct with provided status structure
  218. *
  219. * @param system_id ID of this system
  220. * @param component_id ID of this component (e.g. 200 for IMU)
  221. * @param status MAVLink status structure
  222. * @param msg The MAVLink message to compress the data into
  223. * @param video_stream_status C-struct to read the message contents from
  224. */
  225. static inline uint16_t mavlink_msg_video_stream_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_video_stream_status_t* video_stream_status)
  226. {
  227. return mavlink_msg_video_stream_status_pack_status(system_id, component_id, _status, 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);
  228. }
  229. /**
  230. * @brief Send a video_stream_status message
  231. * @param chan MAVLink channel to send the message
  232. *
  233. * @param stream_id Video Stream ID (1 for first, 2 for second, etc.)
  234. * @param flags Bitmap of stream status flags
  235. * @param framerate [Hz] Frame rate
  236. * @param resolution_h [pix] Horizontal resolution
  237. * @param resolution_v [pix] Vertical resolution
  238. * @param bitrate [bits/s] Bit rate
  239. * @param rotation [deg] Video image rotation clockwise
  240. * @param hfov [deg] Horizontal Field of view
  241. */
  242. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  243. 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)
  244. {
  245. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  246. char buf[MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN];
  247. _mav_put_float(buf, 0, framerate);
  248. _mav_put_uint32_t(buf, 4, bitrate);
  249. _mav_put_uint16_t(buf, 8, flags);
  250. _mav_put_uint16_t(buf, 10, resolution_h);
  251. _mav_put_uint16_t(buf, 12, resolution_v);
  252. _mav_put_uint16_t(buf, 14, rotation);
  253. _mav_put_uint16_t(buf, 16, hfov);
  254. _mav_put_uint8_t(buf, 18, stream_id);
  255. _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);
  256. #else
  257. mavlink_video_stream_status_t packet;
  258. packet.framerate = framerate;
  259. packet.bitrate = bitrate;
  260. packet.flags = flags;
  261. packet.resolution_h = resolution_h;
  262. packet.resolution_v = resolution_v;
  263. packet.rotation = rotation;
  264. packet.hfov = hfov;
  265. packet.stream_id = stream_id;
  266. _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);
  267. #endif
  268. }
  269. /**
  270. * @brief Send a video_stream_status message
  271. * @param chan MAVLink channel to send the message
  272. * @param struct The MAVLink struct to serialize
  273. */
  274. static inline void mavlink_msg_video_stream_status_send_struct(mavlink_channel_t chan, const mavlink_video_stream_status_t* video_stream_status)
  275. {
  276. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  277. 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);
  278. #else
  279. _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);
  280. #endif
  281. }
  282. #if MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  283. /*
  284. This variant of _send() can be used to save stack space by re-using
  285. memory from the receive buffer. The caller provides a
  286. mavlink_message_t which is the size of a full mavlink message. This
  287. is usually the receive buffer for the channel, and allows a reply to an
  288. incoming message with minimum stack space usage.
  289. */
  290. 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)
  291. {
  292. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  293. char *buf = (char *)msgbuf;
  294. _mav_put_float(buf, 0, framerate);
  295. _mav_put_uint32_t(buf, 4, bitrate);
  296. _mav_put_uint16_t(buf, 8, flags);
  297. _mav_put_uint16_t(buf, 10, resolution_h);
  298. _mav_put_uint16_t(buf, 12, resolution_v);
  299. _mav_put_uint16_t(buf, 14, rotation);
  300. _mav_put_uint16_t(buf, 16, hfov);
  301. _mav_put_uint8_t(buf, 18, stream_id);
  302. _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);
  303. #else
  304. mavlink_video_stream_status_t *packet = (mavlink_video_stream_status_t *)msgbuf;
  305. packet->framerate = framerate;
  306. packet->bitrate = bitrate;
  307. packet->flags = flags;
  308. packet->resolution_h = resolution_h;
  309. packet->resolution_v = resolution_v;
  310. packet->rotation = rotation;
  311. packet->hfov = hfov;
  312. packet->stream_id = stream_id;
  313. _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);
  314. #endif
  315. }
  316. #endif
  317. #endif
  318. // MESSAGE VIDEO_STREAM_STATUS UNPACKING
  319. /**
  320. * @brief Get field stream_id from video_stream_status message
  321. *
  322. * @return Video Stream ID (1 for first, 2 for second, etc.)
  323. */
  324. static inline uint8_t mavlink_msg_video_stream_status_get_stream_id(const mavlink_message_t* msg)
  325. {
  326. return _MAV_RETURN_uint8_t(msg, 18);
  327. }
  328. /**
  329. * @brief Get field flags from video_stream_status message
  330. *
  331. * @return Bitmap of stream status flags
  332. */
  333. static inline uint16_t mavlink_msg_video_stream_status_get_flags(const mavlink_message_t* msg)
  334. {
  335. return _MAV_RETURN_uint16_t(msg, 8);
  336. }
  337. /**
  338. * @brief Get field framerate from video_stream_status message
  339. *
  340. * @return [Hz] Frame rate
  341. */
  342. static inline float mavlink_msg_video_stream_status_get_framerate(const mavlink_message_t* msg)
  343. {
  344. return _MAV_RETURN_float(msg, 0);
  345. }
  346. /**
  347. * @brief Get field resolution_h from video_stream_status message
  348. *
  349. * @return [pix] Horizontal resolution
  350. */
  351. static inline uint16_t mavlink_msg_video_stream_status_get_resolution_h(const mavlink_message_t* msg)
  352. {
  353. return _MAV_RETURN_uint16_t(msg, 10);
  354. }
  355. /**
  356. * @brief Get field resolution_v from video_stream_status message
  357. *
  358. * @return [pix] Vertical resolution
  359. */
  360. static inline uint16_t mavlink_msg_video_stream_status_get_resolution_v(const mavlink_message_t* msg)
  361. {
  362. return _MAV_RETURN_uint16_t(msg, 12);
  363. }
  364. /**
  365. * @brief Get field bitrate from video_stream_status message
  366. *
  367. * @return [bits/s] Bit rate
  368. */
  369. static inline uint32_t mavlink_msg_video_stream_status_get_bitrate(const mavlink_message_t* msg)
  370. {
  371. return _MAV_RETURN_uint32_t(msg, 4);
  372. }
  373. /**
  374. * @brief Get field rotation from video_stream_status message
  375. *
  376. * @return [deg] Video image rotation clockwise
  377. */
  378. static inline uint16_t mavlink_msg_video_stream_status_get_rotation(const mavlink_message_t* msg)
  379. {
  380. return _MAV_RETURN_uint16_t(msg, 14);
  381. }
  382. /**
  383. * @brief Get field hfov from video_stream_status message
  384. *
  385. * @return [deg] Horizontal Field of view
  386. */
  387. static inline uint16_t mavlink_msg_video_stream_status_get_hfov(const mavlink_message_t* msg)
  388. {
  389. return _MAV_RETURN_uint16_t(msg, 16);
  390. }
  391. /**
  392. * @brief Decode a video_stream_status message into a struct
  393. *
  394. * @param msg The message to decode
  395. * @param video_stream_status C-struct to decode the message contents into
  396. */
  397. static inline void mavlink_msg_video_stream_status_decode(const mavlink_message_t* msg, mavlink_video_stream_status_t* video_stream_status)
  398. {
  399. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  400. video_stream_status->framerate = mavlink_msg_video_stream_status_get_framerate(msg);
  401. video_stream_status->bitrate = mavlink_msg_video_stream_status_get_bitrate(msg);
  402. video_stream_status->flags = mavlink_msg_video_stream_status_get_flags(msg);
  403. video_stream_status->resolution_h = mavlink_msg_video_stream_status_get_resolution_h(msg);
  404. video_stream_status->resolution_v = mavlink_msg_video_stream_status_get_resolution_v(msg);
  405. video_stream_status->rotation = mavlink_msg_video_stream_status_get_rotation(msg);
  406. video_stream_status->hfov = mavlink_msg_video_stream_status_get_hfov(msg);
  407. video_stream_status->stream_id = mavlink_msg_video_stream_status_get_stream_id(msg);
  408. #else
  409. uint8_t len = msg->len < MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN? msg->len : MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN;
  410. memset(video_stream_status, 0, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN);
  411. memcpy(video_stream_status, _MAV_PAYLOAD(msg), len);
  412. #endif
  413. }