4#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION 269
7typedef struct __mavlink_video_stream_information_t {
10 uint16_t resolution_h;
11 uint16_t resolution_v;
16}) mavlink_video_stream_information_t;
18#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN 246
19#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN 246
20#define MAVLINK_MSG_ID_269_LEN 246
21#define MAVLINK_MSG_ID_269_MIN_LEN 246
23#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC 58
24#define MAVLINK_MSG_ID_269_CRC 58
26#define MAVLINK_MSG_VIDEO_STREAM_INFORMATION_FIELD_URI_LEN 230
28#if MAVLINK_COMMAND_24BIT
29#define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION { \
31 "VIDEO_STREAM_INFORMATION", \
33 { { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_video_stream_information_t, camera_id) }, \
34 { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_video_stream_information_t, status) }, \
35 { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_information_t, framerate) }, \
36 { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_information_t, resolution_h) }, \
37 { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, 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, 12, offsetof(mavlink_video_stream_information_t, rotation) }, \
40 { "uri", NULL, MAVLINK_TYPE_CHAR, 230, 16, offsetof(mavlink_video_stream_information_t, uri) }, \
44#define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION { \
45 "VIDEO_STREAM_INFORMATION", \
47 { { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_video_stream_information_t, camera_id) }, \
48 { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_video_stream_information_t, status) }, \
49 { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_information_t, framerate) }, \
50 { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_information_t, resolution_h) }, \
51 { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_information_t, resolution_v) }, \
52 { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_information_t, bitrate) }, \
53 { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_information_t, rotation) }, \
54 { "uri", NULL, MAVLINK_TYPE_CHAR, 230, 16, offsetof(mavlink_video_stream_information_t, uri) }, \
75static inline uint16_t mavlink_msg_video_stream_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
76 uint8_t camera_id, uint8_t status,
float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation,
const char *uri)
78#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
79 char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN];
80 _mav_put_float(buf, 0, framerate);
81 _mav_put_uint32_t(buf, 4, bitrate);
82 _mav_put_uint16_t(buf, 8, resolution_h);
83 _mav_put_uint16_t(buf, 10, resolution_v);
84 _mav_put_uint16_t(buf, 12, rotation);
85 _mav_put_uint8_t(buf, 14, camera_id);
86 _mav_put_uint8_t(buf, 15, status);
87 _mav_put_char_array(buf, 16, uri, 230);
88 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN);
90 mavlink_video_stream_information_t packet;
91 packet.framerate = framerate;
92 packet.bitrate = bitrate;
93 packet.resolution_h = resolution_h;
94 packet.resolution_v = resolution_v;
95 packet.rotation = rotation;
96 packet.camera_id = camera_id;
97 packet.status = status;
98 mav_array_memcpy(packet.uri, uri,
sizeof(
char)*230);
99 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN);
102 msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION;
103 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);
122static inline uint16_t mavlink_msg_video_stream_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
123 mavlink_message_t* msg,
124 uint8_t camera_id,uint8_t status,
float framerate,uint16_t resolution_h,uint16_t resolution_v,uint32_t bitrate,uint16_t rotation,
const char *uri)
126#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
127 char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN];
128 _mav_put_float(buf, 0, framerate);
129 _mav_put_uint32_t(buf, 4, bitrate);
130 _mav_put_uint16_t(buf, 8, resolution_h);
131 _mav_put_uint16_t(buf, 10, resolution_v);
132 _mav_put_uint16_t(buf, 12, rotation);
133 _mav_put_uint8_t(buf, 14, camera_id);
134 _mav_put_uint8_t(buf, 15, status);
135 _mav_put_char_array(buf, 16, uri, 230);
136 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN);
138 mavlink_video_stream_information_t packet;
139 packet.framerate = framerate;
140 packet.bitrate = bitrate;
141 packet.resolution_h = resolution_h;
142 packet.resolution_v = resolution_v;
143 packet.rotation = rotation;
144 packet.camera_id = camera_id;
145 packet.status = status;
146 mav_array_memcpy(packet.uri, uri,
sizeof(
char)*230);
147 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN);
150 msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION;
151 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);
162static 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)
164 return mavlink_msg_video_stream_information_pack(system_id, component_id, msg, video_stream_information->camera_id, video_stream_information->status, 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->uri);
176static 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)
178 return mavlink_msg_video_stream_information_pack_chan(system_id, component_id, chan, msg, video_stream_information->camera_id, video_stream_information->status, 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->uri);
194#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
196static inline void mavlink_msg_video_stream_information_send(mavlink_channel_t chan, uint8_t camera_id, uint8_t status,
float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation,
const char *uri)
198#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
199 char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN];
200 _mav_put_float(buf, 0, framerate);
201 _mav_put_uint32_t(buf, 4, bitrate);
202 _mav_put_uint16_t(buf, 8, resolution_h);
203 _mav_put_uint16_t(buf, 10, resolution_v);
204 _mav_put_uint16_t(buf, 12, rotation);
205 _mav_put_uint8_t(buf, 14, camera_id);
206 _mav_put_uint8_t(buf, 15, status);
207 _mav_put_char_array(buf, 16, uri, 230);
208 _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);
210 mavlink_video_stream_information_t packet;
211 packet.framerate = framerate;
212 packet.bitrate = bitrate;
213 packet.resolution_h = resolution_h;
214 packet.resolution_v = resolution_v;
215 packet.rotation = rotation;
216 packet.camera_id = camera_id;
217 packet.status = status;
218 mav_array_memcpy(packet.uri, uri,
sizeof(
char)*230);
219 _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);
228static inline void mavlink_msg_video_stream_information_send_struct(mavlink_channel_t chan,
const mavlink_video_stream_information_t* video_stream_information)
230#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
231 mavlink_msg_video_stream_information_send(chan, video_stream_information->camera_id, video_stream_information->status, 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->uri);
233 _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);
237#if MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
245static inline void mavlink_msg_video_stream_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t camera_id, uint8_t status,
float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation,
const char *uri)
247#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
248 char *buf = (
char *)msgbuf;
249 _mav_put_float(buf, 0, framerate);
250 _mav_put_uint32_t(buf, 4, bitrate);
251 _mav_put_uint16_t(buf, 8, resolution_h);
252 _mav_put_uint16_t(buf, 10, resolution_v);
253 _mav_put_uint16_t(buf, 12, rotation);
254 _mav_put_uint8_t(buf, 14, camera_id);
255 _mav_put_uint8_t(buf, 15, status);
256 _mav_put_char_array(buf, 16, uri, 230);
257 _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);
259 mavlink_video_stream_information_t *packet = (mavlink_video_stream_information_t *)msgbuf;
260 packet->framerate = framerate;
261 packet->bitrate = bitrate;
262 packet->resolution_h = resolution_h;
263 packet->resolution_v = resolution_v;
264 packet->rotation = rotation;
265 packet->camera_id = camera_id;
266 packet->status = status;
267 mav_array_memcpy(packet->uri, uri,
sizeof(
char)*230);
268 _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);
283static inline uint8_t mavlink_msg_video_stream_information_get_camera_id(
const mavlink_message_t* msg)
285 return _MAV_RETURN_uint8_t(msg, 14);
293static inline uint8_t mavlink_msg_video_stream_information_get_status(
const mavlink_message_t* msg)
295 return _MAV_RETURN_uint8_t(msg, 15);
303static inline float mavlink_msg_video_stream_information_get_framerate(
const mavlink_message_t* msg)
305 return _MAV_RETURN_float(msg, 0);
313static inline uint16_t mavlink_msg_video_stream_information_get_resolution_h(
const mavlink_message_t* msg)
315 return _MAV_RETURN_uint16_t(msg, 8);
323static inline uint16_t mavlink_msg_video_stream_information_get_resolution_v(
const mavlink_message_t* msg)
325 return _MAV_RETURN_uint16_t(msg, 10);
333static inline uint32_t mavlink_msg_video_stream_information_get_bitrate(
const mavlink_message_t* msg)
335 return _MAV_RETURN_uint32_t(msg, 4);
343static inline uint16_t mavlink_msg_video_stream_information_get_rotation(
const mavlink_message_t* msg)
345 return _MAV_RETURN_uint16_t(msg, 12);
353static inline uint16_t mavlink_msg_video_stream_information_get_uri(
const mavlink_message_t* msg,
char *uri)
355 return _MAV_RETURN_char_array(msg, uri, 230, 16);
364static inline void mavlink_msg_video_stream_information_decode(
const mavlink_message_t* msg, mavlink_video_stream_information_t* video_stream_information)
366#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
367 video_stream_information->framerate = mavlink_msg_video_stream_information_get_framerate(msg);
368 video_stream_information->bitrate = mavlink_msg_video_stream_information_get_bitrate(msg);
369 video_stream_information->resolution_h = mavlink_msg_video_stream_information_get_resolution_h(msg);
370 video_stream_information->resolution_v = mavlink_msg_video_stream_information_get_resolution_v(msg);
371 video_stream_information->rotation = mavlink_msg_video_stream_information_get_rotation(msg);
372 video_stream_information->camera_id = mavlink_msg_video_stream_information_get_camera_id(msg);
373 video_stream_information->status = mavlink_msg_video_stream_information_get_status(msg);
374 mavlink_msg_video_stream_information_get_uri(msg, video_stream_information->uri);
376 uint8_t len = msg->len < MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN;
377 memset(video_stream_information, 0, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN);
378 memcpy(video_stream_information, _MAV_PAYLOAD(msg), len);