QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
QGCVideoStreamInfo.cc
Go to the documentation of this file.
3
4QGC_LOGGING_CATEGORY(QGCVideoStreamInfoLog, "Camera.QGCVideoStreamInfo")
5
6QGCVideoStreamInfo::QGCVideoStreamInfo(const mavlink_video_stream_information_t &info, QObject *parent)
7 : QObject(parent)
8{
9 qCDebug(QGCVideoStreamInfoLog) << this;
10
11 (void) memcpy(&_streamInfo, &info, sizeof(mavlink_video_stream_information_t));
12}
13
14QGCVideoStreamInfo::~QGCVideoStreamInfo()
15{
16
17}
18
19qreal QGCVideoStreamInfo::aspectRatio() const
20{
21 qreal ar = 1.0;
22 if (!resolution().isNull()) {
23 ar = static_cast<double>(_streamInfo.resolution_h) / static_cast<double>(_streamInfo.resolution_v);
24 }
25 return ar;
26}
27
28bool QGCVideoStreamInfo::update(const mavlink_video_stream_status_t &status)
29{
30 bool changed = false;
31
32 if (_streamInfo.hfov != status.hfov) {
33 changed = true;
34 _streamInfo.hfov = status.hfov;
35 }
36
37 if (_streamInfo.flags != status.flags) {
38 changed = true;
39 _streamInfo.flags = status.flags;
40 }
41
42 if (_streamInfo.bitrate != status.bitrate) {
43 changed = true;
44 _streamInfo.bitrate = status.bitrate;
45 }
46
47 if (_streamInfo.rotation != status.rotation) {
48 changed = true;
49 _streamInfo.rotation = status.rotation;
50 }
51
52 if (_streamInfo.framerate != status.framerate) {
53 changed = true;
54 _streamInfo.framerate = status.framerate;
55 }
56
57 if (_streamInfo.resolution_h != status.resolution_h) {
58 changed = true;
59 _streamInfo.resolution_h = status.resolution_h;
60 }
61
62 if (_streamInfo.resolution_v != status.resolution_v) {
63 changed = true;
64 _streamInfo.resolution_v = status.resolution_v;
65 }
66
67 if (changed) {
68 emit infoChanged();
69 }
70
71 return changed;
72}
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.