Commit 545f6353 authored by Matej Frančeškin's avatar Matej Frančeškin

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into pr-taisync-android

parents df74b9ac 67b4758e
...@@ -58,6 +58,15 @@ static const char* kPhotoMode = "PhotoMode"; ...@@ -58,6 +58,15 @@ static const char* kPhotoMode = "PhotoMode";
static const char* kPhotoLapse = "PhotoLapse"; static const char* kPhotoLapse = "PhotoLapse";
static const char* kPhotoLapseCount = "PhotoLapseCount"; static const char* kPhotoLapseCount = "PhotoLapseCount";
//-----------------------------------------------------------------------------
// Known Parameters
static const char *kCAM_EV = "CAM_EV";
static const char *kCAM_EXPMODE = "CAM_EXPMODE";
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";
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_) QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
: QObject(parent) : QObject(parent)
...@@ -146,6 +155,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -146,6 +155,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
, _compID(compID) , _compID(compID)
, _version(0) , _version(0)
, _cached(false) , _cached(false)
, _paramComplete(false)
, _storageFree(0) , _storageFree(0)
, _storageTotal(0) , _storageTotal(0)
, _netManager(nullptr) , _netManager(nullptr)
...@@ -465,6 +475,44 @@ QGCCameraControl::setPhotoMode() ...@@ -465,6 +475,44 @@ QGCCameraControl::setPhotoMode()
} }
} }
//-----------------------------------------------------------------------------
void
QGCCameraControl::setZoomLevel(qreal level)
{
qCDebug(CameraControlLog) << "setZoomLevel()" << level;
if(hasZoom()) {
//-- Limit
level = std::min(std::max(level, 0.0), 100.0);
if(_vehicle) {
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_ZOOM, // Command id
false, // ShowError
ZOOM_TYPE_RANGE, // Zoom type
static_cast<float>(level)); // Level
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::setFocusLevel(qreal level)
{
qCDebug(CameraControlLog) << "setFocusLevel()" << level;
if(hasFocus()) {
//-- Limit
level = std::min(std::max(level, 0.0), 100.0);
if(_vehicle) {
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_FOCUS, // Command id
false, // ShowError
FOCUS_TYPE_RANGE, // Focus type
static_cast<float>(level)); // Level
}
}
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::resetSettings() QGCCameraControl::resetSettings()
...@@ -497,6 +545,51 @@ QGCCameraControl::formatCard(int id) ...@@ -497,6 +545,51 @@ QGCCameraControl::formatCard(int id)
} }
} }
//-----------------------------------------------------------------------------
void
QGCCameraControl::stepZoom(int direction)
{
qCDebug(CameraControlLog) << "stepZoom()" << direction;
if(_vehicle && hasZoom()) {
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_ZOOM, // Command id
false, // ShowError
ZOOM_TYPE_STEP, // Zoom type
direction); // Direction (-1 wide, 1 tele)
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::startZoom(int direction)
{
qCDebug(CameraControlLog) << "startZoom()" << direction;
if(_vehicle && hasZoom()) {
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_ZOOM, // Command id
true, // ShowError
ZOOM_TYPE_CONTINUOUS, // Zoom type
direction); // Direction (-1 wide, 1 tele)
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::stopZoom()
{
qCDebug(CameraControlLog) << "stopZoom()";
if(_vehicle && hasZoom()) {
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_ZOOM, // Command id
true, // ShowError
ZOOM_TYPE_CONTINUOUS, // Zoom type
0); // Direction (-1 wide, 1 tele)
}
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::_requestCaptureStatus() QGCCameraControl::_requestCaptureStatus()
...@@ -1069,6 +1162,10 @@ QGCCameraControl::_updateActiveList() ...@@ -1069,6 +1162,10 @@ QGCCameraControl::_updateActiveList()
qCDebug(CameraControlLogVerbose) << "Excluding" << exclusionList; qCDebug(CameraControlLogVerbose) << "Excluding" << exclusionList;
_activeSettings = active; _activeSettings = active;
emit activeSettingsChanged(); emit activeSettingsChanged();
//-- Force validity of "Facts" based on active set
if(_paramComplete) {
emit parametersReady();
}
} }
} }
...@@ -1273,6 +1370,16 @@ QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings) ...@@ -1273,6 +1370,16 @@ QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings)
{ {
qCDebug(CameraControlLog) << "handleSettings() Mode:" << settings.mode_id; qCDebug(CameraControlLog) << "handleSettings() Mode:" << settings.mode_id;
_setCameraMode(static_cast<CameraMode>(settings.mode_id)); _setCameraMode(static_cast<CameraMode>(settings.mode_id));
qreal z = static_cast<qreal>(settings.zoomLevel);
qreal f = static_cast<qreal>(settings.focusLevel);
if(std::isfinite(z) && z != _zoomLevel) {
_zoomLevel = z;
emit zoomLevelChanged();
}
if(std::isfinite(f) && f != _focusLevel) {
_focusLevel = f;
emit focusLevelChanged();
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -1563,6 +1670,7 @@ QGCCameraControl::_paramDone() ...@@ -1563,6 +1670,7 @@ QGCCameraControl::_paramDone()
} }
} }
//-- All parameters loaded (or timed out) //-- All parameters loaded (or timed out)
_paramComplete = true;
emit parametersReady(); emit parametersReady();
} }
...@@ -1591,3 +1699,45 @@ QGCCameraControl::activeSettings() ...@@ -1591,3 +1699,45 @@ QGCCameraControl::activeSettings()
qCDebug(CameraControlLog) << "Active:" << _activeSettings; qCDebug(CameraControlLog) << "Active:" << _activeSettings;
return _activeSettings; return _activeSettings;
} }
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::exposureMode()
{
return (_paramComplete && _activeSettings.contains(kCAM_EXPMODE)) ? getFact(kCAM_EXPMODE) : nullptr;
}
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::ev()
{
return (_paramComplete && _activeSettings.contains(kCAM_EV)) ? getFact(kCAM_EV) : nullptr;
}
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::iso()
{
return (_paramComplete && _activeSettings.contains(kCAM_ISO)) ? getFact(kCAM_ISO) : nullptr;
}
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::shutter()
{
return (_paramComplete && _activeSettings.contains(kCAM_SHUTTER)) ? getFact(kCAM_SHUTTER) : nullptr;
}
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::aperture()
{
return (_paramComplete && _activeSettings.contains(kCAM_APERTURE)) ? getFact(kCAM_APERTURE) : nullptr;
}
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::wb()
{
return (_paramComplete && _activeSettings.contains(kCAM_WBMODE)) ? getFact(kCAM_WBMODE) : nullptr;
}
...@@ -97,12 +97,25 @@ public: ...@@ -97,12 +97,25 @@ public:
Q_PROPERTY(bool capturesVideo READ capturesVideo NOTIFY infoChanged) Q_PROPERTY(bool capturesVideo READ capturesVideo NOTIFY infoChanged)
Q_PROPERTY(bool capturesPhotos READ capturesPhotos NOTIFY infoChanged) Q_PROPERTY(bool capturesPhotos READ capturesPhotos NOTIFY infoChanged)
Q_PROPERTY(bool hasModes READ hasModes NOTIFY infoChanged) 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 photosInVideoMode READ photosInVideoMode NOTIFY infoChanged) Q_PROPERTY(bool photosInVideoMode READ photosInVideoMode NOTIFY infoChanged)
Q_PROPERTY(bool videoInPhotoMode READ videoInPhotoMode NOTIFY infoChanged) Q_PROPERTY(bool videoInPhotoMode READ videoInPhotoMode NOTIFY infoChanged)
Q_PROPERTY(bool isBasic READ isBasic NOTIFY infoChanged) Q_PROPERTY(bool isBasic READ isBasic NOTIFY infoChanged)
Q_PROPERTY(quint32 storageFree READ storageFree NOTIFY storageFreeChanged) Q_PROPERTY(quint32 storageFree READ storageFree NOTIFY storageFreeChanged)
Q_PROPERTY(QString storageFreeStr READ storageFreeStr NOTIFY storageFreeChanged) Q_PROPERTY(QString storageFreeStr READ storageFreeStr NOTIFY storageFreeChanged)
Q_PROPERTY(quint32 storageTotal READ storageTotal NOTIFY storageTotalChanged) Q_PROPERTY(quint32 storageTotal READ storageTotal NOTIFY storageTotalChanged)
Q_PROPERTY(bool paramComplete READ paramComplete NOTIFY parametersReady)
Q_PROPERTY(qreal zoomLevel READ zoomLevel WRITE setZoomLevel NOTIFY zoomLevelChanged)
Q_PROPERTY(qreal focusLevel READ focusLevel WRITE setFocusLevel NOTIFY focusLevelChanged)
Q_PROPERTY(Fact* exposureMode READ exposureMode NOTIFY parametersReady)
Q_PROPERTY(Fact* ev READ ev NOTIFY parametersReady)
Q_PROPERTY(Fact* iso READ iso NOTIFY parametersReady)
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(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged) Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged)
Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged) Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged)
...@@ -122,6 +135,9 @@ public: ...@@ -122,6 +135,9 @@ public:
Q_INVOKABLE virtual bool toggleVideo (); Q_INVOKABLE virtual bool toggleVideo ();
Q_INVOKABLE virtual void resetSettings (); Q_INVOKABLE virtual void resetSettings ();
Q_INVOKABLE virtual void formatCard (int id = 1); Q_INVOKABLE virtual void formatCard (int id = 1);
Q_INVOKABLE virtual void stepZoom (int direction);
Q_INVOKABLE virtual void startZoom (int direction);
Q_INVOKABLE virtual void stopZoom ();
virtual int version () { return _version; } virtual int version () { return _version; }
virtual QString modelName () { return _modelName; } virtual QString modelName () { return _modelName; }
...@@ -133,6 +149,8 @@ public: ...@@ -133,6 +149,8 @@ public:
virtual bool capturesVideo () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO; } virtual bool capturesVideo () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO; }
virtual bool capturesPhotos () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE; } virtual bool capturesPhotos () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE; }
virtual bool hasModes () { return _info.flags & CAMERA_CAP_FLAGS_HAS_MODES; } 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 photosInVideoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; } 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; } virtual bool videoInPhotoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; }
...@@ -148,7 +166,19 @@ public: ...@@ -148,7 +166,19 @@ public:
virtual quint32 storageFree () { return _storageFree; } virtual quint32 storageFree () { return _storageFree; }
virtual QString storageFreeStr (); virtual QString storageFreeStr ();
virtual quint32 storageTotal () { return _storageTotal; } virtual quint32 storageTotal () { return _storageTotal; }
virtual bool paramComplete () { return _paramComplete; }
virtual qreal zoomLevel () { return _zoomLevel; }
virtual qreal focusLevel () { return _focusLevel; }
virtual Fact* exposureMode ();
virtual Fact* ev ();
virtual Fact* iso ();
virtual Fact* shutter ();
virtual Fact* aperture ();
virtual Fact* wb ();
virtual void setZoomLevel (qreal level);
virtual void setFocusLevel (qreal level);
virtual void setCameraMode (CameraMode mode); virtual void setCameraMode (CameraMode mode);
virtual void setPhotoMode (PhotoMode mode); virtual void setPhotoMode (PhotoMode mode);
virtual void setPhotoLapse (qreal interval); virtual void setPhotoLapse (qreal interval);
...@@ -180,6 +210,8 @@ signals: ...@@ -180,6 +210,8 @@ signals:
void storageTotalChanged (); void storageTotalChanged ();
void dataReady (QByteArray data); void dataReady (QByteArray data);
void parametersReady (); void parametersReady ();
void zoomLevelChanged ();
void focusLevelChanged ();
protected: protected:
virtual void _setVideoStatus (VideoStatus status); virtual void _setVideoStatus (VideoStatus status);
...@@ -198,6 +230,7 @@ protected slots: ...@@ -198,6 +230,7 @@ protected slots:
virtual void _dataReady (QByteArray data); virtual void _dataReady (QByteArray data);
virtual void _paramDone (); virtual void _paramDone ();
private: private:
bool _handleLocalization (QByteArray& bytes); bool _handleLocalization (QByteArray& bytes);
bool _replaceLocaleStrings (const QDomNode node, QByteArray& bytes); bool _replaceLocaleStrings (const QDomNode node, QByteArray& bytes);
...@@ -224,6 +257,9 @@ protected: ...@@ -224,6 +257,9 @@ protected:
mavlink_camera_information_t _info; mavlink_camera_information_t _info;
int _version; int _version;
bool _cached; bool _cached;
bool _paramComplete;
qreal _zoomLevel;
qreal _focusLevel;
uint32_t _storageFree; uint32_t _storageFree;
uint32_t _storageTotal; uint32_t _storageTotal;
QNetworkAccessManager* _netManager; QNetworkAccessManager* _netManager;
......
...@@ -7,20 +7,20 @@ ...@@ -7,20 +7,20 @@
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCCameraManager.h" #include "QGCCameraManager.h"
#include "JoystickManager.h"
QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog") QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog")
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCCameraManager::QGCCameraManager(Vehicle *vehicle) QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
: _vehicle(vehicle) : _vehicle(vehicle)
, _vehicleReadyState(false)
, _currentTask(0)
, _currentCamera(0)
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qCDebug(CameraManagerLog) << "QGCCameraManager Created"; qCDebug(CameraManagerLog) << "QGCCameraManager Created";
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady); connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady);
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived); connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived);
_lastZoomChange.start();
_lastCameraChange.start();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -46,6 +46,9 @@ QGCCameraManager::_vehicleReady(bool ready) ...@@ -46,6 +46,9 @@ QGCCameraManager::_vehicleReady(bool ready)
if(ready) { if(ready) {
if(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle() == _vehicle) { if(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle() == _vehicle) {
_vehicleReadyState = true; _vehicleReadyState = true;
JoystickManager *pJoyMgr = qgcApp()->toolbox()->joystickManager();
_activeJoystickChanged(pJoyMgr->activeJoystick());
connect(pJoyMgr, &JoystickManager::activeJoystickChanged, this, &QGCCameraManager::_activeJoystickChanged);
} }
} }
} }
...@@ -114,7 +117,7 @@ QGCCameraManager::_findCamera(int id) ...@@ -114,7 +117,7 @@ QGCCameraManager::_findCamera(int id)
} }
} }
qWarning() << "Camera component id not found:" << id; qWarning() << "Camera component id not found:" << id;
return NULL; return nullptr;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -127,7 +130,7 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message) ...@@ -127,7 +130,7 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
_cameraInfoRequested[message.compid] = false; _cameraInfoRequested[message.compid] = false;
mavlink_camera_information_t info; mavlink_camera_information_t info;
mavlink_msg_camera_information_decode(&message, &info); mavlink_msg_camera_information_decode(&message, &info);
qCDebug(CameraManagerLog) << "_handleCameraInfo:" << (const char*)(void*)&info.model_name[0] << (const char*)(void*)&info.vendor_name[0] << "Comp ID:" << message.compid; qCDebug(CameraManagerLog) << "_handleCameraInfo:" << reinterpret_cast<const char*>(info.model_name) << reinterpret_cast<const char*>(info.vendor_name) << "Comp ID:" << message.compid;
QGCCameraControl* pCamera = _vehicle->firmwarePlugin()->createCameraControl(&info, _vehicle, message.compid, this); QGCCameraControl* pCamera = _vehicle->firmwarePlugin()->createCameraControl(&info, _vehicle, message.compid, this);
if(pCamera) { if(pCamera) {
QQmlEngine::setObjectOwnership(pCamera, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(pCamera, QQmlEngine::CppOwnership);
...@@ -212,3 +215,51 @@ QGCCameraManager::_requestCameraInfo(int compID) ...@@ -212,3 +215,51 @@ QGCCameraManager::_requestCameraInfo(int compID)
1); // Do Request 1); // Do Request
} }
} }
//----------------------------------------------------------------------------------------
void
QGCCameraManager::_activeJoystickChanged(Joystick* joystick)
{
qCDebug(CameraManagerLog) << "Joystick changed";
if(_activeJoystick) {
disconnect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom);
disconnect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
}
_activeJoystick = joystick;
if(_activeJoystick) {
connect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom);
connect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
}
}
//-----------------------------------------------------------------------------
void
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<QGCCameraControl*>(_cameras[_currentCamera]);
if(pCamera) {
pCamera->stepZoom(direction);
}
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_stepCamera(int direction)
{
if(_lastCameraChange.elapsed() > 1000) {
_lastCameraChange.start();
qCDebug(CameraManagerLog) << "Step Camera" << direction;
int c = _currentCamera + direction;
if(c < 0) c = _cameras.count() - 1;
if(c >= _cameras.count()) c = 0;
setCurrentCamera(c);
}
}
...@@ -17,6 +17,8 @@ ...@@ -17,6 +17,8 @@
Q_DECLARE_LOGGING_CATEGORY(CameraManagerLog) Q_DECLARE_LOGGING_CATEGORY(CameraManagerLog)
class Joystick;
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
class QGCCameraManager : public QObject class QGCCameraManager : public QObject
{ {
...@@ -46,6 +48,9 @@ signals: ...@@ -46,6 +48,9 @@ signals:
protected slots: protected slots:
virtual void _vehicleReady (bool ready); virtual void _vehicleReady (bool ready);
virtual void _mavlinkMessageReceived (const mavlink_message_t& message); virtual void _mavlinkMessageReceived (const mavlink_message_t& message);
virtual void _activeJoystickChanged (Joystick* joystick);
virtual void _stepZoom (int direction);
virtual void _stepCamera (int direction);
protected: protected:
virtual QGCCameraControl* _findCamera (int id); virtual QGCCameraControl* _findCamera (int id);
...@@ -59,11 +64,14 @@ protected: ...@@ -59,11 +64,14 @@ protected:
virtual void _handleCaptureStatus (const mavlink_message_t& message); virtual void _handleCaptureStatus (const mavlink_message_t& message);
protected: protected:
Vehicle* _vehicle; Vehicle* _vehicle = nullptr;
bool _vehicleReadyState; Joystick* _activeJoystick = nullptr;
int _currentTask; bool _vehicleReadyState = false;
int _currentTask = 0;
QmlObjectListModel _cameras; QmlObjectListModel _cameras;
QStringList _cameraLabels; QStringList _cameraLabels;
QMap<int, bool> _cameraInfoRequested; QMap<int, bool> _cameraInfoRequested;
int _currentCamera; int _currentCamera = 0;
QTime _lastZoomChange;
QTime _lastCameraChange;
}; };
...@@ -28,6 +28,7 @@ ...@@ -28,6 +28,7 @@
#include "MultiVehicleManager.h" #include "MultiVehicleManager.h"
#include "Settings/SettingsManager.h" #include "Settings/SettingsManager.h"
#include "Vehicle.h" #include "Vehicle.h"
#include "JoystickManager.h"
QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog") QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
...@@ -36,6 +37,8 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox) ...@@ -36,6 +37,8 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox) : QGCTool(app, toolbox)
{ {
_streamInfo = {}; _streamInfo = {};
_lastZoomChange.start();
_lastStreamChange.start();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -61,9 +64,11 @@ VideoManager::setToolbox(QGCToolbox *toolbox) ...@@ -61,9 +64,11 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged); connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged);
connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged); connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged);
connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged); connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged);
connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged); connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_streamInfoChanged);
MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager(); MultiVehicleManager *pVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle); connect(pVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
JoystickManager *pJoyMgr = qgcApp()->toolbox()->joystickManager();
connect(pJoyMgr, &JoystickManager::activeJoystickChanged, this, &VideoManager::_activeJoystickChanged);
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
#ifndef QGC_DISABLE_UVC #ifndef QGC_DISABLE_UVC
...@@ -272,16 +277,91 @@ VideoManager::_vehicleMessageReceived(const mavlink_message_t& message) ...@@ -272,16 +277,91 @@ VideoManager::_vehicleMessageReceived(const mavlink_message_t& message)
{ {
//-- For now we only handle one stream. There is no UI to pick different streams. //-- For now we only handle one stream. There is no UI to pick different streams.
if(message.msgid == MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION) { if(message.msgid == MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION) {
_videoStreamCompID = message.compid;
mavlink_msg_video_stream_information_decode(&message, &_streamInfo); mavlink_msg_video_stream_information_decode(&message, &_streamInfo);
_hasAutoStream = true;
qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri; qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri;
_restartVideo(); _restartVideo();
emit aspectRatioChanged(); emit streamInfoChanged();
} }
} }
//---------------------------------------------------------------------------------------- //----------------------------------------------------------------------------------------
void void
VideoManager::_aspectRatioChanged() VideoManager::_activeJoystickChanged(Joystick* joystick)
{ {
emit aspectRatioChanged(); 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();
}
}
}
//----------------------------------------------------------------------------------------
void
VideoManager::_streamInfoChanged()
{
emit streamInfoChanged();
} }
...@@ -13,6 +13,7 @@ ...@@ -13,6 +13,7 @@
#include <QObject> #include <QObject>
#include <QTimer> #include <QTimer>
#include <QTime>
#include <QUrl> #include <QUrl>
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
...@@ -24,6 +25,7 @@ Q_DECLARE_LOGGING_CATEGORY(VideoManagerLog) ...@@ -24,6 +25,7 @@ Q_DECLARE_LOGGING_CATEGORY(VideoManagerLog)
class VideoSettings; class VideoSettings;
class Vehicle; class Vehicle;
class Joystick;
class VideoManager : public QGCTool class VideoManager : public QGCTool
{ {
...@@ -41,7 +43,10 @@ public: ...@@ -41,7 +43,10 @@ public:
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT) Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged) Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged)
Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT) Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT)
Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY aspectRatioChanged) 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)
bool hasVideo (); bool hasVideo ();
bool isGStreamer (); bool isGStreamer ();
...@@ -51,6 +56,9 @@ public: ...@@ -51,6 +56,9 @@ public:
QString videoSourceID () { return _videoSourceID; } QString videoSourceID () { return _videoSourceID; }
QString autoURL () { return QString(_streamInfo.uri); } QString autoURL () { return QString(_streamInfo.uri); }
double aspectRatio (); double aspectRatio ();
bool hasZoom () { return _streamInfo.flags & VIDEO_STREAM_HAS_BASIC_ZOOM; }
int currentStream () { return _currentStream; }
int streamCount () { return _streamInfo.count; }
VideoReceiver* videoReceiver () { return _videoReceiver; } VideoReceiver* videoReceiver () { return _videoReceiver; }
...@@ -62,12 +70,15 @@ public: ...@@ -62,12 +70,15 @@ public:
void setfullScreen (bool f) { _fullScreen = f; emit fullScreenChanged(); } void setfullScreen (bool f) { _fullScreen = f; emit fullScreenChanged(); }
void setIsTaisync (bool t) { _isTaisync = t; emit isTaisyncChanged(); } void setIsTaisync (bool t) { _isTaisync = t; emit isTaisyncChanged(); }
void setCurrentStream (int stream);
// Override from QGCTool // Override from QGCTool
void setToolbox (QGCToolbox *toolbox); void setToolbox (QGCToolbox *toolbox);
Q_INVOKABLE void startVideo() {_videoReceiver->start();} Q_INVOKABLE void startVideo () { _videoReceiver->start(); }
Q_INVOKABLE void stopVideo() {_videoReceiver->stop(); } Q_INVOKABLE void stopVideo () { _videoReceiver->stop(); }
Q_INVOKABLE void stepZoom (int direction);
Q_INVOKABLE void stepStream (int direction);
signals: signals:
void hasVideoChanged (); void hasVideoChanged ();
...@@ -75,8 +86,10 @@ signals: ...@@ -75,8 +86,10 @@ signals:
void videoSourceIDChanged (); void videoSourceIDChanged ();
void fullScreenChanged (); void fullScreenChanged ();
void isAutoStreamChanged (); void isAutoStreamChanged ();
void aspectRatioChanged (); void streamInfoChanged ();
void isTaisyncChanged (); void isTaisyncChanged ();
void currentStreamChanged ();
void streamCountChanged ();
private slots: private slots:
void _videoSourceChanged (); void _videoSourceChanged ();
...@@ -84,8 +97,9 @@ private slots: ...@@ -84,8 +97,9 @@ private slots:
void _rtspUrlChanged (); void _rtspUrlChanged ();
void _tcpUrlChanged (); void _tcpUrlChanged ();
void _updateUVC (); void _updateUVC ();
void _aspectRatioChanged (); void _streamInfoChanged ();
void _setActiveVehicle (Vehicle* vehicle); void _setActiveVehicle (Vehicle* vehicle);
void _activeJoystickChanged (Joystick* joystick);
void _vehicleMessageReceived (const mavlink_message_t& message); void _vehicleMessageReceived (const mavlink_message_t& message);
private: private:
...@@ -99,7 +113,13 @@ private: ...@@ -99,7 +113,13 @@ private:
QString _videoSourceID; QString _videoSourceID;
bool _fullScreen = false; bool _fullScreen = false;
Vehicle* _activeVehicle = nullptr; Vehicle* _activeVehicle = nullptr;
Joystick* _activeJoystick = nullptr;
mavlink_video_stream_information_t _streamInfo; mavlink_video_stream_information_t _streamInfo;
bool _hasAutoStream = false;
uint8_t _videoStreamCompID = 0;
int _currentStream = 1;
QTime _lastZoomChange;
QTime _lastStreamChange;
}; };
#endif #endif
...@@ -12,6 +12,10 @@ ...@@ -12,6 +12,10 @@
#include "QGC.h" #include "QGC.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "UAS.h" #include "UAS.h"
#include "QGCApplication.h"
#include "VideoManager.h"
#include "QGCCameraManager.h"
#include "QGCCameraControl.h"
#include <QSettings> #include <QSettings>
...@@ -27,7 +31,7 @@ const char* Joystick::_accumulatorSettingsKey = "Accumulator"; ...@@ -27,7 +31,7 @@ const char* Joystick::_accumulatorSettingsKey = "Accumulator";
const char* Joystick::_deadbandSettingsKey = "Deadband"; const char* Joystick::_deadbandSettingsKey = "Deadband";
const char* Joystick::_circleCorrectionSettingsKey = "Circle_Correction"; const char* Joystick::_circleCorrectionSettingsKey = "Circle_Correction";
const char* Joystick::_frequencySettingsKey = "Frequency"; const char* Joystick::_frequencySettingsKey = "Frequency";
const char* Joystick::_txModeSettingsKey = NULL; const char* Joystick::_txModeSettingsKey = nullptr;
const char* Joystick::_fixedWingTXModeSettingsKey = "TXMode_FixedWing"; const char* Joystick::_fixedWingTXModeSettingsKey = "TXMode_FixedWing";
const char* Joystick::_multiRotorTXModeSettingsKey = "TXMode_MultiRotor"; const char* Joystick::_multiRotorTXModeSettingsKey = "TXMode_MultiRotor";
const char* Joystick::_roverTXModeSettingsKey = "TXMode_Rover"; const char* Joystick::_roverTXModeSettingsKey = "TXMode_Rover";
...@@ -38,6 +42,12 @@ const char* Joystick::_buttonActionArm = QT_TR_NOOP("Arm"); ...@@ -38,6 +42,12 @@ const char* Joystick::_buttonActionArm = QT_TR_NOOP("Arm");
const char* Joystick::_buttonActionDisarm = QT_TR_NOOP("Disarm"); const char* Joystick::_buttonActionDisarm = QT_TR_NOOP("Disarm");
const char* Joystick::_buttonActionVTOLFixedWing = QT_TR_NOOP("VTOL: Fixed Wing"); const char* Joystick::_buttonActionVTOLFixedWing = QT_TR_NOOP("VTOL: Fixed Wing");
const char* Joystick::_buttonActionVTOLMultiRotor = QT_TR_NOOP("VTOL: Multi-Rotor"); const char* Joystick::_buttonActionVTOLMultiRotor = QT_TR_NOOP("VTOL: Multi-Rotor");
const char* Joystick::_buttonActionZoomIn = QT_TR_NOOP("Zoom In");
const char* Joystick::_buttonActionZoomOut = QT_TR_NOOP("Zoom Out");
const char* Joystick::_buttonActionNextStream = QT_TR_NOOP("Next Video Stream");
const char* Joystick::_buttonActionPreviousStream = QT_TR_NOOP("Previous Video Stream");
const char* Joystick::_buttonActionNextCamera = QT_TR_NOOP("Next Camera");
const char* Joystick::_buttonActionPreviousCamera = QT_TR_NOOP("Previous Camera");
const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = { const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = {
"RollAxis", "RollAxis",
...@@ -57,9 +67,9 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC ...@@ -57,9 +67,9 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
, _hatButtonCount(4*hatCount) , _hatButtonCount(4*hatCount)
, _totalButtonCount(_buttonCount+_hatButtonCount) , _totalButtonCount(_buttonCount+_hatButtonCount)
, _calibrationMode(false) , _calibrationMode(false)
, _rgAxisValues(NULL) , _rgAxisValues(nullptr)
, _rgCalibration(NULL) , _rgCalibration(nullptr)
, _rgButtonValues(NULL) , _rgButtonValues(nullptr)
, _lastButtonBits(0) , _lastButtonBits(0)
, _throttleMode(ThrottleModeCenterZero) , _throttleMode(ThrottleModeCenterZero)
, _negativeThrust(false) , _negativeThrust(false)
...@@ -68,7 +78,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC ...@@ -68,7 +78,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
, _deadband(false) , _deadband(false)
, _circleCorrection(true) , _circleCorrection(true)
, _frequency(25.0f) , _frequency(25.0f)
, _activeVehicle(NULL) , _activeVehicle(nullptr)
, _pollingStartedForCalibration(false) , _pollingStartedForCalibration(false)
, _multiVehicleManager(multiVehicleManager) , _multiVehicleManager(multiVehicleManager)
{ {
...@@ -150,12 +160,12 @@ void Joystick::_updateTXModeSettingsKey(Vehicle* activeVehicle) ...@@ -150,12 +160,12 @@ void Joystick::_updateTXModeSettingsKey(Vehicle* activeVehicle)
} else if(activeVehicle->sub()) { } else if(activeVehicle->sub()) {
_txModeSettingsKey = _submarineTXModeSettingsKey; _txModeSettingsKey = _submarineTXModeSettingsKey;
} else { } else {
_txModeSettingsKey = NULL; _txModeSettingsKey = nullptr;
qWarning() << "No valid joystick TXmode settings key for selected vehicle"; qWarning() << "No valid joystick TXmode settings key for selected vehicle";
return; return;
} }
} else { } else {
_txModeSettingsKey = NULL; _txModeSettingsKey = nullptr;
} }
} }
...@@ -659,14 +669,14 @@ int Joystick::getFunctionAxis(AxisFunction_t function) ...@@ -659,14 +669,14 @@ int Joystick::getFunctionAxis(AxisFunction_t function)
QStringList Joystick::actions(void) QStringList Joystick::actions(void)
{ {
QStringList list; QStringList list;
list << _buttonActionArm << _buttonActionDisarm; list << _buttonActionArm << _buttonActionDisarm;
if (_activeVehicle) { if (_activeVehicle) {
list << _activeVehicle->flightModes(); list << _activeVehicle->flightModes();
} }
list << _buttonActionVTOLFixedWing << _buttonActionVTOLMultiRotor; list << _buttonActionVTOLFixedWing << _buttonActionVTOLMultiRotor;
list << _buttonActionZoomIn << _buttonActionZoomOut;
list << _buttonActionNextStream << _buttonActionPreviousStream;
list << _buttonActionNextCamera << _buttonActionPreviousCamera;
return list; return list;
} }
...@@ -838,6 +848,12 @@ void Joystick::_buttonAction(const QString& action) ...@@ -838,6 +848,12 @@ void Joystick::_buttonAction(const QString& action)
_activeVehicle->setVtolInFwdFlight(false); _activeVehicle->setVtolInFwdFlight(false);
} else if (_activeVehicle->flightModes().contains(action)) { } else if (_activeVehicle->flightModes().contains(action)) {
_activeVehicle->setFlightMode(action); _activeVehicle->setFlightMode(action);
} else if(action == _buttonActionZoomIn || action == _buttonActionZoomOut) {
emit stepZoom(action == _buttonActionZoomIn ? 1 : -1);
} else if(action == _buttonActionNextStream || action == _buttonActionPreviousStream) {
emit stepStream(action == _buttonActionNextStream ? 1 : -1);
} else if(action == _buttonActionNextCamera || action == _buttonActionPreviousCamera) {
emit stepCamera(action == _buttonActionNextCamera ? 1 : -1);
} else { } else {
qCDebug(JoystickLog) << "_buttonAction unknown action:" << action; qCDebug(JoystickLog) << "_buttonAction unknown action:" << action;
} }
......
...@@ -164,7 +164,10 @@ signals: ...@@ -164,7 +164,10 @@ signals:
void buttonActionTriggered(int action); void buttonActionTriggered(int action);
void frequencyChanged(); void frequencyChanged ();
void stepZoom (int direction);
void stepCamera (int direction);
void stepStream (int direction);
protected: protected:
void _setDefaultCalibration(void); void _setDefaultCalibration(void);
...@@ -252,6 +255,12 @@ private: ...@@ -252,6 +255,12 @@ private:
static const char* _buttonActionDisarm; static const char* _buttonActionDisarm;
static const char* _buttonActionVTOLFixedWing; static const char* _buttonActionVTOLFixedWing;
static const char* _buttonActionVTOLMultiRotor; static const char* _buttonActionVTOLMultiRotor;
static const char* _buttonActionZoomIn;
static const char* _buttonActionZoomOut;
static const char* _buttonActionNextStream;
static const char* _buttonActionPreviousStream;
static const char* _buttonActionNextCamera;
static const char* _buttonActionPreviousCamera;
private slots: private slots:
void _activeVehicleChanged(Vehicle* activeVehicle); void _activeVehicleChanged(Vehicle* activeVehicle);
......
...@@ -37,10 +37,7 @@ Item { ...@@ -37,10 +37,7 @@ Item {
readonly property real _arrowBaseHeight: radius // Height of vertical side of arrow readonly property real _arrowBaseHeight: radius // Height of vertical side of arrow
readonly property real _arrowPointWidth: radius * 0.666 // Distance from vertical side to point readonly property real _arrowPointWidth: radius * 0.666 // Distance from vertical side to point
readonly property real _dropCornerRadius: ScreenTools.defaultFontPixelWidth * 0.5 readonly property real _dropMargin: ScreenTools.defaultFontPixelWidth
readonly property real _dropCornerRadiusX2: _dropCornerRadius * 2
readonly property real _dropMargin: _dropCornerRadius
readonly property real _dropMarginX2: _dropMargin * 2
property var _dropEdgeTopPoint property var _dropEdgeTopPoint
property real _dropEdgeHeight property real _dropEdgeHeight
...@@ -74,8 +71,8 @@ Item { ...@@ -74,8 +71,8 @@ Item {
var panelComponentWidth = panelLoader.item.width var panelComponentWidth = panelLoader.item.width
var panelComponentHeight = panelLoader.item.height var panelComponentHeight = panelLoader.item.height
dropDownItem.width = panelComponentWidth + (_dropMarginX2 * 2) + _arrowPointWidth dropDownItem.width = panelComponentWidth + (_dropMargin * 2) + _arrowPointWidth
dropDownItem.height = panelComponentHeight + (_dropMarginX2 * 2) dropDownItem.height = panelComponentHeight + (_dropMargin * 2)
dropDownItem.x = _dropEdgeTopPoint.x + _dropMargin dropDownItem.x = _dropEdgeTopPoint.x + _dropMargin
dropDownItem.y = _dropEdgeTopPoint.y -(dropDownItem.height / 2) + radius dropDownItem.y = _dropEdgeTopPoint.y -(dropDownItem.height / 2) + radius
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment