diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0 index 90d9b285e01fe8bfa3b4e8868ca71c5537d43302..c847642263deefa584691eebade8b29a25264442 160000 --- a/libs/mavlink/include/mavlink/v2.0 +++ b/libs/mavlink/include/mavlink/v2.0 @@ -1 +1 @@ -Subproject commit 90d9b285e01fe8bfa3b4e8868ca71c5537d43302 +Subproject commit c847642263deefa584691eebade8b29a25264442 diff --git a/qgcresources.qrc b/qgcresources.qrc index c51db63e3df42b24cb01fbb9e94ec6ae46bce2c9..e87e4a066b91395b533b3d9914ee2a1b0f73f449 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -195,6 +195,7 @@ resources/counter-clockwise-arrow.svg resources/chevron-down.svg resources/chevron-up.svg + resources/DropArrow.svg resources/gear-black.svg resources/gear-white.svg resources/helicoptericon.svg diff --git a/resources/DropArrow.svg b/resources/DropArrow.svg new file mode 100644 index 0000000000000000000000000000000000000000..368bf50373eb64abb345c013ac78a09155feed32 --- /dev/null +++ b/resources/DropArrow.svg @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index ffad98fcd0d1889d5388d4d0d7cf3b774bebf3ce..39605d0901f7badd5a2923644f03a1345f3cbf22 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -10,6 +10,7 @@ #include "SettingsManager.h" #include "VideoManager.h" #include "QGCMapEngine.h" +#include "QGCCameraManager.h" #include #include @@ -66,6 +67,7 @@ static const char *kCAM_ISO = "CAM_ISO"; static const char* kCAM_SHUTTER = "CAM_SHUTTER"; static const char* kCAM_APERTURE = "CAM_APERTURE"; static const char* kCAM_WBMODE = "CAM_WBMODE"; +static const char* kCAM_MODE = "CAM_MODE"; //----------------------------------------------------------------------------- QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_) @@ -153,21 +155,6 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh : FactGroup(0, parent) , _vehicle(vehicle) , _compID(compID) - , _version(0) - , _cached(false) - , _paramComplete(false) - , _storageFree(0) - , _storageTotal(0) - , _netManager(nullptr) - , _cameraMode(CAM_MODE_UNDEFINED) - , _photoMode(PHOTO_CAPTURE_SINGLE) - , _photoLapse(1.0) - , _photoLapseCount(0) - , _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED) - , _photo_status(PHOTO_CAPTURE_STATUS_UNDEFINED) - , _storageInfoRetries(0) - , _captureInfoRetries(0) - , _resetting(false) { QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); memcpy(&_info, info, sizeof(mavlink_camera_information_t)); @@ -190,6 +177,9 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh _photoMode = static_cast(settings.value(kPhotoMode, static_cast(PHOTO_CAPTURE_SINGLE)).toInt()); _photoLapse = settings.value(kPhotoLapse, 1.0).toDouble(); _photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt(); + _recTimer.setSingleShot(false); + _recTimer.setInterval(333); + connect(&_recTimer, &QTimer::timeout, this, &QGCCameraControl::_recTimerHandler); } //----------------------------------------------------------------------------- @@ -208,6 +198,7 @@ QGCCameraControl::_initWhenReady() if(isBasic()) { qCDebug(CameraControlLog) << "Basic, MAVLink only messages."; _requestCameraSettings(); + QTimer::singleShot(250, this, &QGCCameraControl::_checkForVideoStreams); } else { _requestAllParameters(); //-- Give some time to load the parameters before going after the camera settings @@ -237,6 +228,13 @@ QGCCameraControl::firmwareVersion() return ver; } +//----------------------------------------------------------------------------- +QString +QGCCameraControl::recordTimeStr() +{ + return QTime(0, 0).addMSecs(static_cast(recordTime())).toString("hh:mm:ss"); +} + //----------------------------------------------------------------------------- QGCCameraControl::VideoStatus QGCCameraControl::videoStatus() @@ -270,7 +268,6 @@ QGCCameraControl::setCameraMode(CameraMode mode) setPhotoMode(); } else { qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode; - return; } } } @@ -311,8 +308,12 @@ QGCCameraControl::setPhotoLapseCount(int count) void QGCCameraControl::_setCameraMode(CameraMode mode) { - _cameraMode = mode; - emit cameraModeChanged(); + if(_cameraMode != mode) { + _cameraMode = mode; + emit cameraModeChanged(); + //-- Update stream status + _streamStatusTimer.start(1000); + } } //----------------------------------------------------------------------------- @@ -410,7 +411,7 @@ QGCCameraControl::startVideo() _vehicle->sendMavCommand( _compID, // Target component MAV_CMD_VIDEO_START_CAPTURE, // Command id - true, // ShowError + false, // Don't Show Error (handle locally) 0, // Reserved (Set to 0) 0); // CAMERA_CAPTURE_STATUS Frequency return true; @@ -429,7 +430,7 @@ QGCCameraControl::stopVideo() _vehicle->sendMavCommand( _compID, // Target component MAV_CMD_VIDEO_STOP_CAPTURE, // Command id - true, // ShowError + false, // Don't Show Error (handle locally) 0); // Reserved (Set to 0) return true; } @@ -441,17 +442,27 @@ QGCCameraControl::stopVideo() void QGCCameraControl::setVideoMode() { - if(!_resetting) { - if(hasModes() && _cameraMode != CAM_MODE_VIDEO) { - qCDebug(CameraControlLog) << "setVideoMode()"; - //-- Use basic MAVLink message - _vehicle->sendMavCommand( - _compID, // Target component - MAV_CMD_SET_CAMERA_MODE, // Command id - true, // ShowError - 0, // Reserved (Set to 0) - CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video) - _setCameraMode(CAM_MODE_VIDEO); + if(!_resetting && hasModes()) { + qCDebug(CameraControlLog) << "setVideoMode()"; + //-- Does it have a mode parameter? + Fact* pMode = mode(); + if(pMode) { + if(cameraMode() != CAM_MODE_VIDEO) { + pMode->setRawValue(CAM_MODE_VIDEO); + _setCameraMode(CAM_MODE_VIDEO); + } + } else { + //-- Use MAVLink Command + if(_cameraMode != CAM_MODE_VIDEO) { + //-- Use basic MAVLink message + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_SET_CAMERA_MODE, // Command id + true, // ShowError + 0, // Reserved (Set to 0) + CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video) + _setCameraMode(CAM_MODE_VIDEO); + } } } } @@ -460,17 +471,27 @@ QGCCameraControl::setVideoMode() void QGCCameraControl::setPhotoMode() { - if(!_resetting) { - if(hasModes() && _cameraMode != CAM_MODE_PHOTO) { - qCDebug(CameraControlLog) << "setPhotoMode()"; - //-- Use basic MAVLink message - _vehicle->sendMavCommand( - _compID, // Target component - MAV_CMD_SET_CAMERA_MODE, // Command id - true, // ShowError - 0, // Reserved (Set to 0) - CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video) - _setCameraMode(CAM_MODE_PHOTO); + if(!_resetting && hasModes()) { + qCDebug(CameraControlLog) << "setPhotoMode()"; + //-- Does it have a mode parameter? + Fact* pMode = mode(); + if(pMode) { + if(cameraMode() != CAM_MODE_PHOTO) { + pMode->setRawValue(CAM_MODE_PHOTO); + _setCameraMode(CAM_MODE_PHOTO); + } + } else { + //-- Use MAVLink Command + if(_cameraMode != CAM_MODE_PHOTO) { + //-- Use basic MAVLink message + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_SET_CAMERA_MODE, // Command id + true, // ShowError + 0, // Reserved (Set to 0) + CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video) + _setCameraMode(CAM_MODE_PHOTO); + } } } } @@ -693,9 +714,26 @@ QGCCameraControl::_setVideoStatus(VideoStatus status) if(_video_status != status) { _video_status = status; emit videoStatusChanged(); + if(status == VIDEO_CAPTURE_STATUS_RUNNING) { + _recordTime = 0; + _recTime.start(); + _recTimer.start(); + } else { + _recTimer.stop(); + _recordTime = 0; + emit recordTimeChanged(); + } } } +//----------------------------------------------------------------------------- +void +QGCCameraControl::_recTimerHandler() +{ + _recordTime = static_cast(_recTime.elapsed()); + emit recordTimeChanged(); +} + //----------------------------------------------------------------------------- void QGCCameraControl::_setPhotoStatus(PhotoStatus status) @@ -1386,7 +1424,7 @@ QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings) void QGCCameraControl::handleStorageInfo(const mavlink_storage_information_t& st) { - qCDebug(CameraControlLog) << "_handleStorageInfo:" << st.available_capacity << st.status << st.storage_count << st.storage_id << st.total_capacity << st.used_capacity; + qCDebug(CameraControlLog) << "handleStorageInfo:" << st.available_capacity << st.status << st.storage_count << st.storage_id << st.total_capacity << st.used_capacity; uint32_t t = static_cast(st.total_capacity); if(_storageTotal != t) { _storageTotal = t; @@ -1412,6 +1450,12 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap _storageFree = a; emit storageFreeChanged(); } + //-- Do we have recording time? + if(cap.recording_time_ms) { + _recordTime = cap.recording_time_ms; + _recTime = _recTime.addMSecs(_recTime.elapsed() - static_cast(cap.recording_time_ms)); + emit recordTimeChanged(); + } //-- Video/Image Capture Status uint8_t vs = cap.video_status < static_cast(VIDEO_CAPTURE_STATUS_LAST) ? cap.video_status : static_cast(VIDEO_CAPTURE_STATUS_UNDEFINED); uint8_t ps = cap.image_status < static_cast(PHOTO_CAPTURE_LAST) ? cap.image_status : static_cast(PHOTO_CAPTURE_STATUS_UNDEFINED); @@ -1434,6 +1478,209 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap } } +//----------------------------------------------------------------------------- +void +QGCCameraControl::handleVideoInfo(const mavlink_video_stream_information_t* vi) +{ + qCDebug(CameraControlLog) << "handleVideoInfo:" << vi->stream_id << vi->uri; + _expectedCount = vi->count; + if(!_findStream(vi->stream_id)) { + qCDebug(CameraControlLog) << "Create stream handler for stream ID:" << vi->stream_id; + QGCVideoStreamInfo* pStream = new QGCVideoStreamInfo(this, vi); + QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership); + _streams.append(pStream); + emit streamsChanged(); + } + //-- Check for missing count + if(_streams.count() < _expectedCount) { + _streamInfoTimer.start(1000); + } else { + //-- Done + qCDebug(CameraControlLog) << "All stream handlers done"; + _streamInfoTimer.stop(); + emit autoStreamChanged(); + emit _vehicle->dynamicCameras()->streamChanged(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::handleVideoStatus(const mavlink_video_stream_status_t* vs) +{ + _streamStatusTimer.stop(); + qCDebug(CameraControlLog) << "handleVideoStatus:" << vs->stream_id; + QGCVideoStreamInfo* pInfo = _findStream(vs->stream_id); + if(pInfo) { + if(pInfo->update(vs)) { + emit _vehicle->dynamicCameras()->streamChanged(); + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setCurrentStream(int stream) +{ + if(stream != _currentStream && stream >= 0 && stream < _streams.count()) { + if(_currentStream != stream) { + QGCVideoStreamInfo* pInfo = currentStreamInstance(); + if(pInfo) { + //-- Stop current stream + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_VIDEO_STOP_STREAMING, // Command id + false, // ShowError + pInfo->streamID()); // Stream ID + } + _currentStream = stream; + pInfo = currentStreamInstance(); + if(pInfo) { + //-- Start new stream + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_VIDEO_START_STREAMING, // Command id + false, // ShowError + pInfo->streamID()); // Stream ID + //-- Update stream status + _requestStreamStatus(static_cast(pInfo->streamID())); + } + emit currentStreamChanged(); + emit _vehicle->dynamicCameras()->streamChanged(); + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::stopStream() +{ + QGCVideoStreamInfo* pInfo = currentStreamInstance(); + if(pInfo) { + //-- Stop current stream + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_VIDEO_STOP_STREAMING, // Command id + false, // ShowError + pInfo->streamID()); // Stream ID + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::resumeStream() +{ + QGCVideoStreamInfo* pInfo = currentStreamInstance(); + if(pInfo) { + //-- Start new stream + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_VIDEO_START_STREAMING, // Command id + false, // ShowError + pInfo->streamID()); // Stream ID + } +} + +//----------------------------------------------------------------------------- +bool +QGCCameraControl::autoStream() +{ + if(hasVideoStream()) { + return _streams.count() > 0; + } + return false; +} + +//----------------------------------------------------------------------------- +QGCVideoStreamInfo* +QGCCameraControl::currentStreamInstance() +{ + if(_currentStream < _streams.count() && _streams.count()) { + QGCVideoStreamInfo* pStream = qobject_cast(_streams[_currentStream]); + return pStream; + } + return nullptr; +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_requestStreamInfo(uint8_t streamID) +{ + qCDebug(CameraControlLog) << "Requesting video stream info for:" << streamID; + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, // Command id + false, // ShowError + streamID); // Stream ID +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_requestStreamStatus(uint8_t streamID) +{ + qCDebug(CameraControlLog) << "Requesting video stream status for:" << streamID; + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_REQUEST_VIDEO_STREAM_STATUS, // Command id + false, // ShowError + streamID); // Stream ID + _streamStatusTimer.start(1000); // Wait up to a second for it +} + +//----------------------------------------------------------------------------- +QGCVideoStreamInfo* +QGCCameraControl::_findStream(uint8_t id) +{ + for(int i = 0; i < _streams.count(); i++) { + if(_streams[i]) { + QGCVideoStreamInfo* pStream = qobject_cast(_streams[i]); + if(pStream) { + if(pStream->streamID() == id) { + return pStream; + } + } else { + qCritical() << "Null QGCVideoStreamInfo instance"; + } + } + } + qWarning() << "Stream id not found:" << id; + return nullptr; +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_streamTimeout() +{ + _requestCount++; + int count = _expectedCount * 3; + if(_requestCount > count) { + qCWarning(CameraControlLog) << "Giving up requesting video stream info"; + _streamInfoTimer.stop(); + //-- If we have at least one stream, work with what we have. + if(_streams.count()) { + emit autoStreamChanged(); + emit _vehicle->dynamicCameras()->streamChanged(); + } + return; + } + for(uint8_t i = 0; i < _expectedCount; i++) { + //-- Stream ID starts at 1 + if(!_findStream(i+1)) { + _requestStreamInfo(i+1); + return; + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_streamStatusTimeout() +{ + QGCVideoStreamInfo* pStream = currentStreamInstance(); + if(pStream) { + _requestStreamStatus(static_cast(pStream->streamID())); + } +} + //----------------------------------------------------------------------------- QStringList QGCCameraControl::_loadExclusions(QDomNode option) @@ -1672,6 +1919,23 @@ QGCCameraControl::_paramDone() //-- All parameters loaded (or timed out) _paramComplete = true; emit parametersReady(); + //-- Check for video streaming + _checkForVideoStreams(); +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_checkForVideoStreams() +{ + if(_info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM) { + connect(&_streamInfoTimer, &QTimer::timeout, this, &QGCCameraControl::_streamTimeout); + _streamInfoTimer.setSingleShot(false); + connect(&_streamStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_streamStatusTimeout); + _streamStatusTimer.setSingleShot(true); + //-- Request all streams + _requestStreamInfo(0); + _streamInfoTimer.start(2000); + } } //----------------------------------------------------------------------------- @@ -1741,3 +2005,66 @@ QGCCameraControl::wb() { return (_paramComplete && _activeSettings.contains(kCAM_WBMODE)) ? getFact(kCAM_WBMODE) : nullptr; } + +//----------------------------------------------------------------------------- +Fact* +QGCCameraControl::mode() +{ + return _paramComplete ? getFact(kCAM_MODE) : nullptr; +} + +//----------------------------------------------------------------------------- +QGCVideoStreamInfo::QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t *si) + : QObject(parent) +{ + memcpy(&_streamInfo, si, sizeof(mavlink_video_stream_information_t)); +} + +//----------------------------------------------------------------------------- +qreal +QGCVideoStreamInfo::aspectRatio() +{ + if(_streamInfo.resolution_h && _streamInfo.resolution_v) { + return static_cast(_streamInfo.resolution_h) / static_cast(_streamInfo.resolution_v); + } + return 1.0; +} + +//----------------------------------------------------------------------------- +bool +QGCVideoStreamInfo::update(const mavlink_video_stream_status_t* vs) +{ + bool changed = false; + if(_streamInfo.hfov != vs->hfov) { + changed = true; + _streamInfo.hfov = vs->hfov; + } + if(_streamInfo.flags != vs->flags) { + changed = true; + _streamInfo.flags = vs->flags; + } + if(_streamInfo.bitrate != vs->bitrate) { + changed = true; + _streamInfo.bitrate = vs->bitrate; + } + if(_streamInfo.rotation != vs->rotation) { + changed = true; + _streamInfo.rotation = vs->rotation; + } + if(_streamInfo.framerate != vs->framerate) { + changed = true; + _streamInfo.framerate = vs->framerate; + } + if(_streamInfo.resolution_h != vs->resolution_h) { + changed = true; + _streamInfo.resolution_h = vs->resolution_h; + } + if(_streamInfo.resolution_v != vs->resolution_v) { + changed = true; + _streamInfo.resolution_v = vs->resolution_v; + } + if(changed) { + emit infoChanged(); + } + return changed; +} diff --git a/src/Camera/QGCCameraControl.h b/src/Camera/QGCCameraControl.h index 87542920cc48f63f6c35397bb9b261ed0c72d830..7255e1974bc58a6f61bc837a7d2c967308c7a103 100644 --- a/src/Camera/QGCCameraControl.h +++ b/src/Camera/QGCCameraControl.h @@ -17,6 +17,36 @@ class QGCCameraParamIO; Q_DECLARE_LOGGING_CATEGORY(CameraControlLog) Q_DECLARE_LOGGING_CATEGORY(CameraControlLogVerbose) +//----------------------------------------------------------------------------- +class QGCVideoStreamInfo : public QObject +{ + Q_OBJECT +public: + QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t* si); + + Q_PROPERTY(QString uri READ uri NOTIFY infoChanged) + Q_PROPERTY(int streamID READ streamID NOTIFY infoChanged) + Q_PROPERTY(int type READ type NOTIFY infoChanged) + Q_PROPERTY(qreal aspectRatio READ aspectRatio NOTIFY infoChanged) + Q_PROPERTY(qreal hfov READ hfov NOTIFY infoChanged) + Q_PROPERTY(bool isThermal READ isThermal NOTIFY infoChanged) + + QString uri () { return QString(_streamInfo.uri); } + qreal aspectRatio (); + qreal hfov () { return _streamInfo.hfov; } + int type () { return _streamInfo.type; } + int streamID () { return _streamInfo.stream_id; } + bool isThermal () { return _streamInfo.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL; } + + bool update (const mavlink_video_stream_status_t* vs); + +signals: + void infoChanged (); + +private: + mavlink_video_stream_information_t _streamInfo; +}; + //----------------------------------------------------------------------------- class QGCCameraOptionExclusion : public QObject { @@ -99,6 +129,7 @@ public: Q_PROPERTY(bool hasModes READ hasModes NOTIFY infoChanged) Q_PROPERTY(bool hasZoom READ hasZoom NOTIFY infoChanged) Q_PROPERTY(bool hasFocus READ hasFocus NOTIFY infoChanged) + Q_PROPERTY(bool hasVideoStream READ hasVideoStream NOTIFY infoChanged) Q_PROPERTY(bool photosInVideoMode READ photosInVideoMode NOTIFY infoChanged) Q_PROPERTY(bool videoInPhotoMode READ videoInPhotoMode NOTIFY infoChanged) Q_PROPERTY(bool isBasic READ isBasic NOTIFY infoChanged) @@ -116,6 +147,7 @@ public: Q_PROPERTY(Fact* shutter READ shutter NOTIFY parametersReady) Q_PROPERTY(Fact* aperture READ aperture NOTIFY parametersReady) Q_PROPERTY(Fact* wb READ wb NOTIFY parametersReady) + Q_PROPERTY(Fact* mode READ mode NOTIFY parametersReady) Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged) Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged) @@ -124,6 +156,12 @@ public: Q_PROPERTY(qreal photoLapse READ photoLapse WRITE setPhotoLapse NOTIFY photoLapseChanged) Q_PROPERTY(int photoLapseCount READ photoLapseCount WRITE setPhotoLapseCount NOTIFY photoLapseCountChanged) Q_PROPERTY(PhotoMode photoMode READ photoMode WRITE setPhotoMode NOTIFY photoModeChanged) + Q_PROPERTY(int currentStream READ currentStream WRITE setCurrentStream NOTIFY currentStreamChanged) + Q_PROPERTY(bool autoStream READ autoStream NOTIFY autoStreamChanged) + Q_PROPERTY(QmlObjectListModel* streams READ streams NOTIFY streamsChanged) + Q_PROPERTY(QGCVideoStreamInfo* currentStreamInstance READ currentStreamInstance NOTIFY currentStreamChanged) + Q_PROPERTY(quint32 recordTime READ recordTime NOTIFY recordTimeChanged) + Q_PROPERTY(QString recordTimeStr READ recordTimeStr NOTIFY recordTimeChanged) Q_INVOKABLE virtual void setVideoMode (); Q_INVOKABLE virtual void setPhotoMode (); @@ -138,6 +176,8 @@ public: Q_INVOKABLE virtual void stepZoom (int direction); Q_INVOKABLE virtual void startZoom (int direction); Q_INVOKABLE virtual void stopZoom (); + Q_INVOKABLE virtual void stopStream (); + Q_INVOKABLE virtual void resumeStream (); virtual int version () { return _version; } virtual QString modelName () { return _modelName; } @@ -151,6 +191,7 @@ public: virtual bool hasModes () { return _info.flags & CAMERA_CAP_FLAGS_HAS_MODES; } virtual bool hasZoom () { return _info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; } virtual bool hasFocus () { return _info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; } + virtual bool hasVideoStream () { return _info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; } virtual bool photosInVideoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; } virtual bool videoInPhotoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; } @@ -170,12 +211,21 @@ public: virtual qreal zoomLevel () { return _zoomLevel; } virtual qreal focusLevel () { return _focusLevel; } + virtual QmlObjectListModel* streams () { return &_streams; } + virtual QGCVideoStreamInfo* currentStreamInstance(); + virtual int currentStream () { return _currentStream; } + virtual void setCurrentStream (int stream); + virtual bool autoStream (); + virtual quint32 recordTime () { return _recordTime; } + virtual QString recordTimeStr (); + virtual Fact* exposureMode (); virtual Fact* ev (); virtual Fact* iso (); virtual Fact* shutter (); virtual Fact* aperture (); virtual Fact* wb (); + virtual Fact* mode (); virtual void setZoomLevel (qreal level); virtual void setFocusLevel (qreal level); @@ -189,6 +239,8 @@ public: virtual void handleParamAck (const mavlink_param_ext_ack_t& ack); virtual void handleParamValue (const mavlink_param_ext_value_t& value); virtual void handleStorageInfo (const mavlink_storage_information_t& st); + virtual void handleVideoInfo (const mavlink_video_stream_information_t *vi); + virtual void handleVideoStatus (const mavlink_video_stream_status_t *vs); //-- Notify controller a parameter has changed virtual void factChanged (Fact* pFact); @@ -212,11 +264,18 @@ signals: void parametersReady (); void zoomLevelChanged (); void focusLevelChanged (); + void streamsChanged (); + void currentStreamChanged (); + void autoStreamChanged (); + void recordTimeChanged (); protected: virtual void _setVideoStatus (VideoStatus status); virtual void _setPhotoStatus (PhotoStatus status); virtual void _setCameraMode (CameraMode mode); + virtual void _requestStreamInfo (uint8_t streamID); + virtual void _requestStreamStatus (uint8_t streamID); + virtual QGCVideoStreamInfo* _findStream (uint8_t streamID); protected slots: virtual void _initWhenReady (); @@ -229,7 +288,10 @@ protected slots: virtual void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle); virtual void _dataReady (QByteArray data); virtual void _paramDone (); - + virtual void _streamTimeout (); + virtual void _streamStatusTimeout (); + virtual void _recTimerHandler (); + virtual void _checkForVideoStreams (); private: bool _handleLocalization (QByteArray& bytes); @@ -252,26 +314,26 @@ private: QString _getParamName (const char* param_id); protected: - Vehicle* _vehicle; - int _compID; + Vehicle* _vehicle = nullptr; + int _compID = 0; mavlink_camera_information_t _info; - int _version; - bool _cached; - bool _paramComplete; - qreal _zoomLevel; - qreal _focusLevel; - uint32_t _storageFree; - uint32_t _storageTotal; - QNetworkAccessManager* _netManager; + int _version = 0; + bool _cached = false; + bool _paramComplete = false; + qreal _zoomLevel = 0.0; + qreal _focusLevel = 0.0; + uint32_t _storageFree = 0; + uint32_t _storageTotal = 0; + QNetworkAccessManager* _netManager = nullptr; QString _modelName; QString _vendor; QString _cacheFile; - CameraMode _cameraMode; - PhotoMode _photoMode; - qreal _photoLapse; - int _photoLapseCount; - VideoStatus _video_status; - PhotoStatus _photo_status; + CameraMode _cameraMode = CAM_MODE_UNDEFINED; + PhotoMode _photoMode = PHOTO_CAPTURE_SINGLE; + qreal _photoLapse = 1.0; + int _photoLapseCount = 0; + VideoStatus _video_status = VIDEO_CAPTURE_STATUS_UNDEFINED; + PhotoStatus _photo_status = PHOTO_CAPTURE_STATUS_UNDEFINED; QStringList _activeSettings; QStringList _settings; QTimer _captureStatusTimer; @@ -280,10 +342,20 @@ protected: QMap _originalOptNames; QMap _originalOptValues; QMap _paramIO; - int _storageInfoRetries; - int _captureInfoRetries; - bool _resetting; + int _storageInfoRetries = 0; + int _captureInfoRetries = 0; + bool _resetting = false; + QTimer _recTimer; + QTime _recTime; + uint32_t _recordTime = 0; //-- Parameters that require a full update QMap _requestUpdates; QStringList _updatesToRequest; + //-- Video Streams + int _requestCount = 0; + int _currentStream = 0; + int _expectedCount = 1; + QTimer _streamInfoTimer; + QTimer _streamStatusTimer; + QmlObjectListModel _streams; }; diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc index 8610a6f22cee840ef088f6c0c41546fea7d30c54..c6c0e3ec3074d9153d9a4512e6440c87d4dae008 100644 --- a/src/Camera/QGCCameraManager.cc +++ b/src/Camera/QGCCameraManager.cc @@ -11,6 +11,12 @@ QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog") +//----------------------------------------------------------------------------- +QGCCameraManager::CameraStruct::CameraStruct(QObject* parent) + : QObject(parent) +{ +} + //----------------------------------------------------------------------------- QGCCameraManager::QGCCameraManager(Vehicle *vehicle) : _vehicle(vehicle) @@ -19,8 +25,11 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle) qCDebug(CameraManagerLog) << "QGCCameraManager Created"; connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady); connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived); + connect(&_cameraTimer, &QTimer::timeout, this, &QGCCameraManager::_cameraTimeout); + _cameraTimer.setSingleShot(false); _lastZoomChange.start(); _lastCameraChange.start(); + _cameraTimer.start(500); } //----------------------------------------------------------------------------- @@ -35,6 +44,7 @@ QGCCameraManager::setCurrentCamera(int sel) if(sel != _currentCamera && sel >= 0 && sel < _cameras.count()) { _currentCamera = sel; emit currentCameraChanged(); + emit streamChanged(); } } @@ -80,6 +90,12 @@ QGCCameraManager::_mavlinkMessageReceived(const mavlink_message_t& message) case MAVLINK_MSG_ID_PARAM_EXT_VALUE: _handleParamValue(message); break; + case MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION: + _handleVideoStreamInfo(message); + break; + case MAVLINK_MSG_ID_VIDEO_STREAM_STATUS: + _handleVideoStreamStatus(message); + break; } } } @@ -90,16 +106,63 @@ QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message) { mavlink_heartbeat_t heartbeat; mavlink_msg_heartbeat_decode(&message, &heartbeat); - //-- If this heartbeat is from a different node within the vehicle + //-- If this heartbeat is from a different component within the vehicle if(_vehicleReadyState && _vehicle->id() == message.sysid && _vehicle->defaultComponentId() != message.compid) { - if(!_cameraInfoRequested.contains(message.compid)) { - _cameraInfoRequested[message.compid] = true; + //-- First time hearing from this one? + if(!_cameraInfoRequest.contains(message.compid)) { + CameraStruct* pInfo = new CameraStruct(this); + pInfo->lastHeartbeat.start(); + _cameraInfoRequest[message.compid] = pInfo; //-- Request camera info _requestCameraInfo(message.compid); + } else { + //-- Check if we have indeed received the camera info + if(_cameraInfoRequest[message.compid]->infoReceived) { + //-- We have it. Just update the heartbeat timeout + _cameraInfoRequest[message.compid]->lastHeartbeat.start(); + } else { + //-- Try again. Maybe. + if(_cameraInfoRequest[message.compid]->lastHeartbeat.elapsed() > 2000) { + if(_cameraInfoRequest[message.compid]->tryCount > 3) { + if(!_cameraInfoRequest[message.compid]->gaveUp) { + _cameraInfoRequest[message.compid]->gaveUp = true; + qWarning() << "Giving up requesting camera info from" << _vehicle->id() << message.compid; + } + } else { + _cameraInfoRequest[message.compid]->tryCount++; + //-- Request camera info. Again. It could be something other than a camera, in which + // case, we won't ever receive it. + _requestCameraInfo(message.compid); + } + } + } } } } +//----------------------------------------------------------------------------- +QGCCameraControl* +QGCCameraManager::currentCameraInstance() +{ + if(_currentCamera < _cameras.count() && _cameras.count()) { + QGCCameraControl* pCamera = qobject_cast(_cameras[_currentCamera]); + return pCamera; + } + return nullptr; +} + +//----------------------------------------------------------------------------- +QGCVideoStreamInfo* +QGCCameraManager::currentStreamInstance() +{ + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + QGCVideoStreamInfo* pInfo = pCamera->currentStreamInstance(); + return pInfo; + } + return nullptr; +} + //----------------------------------------------------------------------------- QGCCameraControl* QGCCameraManager::_findCamera(int id) @@ -125,9 +188,9 @@ void QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message) { //-- Have we requested it? - if(_cameraInfoRequested.contains(message.compid) && _cameraInfoRequested[message.compid]) { + if(_cameraInfoRequest.contains(message.compid) && !_cameraInfoRequest[message.compid]->infoReceived) { //-- Flag it as done - _cameraInfoRequested[message.compid] = false; + _cameraInfoRequest[message.compid]->infoReceived = true; mavlink_camera_information_t info; mavlink_msg_camera_information_decode(&message, &info); qCDebug(CameraManagerLog) << "_handleCameraInfo:" << reinterpret_cast(info.model_name) << reinterpret_cast(info.vendor_name) << "Comp ID:" << message.compid; @@ -142,6 +205,51 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message) } } +//----------------------------------------------------------------------------- +void +QGCCameraManager::_cameraTimeout() +{ + //-- Iterate cameras + for(int i = 0; i < _cameraInfoRequest.count(); i++) { + if(_cameraInfoRequest[i]) { + //-- Have we received a camera info message? + if(_cameraInfoRequest[i]->infoReceived) { + //-- Has the camera stopped talking to us? + if(_cameraInfoRequest[i]->lastHeartbeat.elapsed() > 5000) { + //-- Camera is gone. Remove it. + QGCCameraControl* pCamera = _findCamera(i); + qWarning() << "Camera" << pCamera->modelName() << "stopped transmitting. Removing from list."; + int idx = _cameraLabels.indexOf(pCamera->modelName()); + if(idx >= 0) { + _cameraLabels.removeAt(idx); + } + idx = _cameras.indexOf(pCamera); + if(idx >= 0) { + _cameras.removeAt(idx); + } + bool autoStream = pCamera->autoStream(); + pCamera->deleteLater(); + delete _cameraInfoRequest[i]; + _cameraInfoRequest.remove(i); + emit cameraLabelsChanged(); + //-- If we have another camera, switch current camera. + if(_cameras.count()) { + setCurrentCamera(0); + } else { + //-- We're out of cameras + emit camerasChanged(); + if(autoStream) { + emit streamChanged(); + } + } + //-- Exit loop. + return; + } + } + } + } +} + //----------------------------------------------------------------------------- void QGCCameraManager::_handleCaptureStatus(const mavlink_message_t &message) @@ -202,6 +310,30 @@ QGCCameraManager::_handleParamValue(const mavlink_message_t& message) } } +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleVideoStreamInfo(const mavlink_message_t& message) +{ + QGCCameraControl* pCamera = _findCamera(message.compid); + if(pCamera) { + mavlink_video_stream_information_t streamInfo; + mavlink_msg_video_stream_information_decode(&message, &streamInfo); + pCamera->handleVideoInfo(&streamInfo); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleVideoStreamStatus(const mavlink_message_t& message) +{ + QGCCameraControl* pCamera = _findCamera(message.compid); + if(pCamera) { + mavlink_video_stream_status_t streamStatus; + mavlink_msg_video_stream_status_decode(&message, &streamStatus); + pCamera->handleVideoStatus(&streamStatus); + } +} + //----------------------------------------------------------------------------- void QGCCameraManager::_requestCameraInfo(int compID) @@ -224,11 +356,13 @@ QGCCameraManager::_activeJoystickChanged(Joystick* joystick) if(_activeJoystick) { disconnect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom); disconnect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera); + disconnect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream); } _activeJoystick = joystick; if(_activeJoystick) { connect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom); connect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera); + connect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream); } } @@ -239,11 +373,9 @@ QGCCameraManager::_stepZoom(int direction) if(_lastZoomChange.elapsed() > 250) { _lastZoomChange.start(); qCDebug(CameraManagerLog) << "Step Camera Zoom" << direction; - if(_cameras.count() && _cameras[_currentCamera]) { - QGCCameraControl* pCamera = qobject_cast(_cameras[_currentCamera]); - if(pCamera) { - pCamera->stepZoom(direction); - } + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + pCamera->stepZoom(direction); } } } @@ -262,4 +394,21 @@ QGCCameraManager::_stepCamera(int direction) } } +//----------------------------------------------------------------------------- +void +QGCCameraManager::_stepStream(int direction) +{ + if(_lastCameraChange.elapsed() > 1000) { + _lastCameraChange.start(); + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + qCDebug(CameraManagerLog) << "Step Camera Stream" << direction; + int c = pCamera->currentStream() + direction; + if(c < 0) c = pCamera->streams()->count() - 1; + if(c >= pCamera->streams()->count()) c = 0; + pCamera->setCurrentStream(c); + } + } +} + diff --git a/src/Camera/QGCCameraManager.h b/src/Camera/QGCCameraManager.h index b0c8b9c60292ffd4af530441f47748b904ecd63c..6b882480cfc9ed0e34c11d88e72ed5eb7e921afc 100644 --- a/src/Camera/QGCCameraManager.h +++ b/src/Camera/QGCCameraManager.h @@ -27,9 +27,10 @@ public: QGCCameraManager(Vehicle* vehicle); virtual ~QGCCameraManager(); - Q_PROPERTY(QmlObjectListModel* cameras READ cameras NOTIFY camerasChanged) - Q_PROPERTY(QStringList cameraLabels READ cameraLabels NOTIFY cameraLabelsChanged) - Q_PROPERTY(int currentCamera READ currentCamera WRITE setCurrentCamera NOTIFY currentCameraChanged) + Q_PROPERTY(QmlObjectListModel* cameras READ cameras NOTIFY camerasChanged) + Q_PROPERTY(QStringList cameraLabels READ cameraLabels NOTIFY cameraLabelsChanged) + Q_PROPERTY(QGCCameraControl* currentCameraInstance READ currentCameraInstance NOTIFY currentCameraChanged) + Q_PROPERTY(int currentCamera READ currentCamera WRITE setCurrentCamera NOTIFY currentCameraChanged) //-- Return a list of cameras provided by this vehicle virtual QmlObjectListModel* cameras () { return &_cameras; } @@ -37,13 +38,17 @@ public: virtual QStringList cameraLabels () { return _cameraLabels; } //-- Current selected camera virtual int currentCamera () { return _currentCamera; } + virtual QGCCameraControl* currentCameraInstance(); //-- Set current camera virtual void setCurrentCamera (int sel); + //-- Current stream + virtual QGCVideoStreamInfo* currentStreamInstance(); signals: void camerasChanged (); void cameraLabelsChanged (); void currentCameraChanged (); + void streamChanged (); protected slots: virtual void _vehicleReady (bool ready); @@ -51,6 +56,8 @@ protected slots: virtual void _activeJoystickChanged (Joystick* joystick); virtual void _stepZoom (int direction); virtual void _stepCamera (int direction); + virtual void _stepStream (int direction); + virtual void _cameraTimeout (); protected: virtual QGCCameraControl* _findCamera (int id); @@ -62,16 +69,29 @@ protected: virtual void _handleParamAck (const mavlink_message_t& message); virtual void _handleParamValue (const mavlink_message_t& message); virtual void _handleCaptureStatus (const mavlink_message_t& message); + virtual void _handleVideoStreamInfo (const mavlink_message_t& message); + virtual void _handleVideoStreamStatus(const mavlink_message_t& message); protected: + + class CameraStruct : public QObject { + public: + CameraStruct(QObject* parent); + QTime lastHeartbeat; + bool infoReceived = false; + bool gaveUp = false; + int tryCount = 0; + }; + Vehicle* _vehicle = nullptr; Joystick* _activeJoystick = nullptr; bool _vehicleReadyState = false; int _currentTask = 0; QmlObjectListModel _cameras; QStringList _cameraLabels; - QMap _cameraInfoRequested; int _currentCamera = 0; QTime _lastZoomChange; QTime _lastCameraChange; + QTimer _cameraTimer; + QMap _cameraInfoRequest; }; diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index 36be213df5a08e7003d098be406b14c3b7259359..391f79b1ca5025c2b6df1fff0658596b70172557 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -27,6 +27,7 @@ Fact::Fact(QObject* parent) , _sendValueChangedSignals (true) , _deferredValueChangeSignal(false) , _valueSliderModel (nullptr) + , _ignoreQGCRebootRequired (false) { FactMetaData* metaData = new FactMetaData(_type, this); setMetaData(metaData); @@ -44,6 +45,7 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec , _sendValueChangedSignals (true) , _deferredValueChangeSignal(false) , _valueSliderModel (nullptr) + , _ignoreQGCRebootRequired (false) { FactMetaData* metaData = new FactMetaData(_type, this); setMetaData(metaData); @@ -61,6 +63,7 @@ Fact::Fact(const QString& settingsGroup, FactMetaData* metaData, QObject* parent , _sendValueChangedSignals (true) , _deferredValueChangeSignal(false) , _valueSliderModel (nullptr) + , _ignoreQGCRebootRequired (false) { qgcApp()->toolbox()->corePlugin()->adjustSettingMetaData(settingsGroup, *metaData); setMetaData(metaData, true /* setDefaultFromMetaData */); @@ -90,7 +93,8 @@ const Fact& Fact::operator=(const Fact& other) _type = other._type; _sendValueChangedSignals = other._sendValueChangedSignals; _deferredValueChangeSignal = other._deferredValueChangeSignal; - _valueSliderModel = nullptr; + _valueSliderModel = nullptr; + _ignoreQGCRebootRequired = other._ignoreQGCRebootRequired; if (_metaData && other._metaData) { *_metaData = *other._metaData; } else { @@ -615,7 +619,9 @@ bool Fact::vehicleRebootRequired(void) const bool Fact::qgcRebootRequired(void) const { - if (_metaData) { + if (_ignoreQGCRebootRequired) { + return false; + } else if (_metaData) { return _metaData->qgcRebootRequired(); } else { qWarning() << kMissingMetadata << name(); @@ -743,3 +749,8 @@ void Fact::_checkForRebootMessaging(void) } } } + +void Fact::_setIgnoreQGCRebootRequired(bool ignore) +{ + _ignoreQGCRebootRequired = ignore; +} diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h index 1490595d061e87c232396c7babf49d264814881c..f8ffcc1589e046c27c43b384c6b5db38b4bb0438 100644 --- a/src/FactSystem/Fact.h +++ b/src/FactSystem/Fact.h @@ -129,6 +129,10 @@ public: bool writeOnly (void) const; bool volatileValue (void) const; + // Internal hack to allow changes to fact which do not signal reboot. Currently used by font point size + // code in ScreenTools.qml to set initial sizing at first boot. + Q_INVOKABLE void _setIgnoreQGCRebootRequired(bool ignore); + Q_INVOKABLE FactValueSliderListModel* valueSliderModel(void); /// Returns the values as a string with full 18 digit precision if float/double. @@ -208,6 +212,7 @@ protected: bool _sendValueChangedSignals; bool _deferredValueChangeSignal; FactValueSliderListModel* _valueSliderModel; + bool _ignoreQGCRebootRequired; }; #endif diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index c8c9a76aba56a7a67bdda618158a589f5cdb340f..df059a4fec4a1de9c5b3a740a2a1a1a3ecf2e036 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -228,13 +228,6 @@ bool APMFirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_m return found; } -int APMFirmwarePlugin::manualControlReservedButtonCount(void) -{ - // We don't know whether the firmware is going to used any of these buttons. - // So reserve them all. - return -1; -} - void APMFirmwarePlugin::_handleIncomingParamValue(Vehicle* vehicle, mavlink_message_t* message) { Q_UNUSED(vehicle); diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index bac34679a75151a1e54e6f5e002e7603784a2a3f..3abab25ee0976d6ab31f5cd4dd6f51926bf358cb 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -90,7 +90,6 @@ public: void pauseVehicle (Vehicle* vehicle) override; void guidedModeRTL (Vehicle* vehicle) override; void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeChange) override; - int manualControlReservedButtonCount(void) override; bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override; void adjustOutgoingMavlinkMessage (Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message) override; virtual void initializeStreamRates (Vehicle* vehicle); diff --git a/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc index a77f5e50b541cb5682c3c070e8dc674bdc1b11df..eb0fe9378efb06a5c22f6313f47ef1df0ac48f73 100644 --- a/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc @@ -164,11 +164,6 @@ int ArduSubFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersi return majorVersionNumber == 3 ? 6 : Vehicle::versionNotSetValue; } -int ArduSubFirmwarePlugin::manualControlReservedButtonCount(void) -{ - return 0; -} - void ArduSubFirmwarePlugin::initializeStreamRates(Vehicle* vehicle) { vehicle->requestDataStream(MAV_DATA_STREAM_RAW_SENSORS, 2); vehicle->requestDataStream(MAV_DATA_STREAM_EXTENDED_STATUS, 2); diff --git a/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h index 1d69bfbfb854760a37e0b16f8c5d874a7f60819f..6a356059a18728fc12bcbd658f61aa941da127eb 100644 --- a/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h @@ -110,9 +110,6 @@ public: QList supportedMissionCommands(void) final; - // Overrides from FirmwarePlugin - int manualControlReservedButtonCount(void) final; - int defaultJoystickTXMode(void) final { return 3; } void initializeStreamRates(Vehicle* vehicle) override final; diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index db2a86969394f52d3033e41e4e42a1e4d2c43960..b7cfadff634b3a3cee4b3c8f3038e3db3a7133b5 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -115,13 +115,6 @@ bool FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode return false; } -int FirmwarePlugin::manualControlReservedButtonCount(void) -{ - // We don't know whether the firmware is going to used any of these buttons. - // So reserve them all. - return -1; -} - int FirmwarePlugin::defaultJoystickTXMode(void) { return 2; diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index 81d2d2abcd7e0e9a4fc87b1142ae2756b4c70a6b..bcae4c08b7d33b688987469028e945fff0ca98bf 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -146,14 +146,6 @@ public: /// @param altitudeChange If > 0, go up by amount specified, if < 0, go down by amount specified virtual void guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange); - /// FIXME: This isn't quite correct being here. All code for Joystick suvehicleTypepport is currently firmware specific - /// not just this. I'm going to try to change that. If not, this will need to be removed. - /// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink - /// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches. - /// The remainder can be assigned to Vehicle actions. - /// @return -1: reserver all buttons, >0 number of buttons to reserve - virtual int manualControlReservedButtonCount(void); - /// Default tx mode to apply to joystick axes /// TX modes are as outlined here: http://www.rc-airplane-world.com/rc-transmitter-modes.html virtual int defaultJoystickTXMode(void); diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 7b19ebf5c07fef25514a649149032b44b34cbbc8..44eb73ff104ccf7c074ddc815264a15a20bb8c8d 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -225,11 +225,6 @@ bool PX4FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_m return found; } -int PX4FirmwarePlugin::manualControlReservedButtonCount(void) -{ - return 0; // 0 buttons reserved for rc switch simulation -} - bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) { int available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability; diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index 2c8059b61361edacda90a4d1d17947de254c05d3..c70b43a0b504ad05107665f1d95c4b2b60d9299f 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -52,7 +52,6 @@ public: double minimumTakeoffAltitude (Vehicle* vehicle) override; void startMission (Vehicle* vehicle) override; bool isGuidedMode (const Vehicle* vehicle) const override; - int manualControlReservedButtonCount(void) override; void initializeVehicle (Vehicle* vehicle) override; bool sendHomePositionToVehicle (void) override; void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) override; diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 66dcb0828a294d2e86bf5a5eaefab26e3c6d7057..5e5a5ae14c77563e10188573cc99b6e0895fd74f 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -415,6 +415,20 @@ Set to 2 to use heading from motion capture Active high + + PWM neutral output on trigger pin + 1000 + 2000 + us + true + + + PWM output to trigger shot + 1000 + 2000 + us + true + @@ -7633,7 +7647,7 @@ to takeoff is reached 1000 true - + Mission Log If enabled, a small additional "mission" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more). true @@ -8248,6 +8262,21 @@ is less than 50% of this value This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user to fine tune the board offset in the event of misalignment. deg + + Serial Configuration for Lanbao PSK-CM8JL65-CC5 + Configure on which serial port to run Lanbao PSK-CM8JL65-CC5. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + + SMBUS Smart battery driver (BQ40Z50) @@ -8341,13 +8370,6 @@ is less than 50% of this value C 3 - - IMU heater controller feedforward value - 0 - 1.0 - microseconds - 3 - IMU heater controller integrator gain value 0 @@ -8355,10 +8377,10 @@ is less than 50% of this value microseconds/C 3 - + IMU heater controller proportional gain value 0 - 1.0 + 2.0 microseconds/C 3 diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index ce8a6eaf72a965739f22a9131934921f7a22c5d7..36fe389a33626ffbfa29281df5ff4d0dbf733e17 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -408,7 +408,7 @@ FlightMap { id: orbitCenterIndicator anchorPoint.x: sourceItem.anchorPointX anchorPoint.y: sourceItem.anchorPointY - coordinate: _activeVehicle ? _activeVehicle.orbitMapCircle.center : undefined + coordinate: _activeVehicle ? _activeVehicle.orbitMapCircle.center : QtPositioning.coordinate() visible: orbitTelemetryCircle.visible sourceItem: MissionItemIndexLabel { diff --git a/src/FlightDisplay/FlightDisplayViewVideo.qml b/src/FlightDisplay/FlightDisplayViewVideo.qml index ed59ab671ae69e0ea8de4ba607a9d6a7ea7a6919..365c05713d6b598d9cef31accbc7ce5a91992af4 100644 --- a/src/FlightDisplay/FlightDisplayViewVideo.qml +++ b/src/FlightDisplay/FlightDisplayViewVideo.qml @@ -8,8 +8,8 @@ ****************************************************************************/ -import QtQuick 2.3 -import QtQuick.Controls 1.2 +import QtQuick 2.11 +import QtQuick.Controls 2.4 import QGroundControl 1.0 import QGroundControl.FlightDisplay 1.0 @@ -28,6 +28,11 @@ Item { property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _dynamicCameras: _activeVehicle ? _activeVehicle.dynamicCameras : null property bool _connected: _activeVehicle ? !_activeVehicle.connectionLost : false + property int _curCameraIndex: _dynamicCameras ? _dynamicCameras.currentCamera : 0 + property bool _isCamera: _dynamicCameras ? _dynamicCameras.cameras.count > 0 : false + property var _camera: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex) : null + property bool _hasZoom: _camera && _camera.hasZoom + property int _fitMode: QGroundControl.settingsManager.videoSettings.videoFit.rawValue Rectangle { id: noVideo anchors.fill: parent @@ -51,10 +56,26 @@ Item { anchors.fill: parent color: "black" visible: _videoReceiver && _videoReceiver.videoRunning + function getWidth() { + //-- Fit Width or Stretch + if(_fitMode === 0 || _fitMode === 2) { + return parent.width + } + //-- Fit Height + return _ar != 0.0 ? parent.height * _ar : parent.width + } + function getHeight() { + //-- Fit Height or Stretch + if(_fitMode === 1 || _fitMode === 2) { + return parent.height + } + //-- Fit Width + return _ar != 0.0 ? parent.width * (1 / _ar) : parent.height + } QGCVideoBackground { id: videoContent - height: parent.height - width: _ar != 0.0 ? height * _ar : parent.width + height: parent.getHeight() + width: parent.getWidth() anchors.centerIn: parent receiver: _videoReceiver display: _videoReceiver && _videoReceiver.videoSurface @@ -104,5 +125,25 @@ Item { QGroundControl.videoManager.fullScreen = !QGroundControl.videoManager.fullScreen } } + PinchArea { + id: pinchZoom + enabled: _hasZoom + anchors.fill: parent + onPinchStarted: pinchZoom.zoom = 0 + onPinchUpdated: { + if(_hasZoom) { + var z = 0 + if(pinch.scale < 1) { + z = Math.round(pinch.scale * -10) + } else { + z = Math.round(pinch.scale) + } + if(pinchZoom.zoom != z) { + _camera.stepZoom(z) + } + } + } + property int zoom: 0 + } } } diff --git a/src/FlightDisplay/VideoManager.cc b/src/FlightDisplay/VideoManager.cc index 5451dad2144f074c7e8b9120d19b915d2b0a34f6..3f2491157c9068d3b47622d2849aaf29e4a5be00 100644 --- a/src/FlightDisplay/VideoManager.cc +++ b/src/FlightDisplay/VideoManager.cc @@ -28,7 +28,7 @@ #include "MultiVehicleManager.h" #include "Settings/SettingsManager.h" #include "Vehicle.h" -#include "JoystickManager.h" +#include "QGCCameraManager.h" QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog") @@ -36,9 +36,6 @@ QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog") VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox) : QGCTool(app, toolbox) { - _streamInfo = {}; - _lastZoomChange.start(); - _lastStreamChange.start(); } //----------------------------------------------------------------------------- @@ -64,11 +61,9 @@ VideoManager::setToolbox(QGCToolbox *toolbox) connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged); connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged); connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged); - connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_streamInfoChanged); + connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged); MultiVehicleManager *pVehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); connect(pVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle); - JoystickManager *pJoyMgr = qgcApp()->toolbox()->joystickManager(); - connect(pJoyMgr, &JoystickManager::activeJoystickChanged, this, &VideoManager::_activeJoystickChanged); #if defined(QGC_GST_STREAMING) #ifndef QGC_DISABLE_UVC @@ -92,14 +87,26 @@ VideoManager::setToolbox(QGCToolbox *toolbox) //----------------------------------------------------------------------------- double VideoManager::aspectRatio() { - if(isAutoStream()) { - if(_streamInfo.resolution_h && _streamInfo.resolution_v) { - return static_cast(_streamInfo.resolution_h) / static_cast(_streamInfo.resolution_v); + if(_activeVehicle && _activeVehicle->dynamicCameras()) { + QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance(); + if(pInfo) { + return pInfo->aspectRatio(); + } + } + return _videoSettings->aspectRatio()->rawValue().toDouble(); +} + +//----------------------------------------------------------------------------- +bool +VideoManager::autoStreamConfigured() +{ + if(_activeVehicle && _activeVehicle->dynamicCameras()) { + QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance(); + if(pInfo) { + return !pInfo->uri().isEmpty(); } - return 1.0; - } else { - return _videoSettings->aspectRatio()->rawValue().toDouble(); } + return false; } //----------------------------------------------------------------------------- @@ -156,6 +163,9 @@ VideoManager::_tcpUrlChanged() bool VideoManager::hasVideo() { + if(autoStreamConfigured()) { + return true; + } QString videoSource = _videoSettings->videoSource()->rawValue().toString(); return !videoSource.isEmpty() && videoSource != VideoSettings::videoSourceNoVideo && videoSource != VideoSettings::videoDisabled; } @@ -169,21 +179,9 @@ VideoManager::isGStreamer() return videoSource == VideoSettings::videoSourceUDP || videoSource == VideoSettings::videoSourceRTSP || - videoSource == VideoSettings::videoSourceAuto || videoSource == VideoSettings::videoSourceTCP || - videoSource == VideoSettings::videoSourceMPEGTS; -#else - return false; -#endif -} - -//----------------------------------------------------------------------------- -bool -VideoManager::isAutoStream() -{ -#if defined(QGC_GST_STREAMING) - QString videoSource = _videoSettings->videoSource()->rawValue().toString(); - return videoSource == VideoSettings::videoSourceAuto; + videoSource == VideoSettings::videoSourceMPEGTS || + autoStreamConfigured(); #else return false; #endif @@ -204,6 +202,28 @@ VideoManager::_updateSettings() { if(!_videoSettings || !_videoReceiver) return; + //-- Auto discovery + if(_activeVehicle && _activeVehicle->dynamicCameras()) { + QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance(); + if(pInfo) { + switch(pInfo->type()) { + case VIDEO_STREAM_TYPE_RTSP: + case VIDEO_STREAM_TYPE_TCP_MPEG: + _videoReceiver->setUri(pInfo->uri()); + break; + case VIDEO_STREAM_TYPE_RTPUDP: + _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(pInfo->uri())); + break; + case VIDEO_STREAM_TYPE_MPEG_TS_H264: + _videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri())); + break; + default: + _videoReceiver->setUri(pInfo->uri()); + break; + } + return; + } + } QString source = _videoSettings->videoSource()->rawValue().toString(); if (source == VideoSettings::videoSourceUDP) _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); @@ -213,24 +233,6 @@ VideoManager::_updateSettings() _videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString()); else if (source == VideoSettings::videoSourceTCP) _videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString())); - //-- Auto discovery - else if (isAutoStream()) { - switch(_streamInfo.type) { - case VIDEO_STREAM_TYPE_RTSP: - case VIDEO_STREAM_TYPE_TCP_MPEG: - _videoReceiver->setUri(QString(_streamInfo.uri)); - break; - case VIDEO_STREAM_TYPE_RTPUDP: - _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(atoi(_streamInfo.uri))); - break; - case VIDEO_STREAM_TYPE_MPEG_TS_H264: - _videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(atoi(_streamInfo.uri))); - break; - default: - _videoReceiver->setUri(QString(_streamInfo.uri)); - break; - } - } } //----------------------------------------------------------------------------- @@ -252,116 +254,31 @@ void VideoManager::_setActiveVehicle(Vehicle* vehicle) { if(_activeVehicle) { - disconnect(_activeVehicle, &Vehicle::mavlinkMessageReceived, this, &VideoManager::_vehicleMessageReceived); + if(_activeVehicle->dynamicCameras()) { + QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance(); + if(pCamera) { + pCamera->stopStream(); + } + disconnect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo); + } } _activeVehicle = vehicle; if(_activeVehicle) { - if(isAutoStream()) { - _videoReceiver->stop(); - } - //-- Video Stream Discovery - connect(_activeVehicle, &Vehicle::mavlinkMessageReceived, this, &VideoManager::_vehicleMessageReceived); - qCDebug(VideoManagerLog) << "Requesting video stream info"; - _activeVehicle->sendMavCommand( - MAV_COMP_ID_ALL, // Target component - MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, // Command id - false, // ShowError - 1, // First camera only - 1); // Request video stream information - } -} - -//---------------------------------------------------------------------------------------- -void -VideoManager::_vehicleMessageReceived(const mavlink_message_t& message) -{ - //-- For now we only handle one stream. There is no UI to pick different streams. - if(message.msgid == MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION) { - _videoStreamCompID = message.compid; - mavlink_msg_video_stream_information_decode(&message, &_streamInfo); - _hasAutoStream = true; - qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri; - _restartVideo(); - emit streamInfoChanged(); - } -} - -//---------------------------------------------------------------------------------------- -void -VideoManager::_activeJoystickChanged(Joystick* joystick) -{ - if(_activeJoystick) { - disconnect(_activeJoystick, &Joystick::stepZoom, this, &VideoManager::stepZoom); - disconnect(_activeJoystick, &Joystick::stepStream, this, &VideoManager::stepStream); - } - _activeJoystick = joystick; - if(_activeJoystick) { - connect(_activeJoystick, &Joystick::stepZoom, this, &VideoManager::stepZoom); - connect(_activeJoystick, &Joystick::stepStream, this, &VideoManager::stepStream); - } -} - -//----------------------------------------------------------------------------- -void -VideoManager::stepZoom(int direction) -{ - if(_lastZoomChange.elapsed() > 250) { - _lastZoomChange.start(); - qCDebug(VideoManagerLog) << "Step Stream Zoom" << direction; - if(_activeVehicle && hasZoom()) { - _activeVehicle->sendMavCommand( - _videoStreamCompID, // Target component - MAV_CMD_SET_CAMERA_ZOOM, // Command id - false, // ShowError - ZOOM_TYPE_STEP, // Zoom type - direction); // Direction (-1 wide, 1 tele) - } - } -} - -//----------------------------------------------------------------------------- -void -VideoManager::stepStream(int direction) -{ - if(_lastStreamChange.elapsed() > 250) { - _lastStreamChange.start(); - int s = _currentStream + direction; - if(s < 1) s = _streamInfo.count; - if(s > _streamInfo.count) s = 1; - setCurrentStream(s); - } -} - -//----------------------------------------------------------------------------- -void -VideoManager::setCurrentStream(int stream) -{ - qCDebug(VideoManagerLog) << "Set Stream" << stream; - //-- TODO: Handle multiple streams - if(_hasAutoStream && stream <= _streamInfo.count && stream > 0 && _activeVehicle) { - if(_currentStream != stream) { - //-- Stop current stream - _activeVehicle->sendMavCommand( - _videoStreamCompID, // Target component - MAV_CMD_VIDEO_STOP_STREAMING, // Command id - false, // ShowError - _currentStream); // Stream ID - //-- Start new stream - _currentStream = stream; - _activeVehicle->sendMavCommand( - _videoStreamCompID, // Target component - MAV_CMD_VIDEO_START_STREAMING, // Command id - false, // ShowError - _currentStream); // Stream ID - _currentStream = stream; - emit currentStreamChanged(); + if(_activeVehicle->dynamicCameras()) { + connect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo); + QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance(); + if(pCamera) { + pCamera->resumeStream(); + } } } + emit autoStreamConfiguredChanged(); + _restartVideo(); } //---------------------------------------------------------------------------------------- void -VideoManager::_streamInfoChanged() +VideoManager::_aspectRatioChanged() { - emit streamInfoChanged(); + emit aspectRatioChanged(); } diff --git a/src/FlightDisplay/VideoManager.h b/src/FlightDisplay/VideoManager.h index 0831725f7a9f2d03fa9ef08126ac3007f4346ef5..8ace9fc3927ec5793e070f5d129dadb1d391cde4 100644 --- a/src/FlightDisplay/VideoManager.h +++ b/src/FlightDisplay/VideoManager.h @@ -35,18 +35,15 @@ public: VideoManager (QGCApplication* app, QGCToolbox* toolbox); ~VideoManager (); - Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged) - Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged) - Q_PROPERTY(bool isAutoStream READ isAutoStream NOTIFY isAutoStreamChanged) - Q_PROPERTY(bool isTaisync READ isTaisync WRITE setIsTaisync NOTIFY isTaisyncChanged) - Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged) - Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT) - Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged) - Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT) - Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY streamInfoChanged) - Q_PROPERTY(bool hasZoom READ hasZoom NOTIFY streamInfoChanged) - Q_PROPERTY(int streamCount READ streamCount NOTIFY streamCountChanged) - Q_PROPERTY(int currentStream READ currentStream WRITE setCurrentStream NOTIFY currentStreamChanged) + Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged) + Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged) + Q_PROPERTY(bool isTaisync READ isTaisync WRITE setIsTaisync NOTIFY isTaisyncChanged) + Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged) + Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT) + Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged) + Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT) + Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY aspectRatioChanged) + Q_PROPERTY(bool autoStreamConfigured READ autoStreamConfigured NOTIFY autoStreamConfiguredChanged) bool hasVideo (); bool isGStreamer (); @@ -54,11 +51,8 @@ public: bool isTaisync () { return _isTaisync; } bool fullScreen () { return _fullScreen; } QString videoSourceID () { return _videoSourceID; } - QString autoURL () { return QString(_streamInfo.uri); } double aspectRatio (); - bool hasZoom () { return _streamInfo.flags & VIDEO_STREAM_HAS_BASIC_ZOOM; } - int currentStream () { return _currentStream; } - int streamCount () { return _streamInfo.count; } + bool autoStreamConfigured(); VideoReceiver* videoReceiver () { return _videoReceiver; } @@ -70,15 +64,12 @@ public: void setfullScreen (bool f) { _fullScreen = f; emit fullScreenChanged(); } void setIsTaisync (bool t) { _isTaisync = t; emit isTaisyncChanged(); } - void setCurrentStream (int stream); // Override from QGCTool void setToolbox (QGCToolbox *toolbox); Q_INVOKABLE void startVideo () { _videoReceiver->start(); } Q_INVOKABLE void stopVideo () { _videoReceiver->stop(); } - Q_INVOKABLE void stepZoom (int direction); - Q_INVOKABLE void stepStream (int direction); signals: void hasVideoChanged (); @@ -86,10 +77,9 @@ signals: void videoSourceIDChanged (); void fullScreenChanged (); void isAutoStreamChanged (); - void streamInfoChanged (); void isTaisyncChanged (); - void currentStreamChanged (); - void streamCountChanged (); + void aspectRatioChanged (); + void autoStreamConfiguredChanged(); private slots: void _videoSourceChanged (); @@ -97,14 +87,12 @@ private slots: void _rtspUrlChanged (); void _tcpUrlChanged (); void _updateUVC (); - void _streamInfoChanged (); void _setActiveVehicle (Vehicle* vehicle); - void _activeJoystickChanged (Joystick* joystick); - void _vehicleMessageReceived (const mavlink_message_t& message); + void _aspectRatioChanged (); + void _restartVideo (); private: void _updateSettings (); - void _restartVideo (); private: bool _isTaisync = false; @@ -113,13 +101,6 @@ private: QString _videoSourceID; bool _fullScreen = false; Vehicle* _activeVehicle = nullptr; - Joystick* _activeJoystick = nullptr; - mavlink_video_stream_information_t _streamInfo; - bool _hasAutoStream = false; - uint8_t _videoStreamCompID = 0; - int _currentStream = 1; - QTime _lastZoomChange; - QTime _lastStreamChange; }; #endif diff --git a/src/FlightMap/Widgets/VideoPageWidget.qml b/src/FlightMap/Widgets/VideoPageWidget.qml index 10d0e6503e9577ee7784a0fcef6bae1efc2a5258..53ac549848c10da331a2281b948bffee0b69d033 100644 --- a/src/FlightMap/Widgets/VideoPageWidget.qml +++ b/src/FlightMap/Widgets/VideoPageWidget.qml @@ -7,10 +7,10 @@ * ****************************************************************************/ -import QtQuick 2.4 +import QtQuick 2.11 import QtPositioning 5.2 import QtQuick.Layouts 1.2 -import QtQuick.Controls 1.4 +import QtQuick.Controls 2.4 import QtQuick.Dialogs 1.2 import QtGraphicalEffects 1.0 @@ -54,13 +54,14 @@ Item { } // Enable/Disable Video Streaming QGCLabel { - text: qsTr("Enable Stream") - font.pointSize: ScreenTools.smallFontPointSize + text: qsTr("Enable Stream") + font.pointSize: ScreenTools.smallFontPointSize } QGCSwitch { - id: enableSwitch - enabled: _streamingEnabled - checked: QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue + id: enableSwitch + enabled: _streamingEnabled + checked: QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue + Layout.alignment: Qt.AlignHCenter onClicked: { if(checked) { QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue = 1 @@ -73,14 +74,15 @@ Item { } // Grid Lines QGCLabel { - text: qsTr("Grid Lines") - font.pointSize: ScreenTools.smallFontPointSize - visible: QGroundControl.videoManager.isGStreamer && QGroundControl.settingsManager.videoSettings.gridLines.visible + text: qsTr("Grid Lines") + font.pointSize: ScreenTools.smallFontPointSize + visible: QGroundControl.videoManager.isGStreamer && QGroundControl.settingsManager.videoSettings.gridLines.visible } QGCSwitch { - enabled: _streamingEnabled && _activeVehicle - checked: QGroundControl.settingsManager.videoSettings.gridLines.rawValue - visible: QGroundControl.videoManager.isGStreamer && QGroundControl.settingsManager.videoSettings.gridLines.visible + enabled: _streamingEnabled && _activeVehicle + checked: QGroundControl.settingsManager.videoSettings.gridLines.rawValue + visible: QGroundControl.videoManager.isGStreamer && QGroundControl.settingsManager.videoSettings.gridLines.visible + Layout.alignment: Qt.AlignHCenter onClicked: { if(checked) { QGroundControl.settingsManager.videoSettings.gridLines.rawValue = 1 @@ -89,6 +91,17 @@ Item { } } } + //-- Video Fit + QGCLabel { + text: qsTr("Video Screen Fit") + font.pointSize: ScreenTools.smallFontPointSize + } + FactComboBox { + fact: QGroundControl.settingsManager.videoSettings.videoFit + indexModel: false + Layout.alignment: Qt.AlignHCenter + } + //-- Video Recording QGCLabel { text: _recordingVideo ? qsTr("Stop Recording") : qsTr("Record Stream") font.pointSize: ScreenTools.smallFontPointSize diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index e06d9d550257beaa5ee0a828f8517cc0b8564d47..6249995d1926c55dbd1a951158859ff886896898 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -516,12 +516,6 @@ void Joystick::run(void) // Set up button pressed information - // We only send the buttons the firmwware has reserved - int reservedButtonCount = _activeVehicle->manualControlReservedButtonCount(); - if (reservedButtonCount == -1) { - reservedButtonCount = _totalButtonCount; - } - quint16 newButtonBits = 0; // New set of button which are down quint16 buttonPressedBits = 0; // Buttons pressed for manualControl signal @@ -536,12 +530,9 @@ void Joystick::run(void) // Button was up last time through, but is now down which indicates a button press qCDebug(JoystickLog) << "button triggered" << buttonIndex; - if (buttonIndex >= reservedButtonCount) { - // Button is above firmware reserved set - QString buttonAction =_rgButtonActions[buttonIndex]; - if (!buttonAction.isEmpty()) { - _buttonAction(buttonAction); - } + QString buttonAction =_rgButtonActions[buttonIndex]; + if (!buttonAction.isEmpty()) { + _buttonAction(buttonAction); } } @@ -554,6 +545,7 @@ void Joystick::run(void) qCDebug(JoystickValuesLog) << "name:roll:pitch:yaw:throttle" << name() << roll << -pitch << yaw << throttle; + // NOTE: The buttonPressedBits going to MANUAL_CONTROL are currently used by ArduSub. emit manualControl(roll, -pitch, yaw, throttle, buttonPressedBits, _activeVehicle->joystickMode()); } diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index 49c116bab9d0b7a15b7399f9d4f4822b4ef2f881..a6ce14e3bf3f9e8bbace885fbd622f0ebf15e0ef 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -153,7 +153,7 @@ "param1": { "label": "Abort Alt", "units": "m", - "default": 25.0, + "default": 0, "decimalPlaces": 2 }, "param4": { diff --git a/src/PlanView/SimpleItemEditor.qml b/src/PlanView/SimpleItemEditor.qml index e638b45aa3a9102cc24f19951b864eaa7b8e20de..8c765710cde9cbff90c65cbaa8ab2082b6866222 100644 --- a/src/PlanView/SimpleItemEditor.qml +++ b/src/PlanView/SimpleItemEditor.qml @@ -32,22 +32,32 @@ Rectangle { property string _altModeAboveTerrainHelpText: qsTr("Altitude above terrain\nActual AMSL altitude: %1 %2").arg(missionItem.amslAltAboveTerrain.valueString).arg(missionItem.amslAltAboveTerrain.units) property string _altModeTerrainFrameHelpText: qsTr("Using terrain reference frame") + readonly property string _altModeRelativeExtraUnits: qsTr(" (Rel)") + readonly property string _altModeAbsoluteExtraUnits: qsTr(" (AMSL)") + readonly property string _altModeAboveTerrainExtraUnits: qsTr(" (Abv Terr)") + readonly property string _altModeTerrainFrameExtraUnits: qsTr(" (TerrF)") + function updateAltitudeModeText() { if (missionItem.altitudeMode === _altModeRelative) { altModeLabel.text = qsTr("Altitude") altModeHelp.text = _altModeRelativeHelpText + altField.extraUnits = _altModeRelativeExtraUnits } else if (missionItem.altitudeMode === _altModeAbsolute) { altModeLabel.text = qsTr("Above Mean Sea Level") altModeHelp.text = _altModeAbsoluteHelpText + altField.extraUnits = _altModeAbsoluteExtraUnits } else if (missionItem.altitudeMode === _altModeAboveTerrain) { altModeLabel.text = qsTr("Above Terrain") altModeHelp.text = Qt.binding(function() { return _altModeAboveTerrainHelpText }) + altField.extraUnits = _altModeAboveTerrainExtraUnits } else if (missionItem.altitudeMode === _altModeTerrainFrame) { altModeLabel.text = qsTr("Terrain Frame") altModeHelp.text = _altModeTerrainFrameHelpText + altField.extraUnits = _altModeTerrainFrameExtraUnits } else { altModeLabel.text = qsTr("Internal Error") altModeHelp.text = "" + altField.extraUnits = "" } } @@ -130,11 +140,11 @@ Rectangle { id: altHamburger anchors.leftMargin: ScreenTools.defaultFontPixelWidth / 4 anchors.left: altModeLabel.right - anchors.top: altModeLabel.top - width: height - height: altModeLabel.height + anchors.verticalCenter: altModeLabel.verticalCenter + width: ScreenTools.defaultFontPixelHeight / 2 + height: width sourceSize.height: height - source: "qrc:/qmlimages/Hamburger.svg" + source: "/res/DropArrow.svg" color: qgcPal.text } @@ -166,6 +176,7 @@ Rectangle { checkable: true checked: missionItem.altitudeMode === _altModeAboveTerrain onTriggered: missionItem.altitudeMode = _altModeAboveTerrain + visible: missionItem.specifiesCoordinate } MenuItem { @@ -179,15 +190,21 @@ Rectangle { } FactTextField { - fact: missionItem.altitude + id: altField + fact: missionItem.altitude + unitsLabel: fact.units + extraUnits + anchors.left: parent.left + anchors.right: parent.right + + property string extraUnits } QGCLabel { - id: altModeHelp - anchors.left: parent.left - anchors.right: parent.right - wrapMode: Text.WordWrap - font.pointSize: ScreenTools.smallFontPointSize + id: altModeHelp + wrapMode: Text.WordWrap + font.pointSize: ScreenTools.smallFontPointSize + anchors.left: parent.left + anchors.right: parent.right } } } diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 534ef45f1f050feadf9efd1bd605606e430cfa20..b5f63f9dc780d730cd174b143701292024602aa5 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -414,6 +414,7 @@ void QGCApplication::_initCommon(void) qmlRegisterUncreatableType (kQGCVehicle, 1, 0, "ParameterManager", kRefOnly); qmlRegisterUncreatableType (kQGCVehicle, 1, 0, "QGCCameraManager", kRefOnly); qmlRegisterUncreatableType (kQGCVehicle, 1, 0, "QGCCameraControl", kRefOnly); + qmlRegisterUncreatableType (kQGCVehicle, 1, 0, "QGCVideoStreamInfo", kRefOnly); qmlRegisterUncreatableType (kQGCVehicle, 1, 0, "LinkInterface", kRefOnly); qmlRegisterUncreatableType (kQGCControllers, 1, 0, "MissionController", kRefOnly); qmlRegisterUncreatableType (kQGCControllers, 1, 0, "GeoFenceController", kRefOnly); diff --git a/src/QmlControls/ScreenTools.qml b/src/QmlControls/ScreenTools.qml index a1c786cf65a7b1ea3478eb9e69929864265171c2..3e6d456f76faa0e7949a785d86b051689a38ef57 100644 --- a/src/QmlControls/ScreenTools.qml +++ b/src/QmlControls/ScreenTools.qml @@ -181,7 +181,9 @@ Item { } else { baseSize = _defaultFont.font.pointSize; } + _appFontPointSizeFact._setIgnoreQGCRebootRequired(true) _appFontPointSizeFact.value = baseSize + _appFontPointSizeFact._setIgnoreQGCRebootRequired(false) //-- Release build doesn't get signal if(!ScreenToolsController.isDebug) _screenTools._setBasePointSize(baseSize); diff --git a/src/QmlControls/ToolStrip.qml b/src/QmlControls/ToolStrip.qml index 4ab074dec41af5aa55b7fbb1223924932477b427..8e1335c50845b1d6d4a2ad970ff3ee48196861c1 100644 --- a/src/QmlControls/ToolStrip.qml +++ b/src/QmlControls/ToolStrip.qml @@ -65,7 +65,7 @@ Rectangle { QGCLabel { anchors.horizontalCenter: parent.horizontalCenter text: title - font.pointSize: ScreenTools.smallFontPointSize + font.pointSize: ScreenTools.mobile ? ScreenTools.smallFontPointSize : ScreenTools.defaultFontPointSize } Rectangle { diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 16ea77d446c64445a64662ba733c9f32bc4a52e2..544e5e132d5cad78abde0d99d19673b8de0c5ffe 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -21,7 +21,6 @@ const char* VideoSettings::videoSourceNoVideo = "No Video Available"; const char* VideoSettings::videoDisabled = "Video Stream Disabled"; -const char* VideoSettings::videoSourceAuto = "Automatic Video Stream"; const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream"; const char* VideoSettings::videoSourceUDP = "UDP Video Stream"; const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream"; @@ -35,7 +34,6 @@ DECLARE_SETTINGGROUP(Video, "Video") // Setup enum values for videoSource settings into meta data QStringList videoSourceList; #ifdef QGC_GST_STREAMING - videoSourceList.append(videoSourceAuto); videoSourceList.append(videoSourceRTSP); #ifndef NO_UDP_VIDEO videoSourceList.append(videoSourceUDP); @@ -133,10 +131,16 @@ bool VideoSettings::streamConfigured(void) #if !defined(QGC_GST_STREAMING) return false; #endif + //-- First, check if it's disabled QString vSource = videoSource()->rawValue().toString(); if(vSource == videoSourceNoVideo || vSource == videoDisabled) { return false; } + //-- Check if it's autoconfigured + if(qgcApp()->toolbox()->videoManager()->autoStreamConfigured()) { + qCDebug(VideoManagerLog) << "Stream auto configured"; + return true; + } //-- If UDP, check if port is set if(vSource == videoSourceUDP) { qCDebug(VideoManagerLog) << "Testing configuration for UDP Stream:" << udpPort()->rawValue().toInt(); @@ -157,11 +161,6 @@ bool VideoSettings::streamConfigured(void) qCDebug(VideoManagerLog) << "Testing configuration for MPEG-TS Stream:" << udpPort()->rawValue().toInt(); return udpPort()->rawValue().toInt() != 0; } - //-- If Auto, check for received URL - if(vSource == videoSourceAuto) { - qCDebug(VideoManagerLog) << "Testing configuration for Auto Stream:" << qgcApp()->toolbox()->videoManager()->autoURL(); - return !qgcApp()->toolbox()->videoManager()->autoURL().isEmpty(); - } return false; } diff --git a/src/Settings/VideoSettings.h b/src/Settings/VideoSettings.h index ff560235851f9de52338eb4514335725def43b85..a419b6a95d8e7ee7b12f3d7dc286931349dc8026 100644 --- a/src/Settings/VideoSettings.h +++ b/src/Settings/VideoSettings.h @@ -36,14 +36,12 @@ public: DEFINE_SETTINGFACT(disableWhenDisarmed) Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged) - Q_PROPERTY(QString autoVideoSource READ autoVideoSource CONSTANT) Q_PROPERTY(QString rtspVideoSource READ rtspVideoSource CONSTANT) Q_PROPERTY(QString udpVideoSource READ udpVideoSource CONSTANT) Q_PROPERTY(QString tcpVideoSource READ tcpVideoSource CONSTANT) Q_PROPERTY(QString mpegtsVideoSource READ mpegtsVideoSource CONSTANT) bool streamConfigured (); - QString autoVideoSource () { return videoSourceAuto; } QString rtspVideoSource () { return videoSourceRTSP; } QString udpVideoSource () { return videoSourceUDP; } QString tcpVideoSource () { return videoSourceTCP; } @@ -53,7 +51,6 @@ public: static const char* videoDisabled; static const char* videoSourceUDP; static const char* videoSourceRTSP; - static const char* videoSourceAuto; static const char* videoSourceTCP; static const char* videoSourceMPEGTS; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 4b9b33ef6e71b62d3c19c916f666fd761cffff64..56a2762fc6705f9ed94a1cc9eb9b5658dd70fe0f 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2214,11 +2214,6 @@ void Vehicle::resetMessages() } } -int Vehicle::manualControlReservedButtonCount(void) -{ - return _firmwarePlugin->manualControlReservedButtonCount(); -} - void Vehicle::_loadSettings(void) { if (!_active) { diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index b330984442289aba2681bde17bca3ad7ae07baf1..7bb9072a0340612f06fbf07e6ad4cc195e424c59 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -691,12 +691,6 @@ public: /// Resets link status counters Q_INVOKABLE void resetCounters (); - /// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink - /// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches. - /// The remainder can be assigned to Vehicle actions. - /// @return -1: reserver all buttons, >0 number of buttons to reserve - Q_PROPERTY(int manualControlReservedButtonCount READ manualControlReservedButtonCount CONSTANT) - // Called when the message drop-down is invoked to clear current count Q_INVOKABLE void resetMessages(); @@ -821,8 +815,6 @@ public: /// Provides access to the Firmware Plugin for this Vehicle FirmwarePlugin* firmwarePlugin(void) { return _firmwarePlugin; } - int manualControlReservedButtonCount(void); - MissionManager* missionManager(void) { return _missionManager; } GeoFenceManager* geoFenceManager(void) { return _geoFenceManager; } RallyPointManager* rallyPointManager(void) { return _rallyPointManager; } diff --git a/src/VehicleSetup/Bootloader.h b/src/VehicleSetup/Bootloader.h index 10a1b55ad75f4711d7c27c1a7e66eea5ccf13e89..d2d3c19ca6b96104fd9a2a5a61cd084c6040ec9e 100644 --- a/src/VehicleSetup/Bootloader.h +++ b/src/VehicleSetup/Bootloader.h @@ -74,6 +74,7 @@ public: static const int boardIDTAPV1 = 64; ///< TAP V1 board, as from USB PID static const int boardIDASCV1 = 65; ///< ASC V1 board, as from USB PID static const int boardIDCrazyflie2 = 12; ///< Crazyflie 2.0 board, as from USB PID + static const int boardIDOmnibusF4SD = 42; ///< Omnibus F4 SD, as from USB PID static const int boardIDNXPHliteV3 = 28; ///< NXPHliteV3 board, as from USB PID /// Simulated board id for V3 which is a V2 board which supports larger flash space diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc index a6fa917f4d215cee20debe7298745140945ba99e..3d189f463e2a66192f5eca85b611a8556fc5a22f 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/VehicleSetup/FirmwareUpgradeController.cc @@ -262,6 +262,12 @@ void FirmwareUpgradeController::_initFirmwareHash() { AutoPilotStackPX4, DeveloperFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/master/crazyflie_default.px4"}, }; + FirmwareToUrlElement_t rgOmnibusF4SDFirmwareArray[] = { + { AutoPilotStackPX4, StableFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/stable/omnibus_f4sd_default.px4"}, + { AutoPilotStackPX4, BetaFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/beta/omnibus_f4sd_default.px4"}, + { AutoPilotStackPX4, DeveloperFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/master/omnibus_f4sd_default.px4"}, + }; + /////////////////////////////// px4flow firmwares /////////////////////////////////////// FirmwareToUrlElement_t rgPX4FLowFirmwareArray[] = { { PX4FlowPX4, StableFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Flow/master/px4flow.px4" }, @@ -447,6 +453,12 @@ void FirmwareUpgradeController::_initFirmwareHash() _rgCrazyflie2Firmware.insert(FirmwareIdentifier(element.stackType, element.firmwareType, element.vehicleType), element.url); } + size = sizeof(rgOmnibusF4SDFirmwareArray)/sizeof(rgOmnibusF4SDFirmwareArray[0]); + for (int i = 0; i < size; i++) { + const FirmwareToUrlElement_t& element = rgOmnibusF4SDFirmwareArray[i]; + _rgOmnibusF4SDFirmware.insert(FirmwareIdentifier(element.stackType, element.firmwareType, element.vehicleType), element.url); + } + size = sizeof(rgPX4FLowFirmwareArray)/sizeof(rgPX4FLowFirmwareArray[0]); for (int i = 0; i < size; i++) { const FirmwareToUrlElement_t& element = rgPX4FLowFirmwareArray[i]; @@ -514,6 +526,9 @@ QHash* FirmwareUpgradeCo case Bootloader::boardIDCrazyflie2: rgFirmware = &_rgCrazyflie2Firmware; break; + case Bootloader::boardIDOmnibusF4SD: + rgFirmware = &_rgOmnibusF4SDFirmware; + break; case Bootloader::boardIDNXPHliteV3: rgFirmware = &_rgNXPHliteV3Firmware; break; diff --git a/src/VehicleSetup/FirmwareUpgradeController.h b/src/VehicleSetup/FirmwareUpgradeController.h index d4cc36d19a0e8f66ad0554333bc5826c65a63bea..3aaed12733850f1ac4571ef0410a1d6b947a69c6 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.h +++ b/src/VehicleSetup/FirmwareUpgradeController.h @@ -211,6 +211,7 @@ private: QHash _rgTAPV1Firmware; QHash _rgASCV1Firmware; QHash _rgCrazyflie2Firmware; + QHash _rgOmnibusF4SDFirmware; QHash _rgNXPHliteV3Firmware; QHash _rgPX4FLowFirmware; QHash _rg3DRRadioFirmware; diff --git a/src/VehicleSetup/JoystickConfig.qml b/src/VehicleSetup/JoystickConfig.qml index 396a1edcaa2967150a34e2a2f519f7d775f17ec3..db6c1a4af40f6ac2a99991e9a95497087a69f4a8 100644 --- a/src/VehicleSetup/JoystickConfig.qml +++ b/src/VehicleSetup/JoystickConfig.qml @@ -620,20 +620,13 @@ SetupPage { width: parent.width spacing: ScreenTools.defaultFontPixelHeight / 3 - QGCLabel { - visible: _activeVehicle.manualControlReservedButtonCount != 0 - text: qsTr("Buttons 0-%1 reserved for firmware use").arg(reservedButtonCount) - - property int reservedButtonCount: _activeVehicle.manualControlReservedButtonCount == -1 ? _activeJoystick.totalButtonCount : _activeVehicle.manualControlReservedButtonCount - } - Repeater { id: buttonActionRepeater model: _activeJoystick ? Math.min(_activeJoystick.totalButtonCount, _maxButtons) : 0 Row { spacing: ScreenTools.defaultFontPixelWidth - visible: (_activeVehicle.manualControlReservedButtonCount == -1 ? false : modelData >= _activeVehicle.manualControlReservedButtonCount) && !_activeVehicle.supportsJSButton + visible: !_activeVehicle.supportsJSButton property bool pressed diff --git a/src/VideoStreaming/VideoReceiver.cc b/src/VideoStreaming/VideoReceiver.cc index 3ff914693a145ff8322ec56e4e5e03a423cc6ebe..22fcf2b115077a4b101f127e4a8a5a00fa790124 100644 --- a/src/VideoStreaming/VideoReceiver.cc +++ b/src/VideoStreaming/VideoReceiver.cc @@ -472,7 +472,7 @@ VideoReceiver::start() void VideoReceiver::stop() { - if(qgcApp()->runningUnitTests()) { + if(qgcApp() && qgcApp()->runningUnitTests()) { return; } #if defined(QGC_GST_STREAMING) diff --git a/src/api/QGCCorePlugin.cc b/src/api/QGCCorePlugin.cc index eebaf95401cf429422a57a1113f4d008557e80f2..eeaa2678d986dc3ea8197af98667e065caf9ad8a 100644 --- a/src/api/QGCCorePlugin.cc +++ b/src/api/QGCCorePlugin.cc @@ -18,6 +18,10 @@ #include "VideoReceiver.h" #include "QGCLoggingCategory.h" +#if !defined(__mobile__) +#include "QGCQmlWidgetHolder.h" +#endif + #include #include @@ -324,3 +328,17 @@ QString QGCCorePlugin::stableVersionCheckFileUrl(void) const return QString("https://s3-us-west-2.amazonaws.com/qgroundcontrol/latest/QGC.version.txt"); #endif } + +#if !defined(__mobile__) +QGCQmlWidgetHolder* QGCCorePlugin::createMainQmlWidgetHolder(QLayout *mainLayout, QWidget* parent) +{ + QGCQmlWidgetHolder* pMainQmlWidgetHolder = new QGCQmlWidgetHolder(QString(), nullptr, parent); + mainLayout->addWidget(pMainQmlWidgetHolder); + pMainQmlWidgetHolder->setVisible(true); + QQmlEngine::setObjectOwnership(parent, QQmlEngine::CppOwnership); + pMainQmlWidgetHolder->setContextPropertyObject("controller", parent); + pMainQmlWidgetHolder->setContextPropertyObject("debugMessageModel", AppMessages::getModel()); + pMainQmlWidgetHolder->setSource(QUrl::fromUserInput("qrc:qml/MainWindowHybrid.qml")); + return pMainQmlWidgetHolder; +} +#endif diff --git a/src/api/QGCCorePlugin.h b/src/api/QGCCorePlugin.h index a4812577ec933c2593e3647e866efb722b113ad0..c5ec1db8c06018f050abbe4fe3ae0a49ed3577f8 100644 --- a/src/api/QGCCorePlugin.h +++ b/src/api/QGCCorePlugin.h @@ -34,6 +34,12 @@ class QmlObjectListModel; class VideoReceiver; class PlanMasterController; +#if !defined(__mobile__) +class QLayout; +class QMainWindow; +class QGCQmlWidgetHolder; +#endif + class QGCCorePlugin : public QGCTool { Q_OBJECT @@ -102,6 +108,11 @@ public: /// Allows the plugin to override the creation of the root (native) window. virtual QQmlApplicationEngine* createRootWindow(QObject* parent); + /// Allows the plugin to have a chance to initialize the creation of the root (non native) window. +#if !defined(__mobile__) + virtual QGCQmlWidgetHolder* createMainQmlWidgetHolder(QLayout* mainLayout, QWidget *parent); +#endif + /// Allows the plugin to override the creation of VideoReceiver. virtual VideoReceiver* createVideoReceiver(QObject* parent); diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 1116629e60237f72481e74b31e23e430b8b4c3d5..7a98324b0c0ba2952d8ecf82c0c2b1a2314a67a4 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -84,7 +84,7 @@ static const char *rgDockWidgetNames[] = { static const char* _visibleWidgetsKey = "VisibleWidgets"; #endif -static MainWindow* _instance = NULL; ///< @brief MainWindow singleton +static MainWindow* _instance = nullptr; ///< @brief MainWindow singleton MainWindow* MainWindow::_create() { @@ -106,10 +106,10 @@ void MainWindow::deleteInstance(void) /// by MainWindow::_create method. Hence no other code should have access to /// constructor. MainWindow::MainWindow() - : _mavlinkDecoder (NULL) + : _mavlinkDecoder (nullptr) , _lowPowerMode (false) , _showStatusBar (false) - , _mainQmlWidgetHolder (NULL) + , _mainQmlWidgetHolder (nullptr) , _forceClose (false) { _instance = this; @@ -138,21 +138,15 @@ MainWindow::MainWindow() _centralLayout->setContentsMargins(0, 0, 0, 0); centralWidget()->setLayout(_centralLayout); - _mainQmlWidgetHolder = new QGCQmlWidgetHolder(QString(), NULL, this); - _centralLayout->addWidget(_mainQmlWidgetHolder); - _mainQmlWidgetHolder->setVisible(true); - - QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); - _mainQmlWidgetHolder->setContextPropertyObject("controller", this); - _mainQmlWidgetHolder->setContextPropertyObject("debugMessageModel", AppMessages::getModel()); - _mainQmlWidgetHolder->setSource(QUrl::fromUserInput("qrc:qml/MainWindowHybrid.qml")); + //-- Allow plugin to initialize main QML Widget + _mainQmlWidgetHolder = qgcApp()->toolbox()->corePlugin()->createMainQmlWidgetHolder(_centralLayout, this); // Image provider QQuickImageProvider* pImgProvider = dynamic_cast(qgcApp()->toolbox()->imageProvider()); _mainQmlWidgetHolder->getEngine()->addImageProvider(QStringLiteral("QGCImages"), pImgProvider); // Set dock options - setDockOptions(0); + setDockOptions(nullptr); // Setup corners setCorner(Qt::BottomRightCorner, Qt::BottomDockWidgetArea); @@ -162,7 +156,7 @@ MainWindow::MainWindow() #endif #ifdef UNITTEST_BUILD - QAction* qmlTestAction = new QAction("Test QML palette and controls", NULL); + QAction* qmlTestAction = new QAction("Test QML palette and controls", nullptr); connect(qmlTestAction, &QAction::triggered, this, &MainWindow::_showQmlTestWidget); _ui.menuWidgets->addAction(qmlTestAction); #endif @@ -246,14 +240,14 @@ MainWindow::~MainWindow() _mavlinkDecoder->finish(); _mavlinkDecoder->wait(1000); _mavlinkDecoder->deleteLater(); - _mavlinkDecoder = NULL; + _mavlinkDecoder = nullptr; } // This needs to happen before we get into the QWidget dtor // otherwise the QML engine reads freed data and tries to // destroy MainWindow a second time. delete _mainQmlWidgetHolder; - _instance = NULL; + _instance = nullptr; } QString MainWindow::_getWindowGeometryKey() @@ -315,7 +309,7 @@ void MainWindow::_showDockWidget(const QString& name, bool show) /// Creates the specified inner dock widget and adds to the QDockWidget bool MainWindow::_createInnerDockWidget(const QString& widgetName) { - QGCDockWidget* widget = NULL; + QGCDockWidget* widget = nullptr; QAction *action = _mapName2Action[widgetName]; if(action) { switch(action->data().toInt()) { @@ -339,7 +333,7 @@ bool MainWindow::_createInnerDockWidget(const QString& widgetName) _mapName2DockWidget[widgetName] = widget; } } - return widget != NULL; + return widget != nullptr; } void MainWindow::_hideAllDockWidgets(void) @@ -510,7 +504,7 @@ void MainWindow::_storeVisibleWidgetsSettings(void) QObject* MainWindow::rootQmlObject(void) { - return _mainQmlWidgetHolder->getRootObject(); + return _mainQmlWidgetHolder ? _mainQmlWidgetHolder->getRootObject() : nullptr; } void MainWindow::_showAdvancedUIChanged(bool advanced) diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index 2a906c2cc44f64d193a255b512126ac86226936a..a358e29338399b803557f81f4e57dd848b08e036 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -47,7 +47,6 @@ QGCView { property string _videoSource: QGroundControl.settingsManager.videoSettings.videoSource.value property bool _isGst: QGroundControl.videoManager.isGStreamer - property bool _isAutoStream: QGroundControl.videoManager.isAutoStream property bool _isUDP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.udpVideoSource property bool _isRTSP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.rtspVideoSource property bool _isTCP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.tcpVideoSource @@ -691,7 +690,7 @@ QGCView { QGCLabel { id: videoSectionLabel text: qsTr("Video") - visible: QGroundControl.settingsManager.videoSettings.visible + visible: QGroundControl.settingsManager.videoSettings.visible && !QGroundControl.videoManager.autoStreamConfigured } Rectangle { Layout.preferredWidth: videoGrid.width + (_margins * 2) @@ -751,12 +750,12 @@ QGCView { } QGCLabel { text: qsTr("Aspect Ratio") - visible: !_isAutoStream && _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible + visible: _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible } FactTextField { Layout.preferredWidth: _comboFieldWidth fact: QGroundControl.settingsManager.videoSettings.aspectRatio - visible: !_isAutoStream && _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible + visible: _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible } QGCLabel { @@ -776,10 +775,10 @@ QGCView { QGCLabel { id: videoRecSectionLabel text: qsTr("Video Recording") - visible: QGroundControl.settingsManager.videoSettings.visible && _isGst + visible: (QGroundControl.settingsManager.videoSettings.visible && _isGst) || QGroundControl.videoManager.autoStreamConfigured } Rectangle { - Layout.preferredWidth: videoRecCol.width + (_margins * 2) + Layout.preferredWidth: videoRecCol.width + (_margins * 2) Layout.preferredHeight: videoRecCol.height + (_margins * 2) Layout.fillWidth: true color: qgcPal.windowShade