9 qCDebug(QGCVideoStreamInfoLog) <<
this;
11 (void) memcpy(&_streamInfo, &info,
sizeof(mavlink_video_stream_information_t));
14QGCVideoStreamInfo::~QGCVideoStreamInfo()
19qreal QGCVideoStreamInfo::aspectRatio()
const
22 if (!resolution().isNull()) {
23 ar =
static_cast<double>(_streamInfo.resolution_h) /
static_cast<double>(_streamInfo.resolution_v);
28bool QGCVideoStreamInfo::update(
const mavlink_video_stream_status_t &status)
32 if (_streamInfo.hfov != status.hfov) {
34 _streamInfo.hfov = status.hfov;
37 if (_streamInfo.flags != status.flags) {
39 _streamInfo.flags = status.flags;
42 if (_streamInfo.bitrate != status.bitrate) {
44 _streamInfo.bitrate = status.bitrate;
47 if (_streamInfo.rotation != status.rotation) {
49 _streamInfo.rotation = status.rotation;
52 if (_streamInfo.framerate != status.framerate) {
54 _streamInfo.framerate = status.framerate;
57 if (_streamInfo.resolution_h != status.resolution_h) {
59 _streamInfo.resolution_h = status.resolution_h;
62 if (_streamInfo.resolution_v != status.resolution_v) {
64 _streamInfo.resolution_v = status.resolution_v;
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.