mavlink_msg_video_stream_information.h 23 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481
  1. #pragma once
  2. // MESSAGE VIDEO_STREAM_INFORMATION PACKING
  3. #define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION 269
  4. typedef struct __mavlink_video_stream_information_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. uint8_t count; /*< Number of streams available.*/
  14. uint8_t type; /*< Type of stream.*/
  15. char name[32]; /*< Stream name.*/
  16. char uri[160]; /*< Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).*/
  17. } mavlink_video_stream_information_t;
  18. #define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN 213
  19. #define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN 213
  20. #define MAVLINK_MSG_ID_269_LEN 213
  21. #define MAVLINK_MSG_ID_269_MIN_LEN 213
  22. #define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC 109
  23. #define MAVLINK_MSG_ID_269_CRC 109
  24. #define MAVLINK_MSG_VIDEO_STREAM_INFORMATION_FIELD_NAME_LEN 32
  25. #define MAVLINK_MSG_VIDEO_STREAM_INFORMATION_FIELD_URI_LEN 160
  26. #if MAVLINK_COMMAND_24BIT
  27. #define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION { \
  28. 269, \
  29. "VIDEO_STREAM_INFORMATION", \
  30. 12, \
  31. { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_video_stream_information_t, stream_id) }, \
  32. { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_video_stream_information_t, count) }, \
  33. { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_video_stream_information_t, type) }, \
  34. { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_information_t, flags) }, \
  35. { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_information_t, framerate) }, \
  36. { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_information_t, resolution_h) }, \
  37. { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_information_t, resolution_v) }, \
  38. { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_information_t, bitrate) }, \
  39. { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_video_stream_information_t, rotation) }, \
  40. { "hfov", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_video_stream_information_t, hfov) }, \
  41. { "name", NULL, MAVLINK_TYPE_CHAR, 32, 21, offsetof(mavlink_video_stream_information_t, name) }, \
  42. { "uri", NULL, MAVLINK_TYPE_CHAR, 160, 53, offsetof(mavlink_video_stream_information_t, uri) }, \
  43. } \
  44. }
  45. #else
  46. #define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION { \
  47. "VIDEO_STREAM_INFORMATION", \
  48. 12, \
  49. { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_video_stream_information_t, stream_id) }, \
  50. { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_video_stream_information_t, count) }, \
  51. { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_video_stream_information_t, type) }, \
  52. { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_information_t, flags) }, \
  53. { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_information_t, framerate) }, \
  54. { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_information_t, resolution_h) }, \
  55. { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_information_t, resolution_v) }, \
  56. { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_information_t, bitrate) }, \
  57. { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_video_stream_information_t, rotation) }, \
  58. { "hfov", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_video_stream_information_t, hfov) }, \
  59. { "name", NULL, MAVLINK_TYPE_CHAR, 32, 21, offsetof(mavlink_video_stream_information_t, name) }, \
  60. { "uri", NULL, MAVLINK_TYPE_CHAR, 160, 53, offsetof(mavlink_video_stream_information_t, uri) }, \
  61. } \
  62. }
  63. #endif
  64. /**
  65. * @brief Pack a video_stream_information 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 stream_id Video Stream ID (1 for first, 2 for second, etc.)
  71. * @param count Number of streams available.
  72. * @param type Type of stream.
  73. * @param flags Bitmap of stream status flags.
  74. * @param framerate [Hz] Frame rate.
  75. * @param resolution_h [pix] Horizontal resolution.
  76. * @param resolution_v [pix] Vertical resolution.
  77. * @param bitrate [bits/s] Bit rate.
  78. * @param rotation [deg] Video image rotation clockwise.
  79. * @param hfov [deg] Horizontal Field of view.
  80. * @param name Stream name.
  81. * @param uri Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).
  82. * @return length of the message in bytes (excluding serial stream start sign)
  83. */
  84. static inline uint16_t mavlink_msg_video_stream_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  85. uint8_t stream_id, uint8_t count, uint8_t type, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov, const char *name, const char *uri)
  86. {
  87. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  88. char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN];
  89. _mav_put_float(buf, 0, framerate);
  90. _mav_put_uint32_t(buf, 4, bitrate);
  91. _mav_put_uint16_t(buf, 8, flags);
  92. _mav_put_uint16_t(buf, 10, resolution_h);
  93. _mav_put_uint16_t(buf, 12, resolution_v);
  94. _mav_put_uint16_t(buf, 14, rotation);
  95. _mav_put_uint16_t(buf, 16, hfov);
  96. _mav_put_uint8_t(buf, 18, stream_id);
  97. _mav_put_uint8_t(buf, 19, count);
  98. _mav_put_uint8_t(buf, 20, type);
  99. _mav_put_char_array(buf, 21, name, 32);
  100. _mav_put_char_array(buf, 53, uri, 160);
  101. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN);
  102. #else
  103. mavlink_video_stream_information_t packet;
  104. packet.framerate = framerate;
  105. packet.bitrate = bitrate;
  106. packet.flags = flags;
  107. packet.resolution_h = resolution_h;
  108. packet.resolution_v = resolution_v;
  109. packet.rotation = rotation;
  110. packet.hfov = hfov;
  111. packet.stream_id = stream_id;
  112. packet.count = count;
  113. packet.type = type;
  114. mav_array_memcpy(packet.name, name, sizeof(char)*32);
  115. mav_array_memcpy(packet.uri, uri, sizeof(char)*160);
  116. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN);
  117. #endif
  118. msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION;
  119. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC);
  120. }
  121. /**
  122. * @brief Pack a video_stream_information message on a channel
  123. * @param system_id ID of this system
  124. * @param component_id ID of this component (e.g. 200 for IMU)
  125. * @param chan The MAVLink channel this message will be sent over
  126. * @param msg The MAVLink message to compress the data into
  127. * @param stream_id Video Stream ID (1 for first, 2 for second, etc.)
  128. * @param count Number of streams available.
  129. * @param type Type of stream.
  130. * @param flags Bitmap of stream status flags.
  131. * @param framerate [Hz] Frame rate.
  132. * @param resolution_h [pix] Horizontal resolution.
  133. * @param resolution_v [pix] Vertical resolution.
  134. * @param bitrate [bits/s] Bit rate.
  135. * @param rotation [deg] Video image rotation clockwise.
  136. * @param hfov [deg] Horizontal Field of view.
  137. * @param name Stream name.
  138. * @param uri Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).
  139. * @return length of the message in bytes (excluding serial stream start sign)
  140. */
  141. static inline uint16_t mavlink_msg_video_stream_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  142. mavlink_message_t* msg,
  143. uint8_t stream_id,uint8_t count,uint8_t type,uint16_t flags,float framerate,uint16_t resolution_h,uint16_t resolution_v,uint32_t bitrate,uint16_t rotation,uint16_t hfov,const char *name,const char *uri)
  144. {
  145. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  146. char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN];
  147. _mav_put_float(buf, 0, framerate);
  148. _mav_put_uint32_t(buf, 4, bitrate);
  149. _mav_put_uint16_t(buf, 8, flags);
  150. _mav_put_uint16_t(buf, 10, resolution_h);
  151. _mav_put_uint16_t(buf, 12, resolution_v);
  152. _mav_put_uint16_t(buf, 14, rotation);
  153. _mav_put_uint16_t(buf, 16, hfov);
  154. _mav_put_uint8_t(buf, 18, stream_id);
  155. _mav_put_uint8_t(buf, 19, count);
  156. _mav_put_uint8_t(buf, 20, type);
  157. _mav_put_char_array(buf, 21, name, 32);
  158. _mav_put_char_array(buf, 53, uri, 160);
  159. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN);
  160. #else
  161. mavlink_video_stream_information_t packet;
  162. packet.framerate = framerate;
  163. packet.bitrate = bitrate;
  164. packet.flags = flags;
  165. packet.resolution_h = resolution_h;
  166. packet.resolution_v = resolution_v;
  167. packet.rotation = rotation;
  168. packet.hfov = hfov;
  169. packet.stream_id = stream_id;
  170. packet.count = count;
  171. packet.type = type;
  172. mav_array_memcpy(packet.name, name, sizeof(char)*32);
  173. mav_array_memcpy(packet.uri, uri, sizeof(char)*160);
  174. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN);
  175. #endif
  176. msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION;
  177. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC);
  178. }
  179. /**
  180. * @brief Encode a video_stream_information struct
  181. *
  182. * @param system_id ID of this system
  183. * @param component_id ID of this component (e.g. 200 for IMU)
  184. * @param msg The MAVLink message to compress the data into
  185. * @param video_stream_information C-struct to read the message contents from
  186. */
  187. static inline uint16_t mavlink_msg_video_stream_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_video_stream_information_t* video_stream_information)
  188. {
  189. return mavlink_msg_video_stream_information_pack(system_id, component_id, msg, video_stream_information->stream_id, video_stream_information->count, video_stream_information->type, video_stream_information->flags, video_stream_information->framerate, video_stream_information->resolution_h, video_stream_information->resolution_v, video_stream_information->bitrate, video_stream_information->rotation, video_stream_information->hfov, video_stream_information->name, video_stream_information->uri);
  190. }
  191. /**
  192. * @brief Encode a video_stream_information struct on a channel
  193. *
  194. * @param system_id ID of this system
  195. * @param component_id ID of this component (e.g. 200 for IMU)
  196. * @param chan The MAVLink channel this message will be sent over
  197. * @param msg The MAVLink message to compress the data into
  198. * @param video_stream_information C-struct to read the message contents from
  199. */
  200. static inline uint16_t mavlink_msg_video_stream_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_video_stream_information_t* video_stream_information)
  201. {
  202. return mavlink_msg_video_stream_information_pack_chan(system_id, component_id, chan, msg, video_stream_information->stream_id, video_stream_information->count, video_stream_information->type, video_stream_information->flags, video_stream_information->framerate, video_stream_information->resolution_h, video_stream_information->resolution_v, video_stream_information->bitrate, video_stream_information->rotation, video_stream_information->hfov, video_stream_information->name, video_stream_information->uri);
  203. }
  204. /**
  205. * @brief Send a video_stream_information message
  206. * @param chan MAVLink channel to send the message
  207. *
  208. * @param stream_id Video Stream ID (1 for first, 2 for second, etc.)
  209. * @param count Number of streams available.
  210. * @param type Type of stream.
  211. * @param flags Bitmap of stream status flags.
  212. * @param framerate [Hz] Frame rate.
  213. * @param resolution_h [pix] Horizontal resolution.
  214. * @param resolution_v [pix] Vertical resolution.
  215. * @param bitrate [bits/s] Bit rate.
  216. * @param rotation [deg] Video image rotation clockwise.
  217. * @param hfov [deg] Horizontal Field of view.
  218. * @param name Stream name.
  219. * @param uri Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).
  220. */
  221. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  222. static inline void mavlink_msg_video_stream_information_send(mavlink_channel_t chan, uint8_t stream_id, uint8_t count, uint8_t type, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov, const char *name, const char *uri)
  223. {
  224. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  225. char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN];
  226. _mav_put_float(buf, 0, framerate);
  227. _mav_put_uint32_t(buf, 4, bitrate);
  228. _mav_put_uint16_t(buf, 8, flags);
  229. _mav_put_uint16_t(buf, 10, resolution_h);
  230. _mav_put_uint16_t(buf, 12, resolution_v);
  231. _mav_put_uint16_t(buf, 14, rotation);
  232. _mav_put_uint16_t(buf, 16, hfov);
  233. _mav_put_uint8_t(buf, 18, stream_id);
  234. _mav_put_uint8_t(buf, 19, count);
  235. _mav_put_uint8_t(buf, 20, type);
  236. _mav_put_char_array(buf, 21, name, 32);
  237. _mav_put_char_array(buf, 53, uri, 160);
  238. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC);
  239. #else
  240. mavlink_video_stream_information_t packet;
  241. packet.framerate = framerate;
  242. packet.bitrate = bitrate;
  243. packet.flags = flags;
  244. packet.resolution_h = resolution_h;
  245. packet.resolution_v = resolution_v;
  246. packet.rotation = rotation;
  247. packet.hfov = hfov;
  248. packet.stream_id = stream_id;
  249. packet.count = count;
  250. packet.type = type;
  251. mav_array_memcpy(packet.name, name, sizeof(char)*32);
  252. mav_array_memcpy(packet.uri, uri, sizeof(char)*160);
  253. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC);
  254. #endif
  255. }
  256. /**
  257. * @brief Send a video_stream_information message
  258. * @param chan MAVLink channel to send the message
  259. * @param struct The MAVLink struct to serialize
  260. */
  261. static inline void mavlink_msg_video_stream_information_send_struct(mavlink_channel_t chan, const mavlink_video_stream_information_t* video_stream_information)
  262. {
  263. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  264. mavlink_msg_video_stream_information_send(chan, video_stream_information->stream_id, video_stream_information->count, video_stream_information->type, video_stream_information->flags, video_stream_information->framerate, video_stream_information->resolution_h, video_stream_information->resolution_v, video_stream_information->bitrate, video_stream_information->rotation, video_stream_information->hfov, video_stream_information->name, video_stream_information->uri);
  265. #else
  266. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, (const char *)video_stream_information, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC);
  267. #endif
  268. }
  269. #if MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  270. /*
  271. This variant of _send() can be used to save stack space by re-using
  272. memory from the receive buffer. The caller provides a
  273. mavlink_message_t which is the size of a full mavlink message. This
  274. is usually the receive buffer for the channel, and allows a reply to an
  275. incoming message with minimum stack space usage.
  276. */
  277. static inline void mavlink_msg_video_stream_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stream_id, uint8_t count, uint8_t type, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov, const char *name, const char *uri)
  278. {
  279. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  280. char *buf = (char *)msgbuf;
  281. _mav_put_float(buf, 0, framerate);
  282. _mav_put_uint32_t(buf, 4, bitrate);
  283. _mav_put_uint16_t(buf, 8, flags);
  284. _mav_put_uint16_t(buf, 10, resolution_h);
  285. _mav_put_uint16_t(buf, 12, resolution_v);
  286. _mav_put_uint16_t(buf, 14, rotation);
  287. _mav_put_uint16_t(buf, 16, hfov);
  288. _mav_put_uint8_t(buf, 18, stream_id);
  289. _mav_put_uint8_t(buf, 19, count);
  290. _mav_put_uint8_t(buf, 20, type);
  291. _mav_put_char_array(buf, 21, name, 32);
  292. _mav_put_char_array(buf, 53, uri, 160);
  293. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC);
  294. #else
  295. mavlink_video_stream_information_t *packet = (mavlink_video_stream_information_t *)msgbuf;
  296. packet->framerate = framerate;
  297. packet->bitrate = bitrate;
  298. packet->flags = flags;
  299. packet->resolution_h = resolution_h;
  300. packet->resolution_v = resolution_v;
  301. packet->rotation = rotation;
  302. packet->hfov = hfov;
  303. packet->stream_id = stream_id;
  304. packet->count = count;
  305. packet->type = type;
  306. mav_array_memcpy(packet->name, name, sizeof(char)*32);
  307. mav_array_memcpy(packet->uri, uri, sizeof(char)*160);
  308. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC);
  309. #endif
  310. }
  311. #endif
  312. #endif
  313. // MESSAGE VIDEO_STREAM_INFORMATION UNPACKING
  314. /**
  315. * @brief Get field stream_id from video_stream_information message
  316. *
  317. * @return Video Stream ID (1 for first, 2 for second, etc.)
  318. */
  319. static inline uint8_t mavlink_msg_video_stream_information_get_stream_id(const mavlink_message_t* msg)
  320. {
  321. return _MAV_RETURN_uint8_t(msg, 18);
  322. }
  323. /**
  324. * @brief Get field count from video_stream_information message
  325. *
  326. * @return Number of streams available.
  327. */
  328. static inline uint8_t mavlink_msg_video_stream_information_get_count(const mavlink_message_t* msg)
  329. {
  330. return _MAV_RETURN_uint8_t(msg, 19);
  331. }
  332. /**
  333. * @brief Get field type from video_stream_information message
  334. *
  335. * @return Type of stream.
  336. */
  337. static inline uint8_t mavlink_msg_video_stream_information_get_type(const mavlink_message_t* msg)
  338. {
  339. return _MAV_RETURN_uint8_t(msg, 20);
  340. }
  341. /**
  342. * @brief Get field flags from video_stream_information message
  343. *
  344. * @return Bitmap of stream status flags.
  345. */
  346. static inline uint16_t mavlink_msg_video_stream_information_get_flags(const mavlink_message_t* msg)
  347. {
  348. return _MAV_RETURN_uint16_t(msg, 8);
  349. }
  350. /**
  351. * @brief Get field framerate from video_stream_information message
  352. *
  353. * @return [Hz] Frame rate.
  354. */
  355. static inline float mavlink_msg_video_stream_information_get_framerate(const mavlink_message_t* msg)
  356. {
  357. return _MAV_RETURN_float(msg, 0);
  358. }
  359. /**
  360. * @brief Get field resolution_h from video_stream_information message
  361. *
  362. * @return [pix] Horizontal resolution.
  363. */
  364. static inline uint16_t mavlink_msg_video_stream_information_get_resolution_h(const mavlink_message_t* msg)
  365. {
  366. return _MAV_RETURN_uint16_t(msg, 10);
  367. }
  368. /**
  369. * @brief Get field resolution_v from video_stream_information message
  370. *
  371. * @return [pix] Vertical resolution.
  372. */
  373. static inline uint16_t mavlink_msg_video_stream_information_get_resolution_v(const mavlink_message_t* msg)
  374. {
  375. return _MAV_RETURN_uint16_t(msg, 12);
  376. }
  377. /**
  378. * @brief Get field bitrate from video_stream_information message
  379. *
  380. * @return [bits/s] Bit rate.
  381. */
  382. static inline uint32_t mavlink_msg_video_stream_information_get_bitrate(const mavlink_message_t* msg)
  383. {
  384. return _MAV_RETURN_uint32_t(msg, 4);
  385. }
  386. /**
  387. * @brief Get field rotation from video_stream_information message
  388. *
  389. * @return [deg] Video image rotation clockwise.
  390. */
  391. static inline uint16_t mavlink_msg_video_stream_information_get_rotation(const mavlink_message_t* msg)
  392. {
  393. return _MAV_RETURN_uint16_t(msg, 14);
  394. }
  395. /**
  396. * @brief Get field hfov from video_stream_information message
  397. *
  398. * @return [deg] Horizontal Field of view.
  399. */
  400. static inline uint16_t mavlink_msg_video_stream_information_get_hfov(const mavlink_message_t* msg)
  401. {
  402. return _MAV_RETURN_uint16_t(msg, 16);
  403. }
  404. /**
  405. * @brief Get field name from video_stream_information message
  406. *
  407. * @return Stream name.
  408. */
  409. static inline uint16_t mavlink_msg_video_stream_information_get_name(const mavlink_message_t* msg, char *name)
  410. {
  411. return _MAV_RETURN_char_array(msg, name, 32, 21);
  412. }
  413. /**
  414. * @brief Get field uri from video_stream_information message
  415. *
  416. * @return Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).
  417. */
  418. static inline uint16_t mavlink_msg_video_stream_information_get_uri(const mavlink_message_t* msg, char *uri)
  419. {
  420. return _MAV_RETURN_char_array(msg, uri, 160, 53);
  421. }
  422. /**
  423. * @brief Decode a video_stream_information message into a struct
  424. *
  425. * @param msg The message to decode
  426. * @param video_stream_information C-struct to decode the message contents into
  427. */
  428. static inline void mavlink_msg_video_stream_information_decode(const mavlink_message_t* msg, mavlink_video_stream_information_t* video_stream_information)
  429. {
  430. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  431. video_stream_information->framerate = mavlink_msg_video_stream_information_get_framerate(msg);
  432. video_stream_information->bitrate = mavlink_msg_video_stream_information_get_bitrate(msg);
  433. video_stream_information->flags = mavlink_msg_video_stream_information_get_flags(msg);
  434. video_stream_information->resolution_h = mavlink_msg_video_stream_information_get_resolution_h(msg);
  435. video_stream_information->resolution_v = mavlink_msg_video_stream_information_get_resolution_v(msg);
  436. video_stream_information->rotation = mavlink_msg_video_stream_information_get_rotation(msg);
  437. video_stream_information->hfov = mavlink_msg_video_stream_information_get_hfov(msg);
  438. video_stream_information->stream_id = mavlink_msg_video_stream_information_get_stream_id(msg);
  439. video_stream_information->count = mavlink_msg_video_stream_information_get_count(msg);
  440. video_stream_information->type = mavlink_msg_video_stream_information_get_type(msg);
  441. mavlink_msg_video_stream_information_get_name(msg, video_stream_information->name);
  442. mavlink_msg_video_stream_information_get_uri(msg, video_stream_information->uri);
  443. #else
  444. uint8_t len = msg->len < MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN;
  445. memset(video_stream_information, 0, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN);
  446. memcpy(video_stream_information, _MAV_PAYLOAD(msg), len);
  447. #endif
  448. }