Commit 91673ba1 authored by Gus Grubba's avatar Gus Grubba
Browse files

Merge branch 'cameraControl' into camControl

* cameraControl: (51 commits)
  Debug info
  Adding support for custom value.
  Parse min, max, step and unit off camera definition file Ignore Fact index if there are no enums (avoid adding an "Unknown" entry) Add function to convert and clamp a (Fact) value.
  Adding support for booleans Adding some more logging
  Keep asking for capture status while camera is not idle.
  Define how long to wait for RTSP frame before deciding the link is gone.
  Toggle video stream full screen
  Enable/Disable Offline maps import/export.
  Vehicle UID
  Handle capture status retries when capturing images. Allow plugin to validate parameter setting.
  Keep track of photo status (image capture) Don't allow "Take Photo" is status is not idle. Handle In Progress response (basically, do nothing) Request capture status when stopping video recording.
  For whatever reason, showing the dialog through a function causes a crash in QML (undebugable--new word!)
  Revert "Build fix due to MAVLink update."
  Revert "MAVLink signing (WIP)"
  Make custom dialog into a function Internet available now has a signal
  Wait a bit between reset and request parameters
  Build fix due to MAVLink update.
  MAVLink signing (WIP)
  Fixing uninitialized variable warning.
  Make slots protected instead of private.
  ...

# Conflicts:
#	src/FirmwarePlugin/FirmwarePlugin.cc
#	src/FlightDisplay/FlightDisplayView.qml
#	src/FlightDisplay/FlightDisplayViewVideo.qml
#	src/MissionManager/MissionManager.cc
#	src/Vehicle/Vehicle.cc
#	src/Vehicle/Vehicle.h
#	src/api/QGCCorePlugin.h
parents b93d3944 e2a03fe8
......@@ -92,46 +92,6 @@ MacBuild {
-lSDL2
}
##
# [OPTIONAL] Speech synthesis library support.
# Can be forcibly disabled by adding a `DEFINES+=DISABLE_SPEECH` argument to qmake.
# Linux support requires the eSpeak speech synthesizer (espeak).
# Mac support is provided in Snow Leopard and newer (10.6+)
# Windows is supported as of Windows 7
#
contains (DEFINES, DISABLE_SPEECH) {
message("Skipping support for speech output (manual override from command line)")
DEFINES -= DISABLE_SPEECH
# Otherwise the user can still disable this feature in the user_config.pri file.
} else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_SPEECH) {
message("Skipping support for speech output (manual override from user_config.pri)")
} else:LinuxBuild {
exists(/usr/include/espeak) | exists(/usr/local/include/espeak) {
message("Including support for speech output")
DEFINES += QGC_SPEECH_ENABLED
LIBS += \
-lespeak
} else {
warning("Skipping support for speech output (missing libraries, see README)")
}
}
# Mac support is built into OS 10.6+.
else:MacBuild|iOSBuild {
message("Including support for speech output")
DEFINES += QGC_SPEECH_ENABLED
}
# Windows supports speech through native API.
else:WindowsBuild {
message("Including support for speech output")
DEFINES += QGC_SPEECH_ENABLED
LIBS += -lOle32
}
# Android supports speech through native (Java) API.
else:AndroidBuild {
message("Including support for speech output")
DEFINES += QGC_SPEECH_ENABLED
}
#
# [OPTIONAL] Zeroconf for UDP links
#
......
......@@ -45,15 +45,13 @@ import android.widget.Toast;
import android.util.Log;
import android.os.PowerManager;
import android.view.WindowManager;
//-- Text To Speech
import android.os.Bundle;
import android.speech.tts.TextToSpeech;
import com.hoho.android.usbserial.driver.*;
import org.qtproject.qt5.android.bindings.QtActivity;
import org.qtproject.qt5.android.bindings.QtApplication;
public class QGCActivity extends QtActivity implements TextToSpeech.OnInitListener
public class QGCActivity extends QtActivity
{
public static int BAD_PORT = 0;
private static QGCActivity m_instance;
......@@ -66,7 +64,6 @@ public class QGCActivity extends QtActivity implements TextToSpeech.OnInitListen
private BroadcastReceiver m_UsbReceiver = null;
private final static ExecutorService m_Executor = Executors.newSingleThreadExecutor();
private static final String TAG = "QGC_QGCActivity";
private static TextToSpeech m_tts;
private static PowerManager.WakeLock m_wl;
public static Context m_context;
......@@ -111,17 +108,9 @@ public class QGCActivity extends QtActivity implements TextToSpeech.OnInitListen
Log.i(TAG, "Instance created");
}
/////////////////////////////////////////////////////////////////////////////////////////////////////////
//
// Text To Speech
// Pigback a ride for providing TTS to QGC
//
/////////////////////////////////////////////////////////////////////////////////////////////////////////
@Override
public void onCreate(Bundle savedInstanceState) {
super.onCreate(savedInstanceState);
m_tts = new TextToSpeech(this,this);
PowerManager pm = (PowerManager)m_instance.getSystemService(Context.POWER_SERVICE);
m_wl = pm.newWakeLock(PowerManager.SCREEN_BRIGHT_WAKE_LOCK, "QGroundControl");
if(m_wl != null) {
......@@ -140,7 +129,6 @@ public class QGCActivity extends QtActivity implements TextToSpeech.OnInitListen
m_wl.release();
Log.i(TAG, "SCREEN_BRIGHT_WAKE_LOCK released.");
}
m_tts.shutdown();
} catch(Exception e) {
Log.e(TAG, "Exception onDestroy()");
}
......@@ -150,12 +138,6 @@ public class QGCActivity extends QtActivity implements TextToSpeech.OnInitListen
public void onInit(int status) {
}
public static void say(String msg)
{
Log.i(TAG, "Say: " + msg);
m_tts.speak(msg, TextToSpeech.QUEUE_FLUSH, null);
}
/////////////////////////////////////////////////////////////////////////////////////////////////////////
//
// Find all current devices that match the device filter described in the androidmanifest.xml and the
......
......@@ -47,6 +47,9 @@
<file alias="wifi.svg">src/AutoPilotPlugins/Common/Images/wifi.svg</file>
<file alias="arrow-down.png">src/QmlControls/arrow-down.png</file>
<file alias="camera.svg">resources/camera.svg</file>
<file alias="camera_photo.svg">src/Camera/images/camera_photo.svg</file>
<file alias="camera_settings.svg">src/Camera/images/camera_settings.svg</file>
<file alias="camera_video.svg">src/Camera/images/camera_video.svg</file>
<file alias="check.png">src/QmlControls/check.png</file>
<file alias="FirmwareUpgradeIcon.png">src/VehicleSetup/FirmwareUpgradeIcon.png</file>
<file alias="FlightModesComponentIcon.png">src/AutoPilotPlugins/PX4/Images/FlightModesComponentIcon.png</file>
......
......@@ -224,7 +224,8 @@ QT += \
sql \
svg \
widgets \
xml
xml \
texttospeech
# Multimedia only used if QVC is enabled
!contains (DEFINES, QGC_DISABLE_UVC) {
......@@ -333,6 +334,7 @@ INCLUDEPATH += \
src \
src/api \
src/AnalyzeView \
src/Camera \
src/AutoPilotPlugins \
src/FlightDisplay \
src/FlightMap \
......@@ -485,6 +487,9 @@ HEADERS += \
src/AnalyzeView/ExifParser.h \
src/AnalyzeView/ULogParser.h \
src/AnalyzeView/PX4LogParser.h \
src/Camera/QGCCameraControl.h \
src/Camera/QGCCameraIO.h \
src/Camera/QGCCameraManager.h \
src/CmdLineOptParser.h \
src/FirmwarePlugin/PX4/px4_custom_mode.h \
src/FlightDisplay/VideoManager.h \
......@@ -565,7 +570,6 @@ HEADERS += \
src/Terrain.h \
src/Vehicle/MAVLinkLogManager.h \
src/VehicleSetup/JoystickConfigController.h \
src/audio/QGCAudioWorker.h \
src/comm/LinkConfiguration.h \
src/comm/LinkInterface.h \
src/comm/LinkManager.h \
......@@ -660,7 +664,6 @@ HEADERS += \
iOSBuild {
OBJECTIVE_SOURCES += \
src/audio/QGCAudioWorker_iOS.mm \
src/MobileScreenMgr.mm \
}
......@@ -673,6 +676,9 @@ SOURCES += \
src/AnalyzeView/ExifParser.cc \
src/AnalyzeView/ULogParser.cc \
src/AnalyzeView/PX4LogParser.cc \
src/Camera/QGCCameraControl.cc \
src/Camera/QGCCameraIO.cc \
src/Camera/QGCCameraManager.cc \
src/CmdLineOptParser.cc \
src/FlightDisplay/VideoManager.cc \
src/FlightMap/Widgets/ValuesWidgetController.cc \
......@@ -748,7 +754,6 @@ SOURCES += \
src/Terrain.cc \
src/Vehicle/MAVLinkLogManager.cc \
src/VehicleSetup/JoystickConfigController.cc \
src/audio/QGCAudioWorker.cpp \
src/comm/LinkConfiguration.cc \
src/comm/LinkInterface.cc \
src/comm/LinkManager.cc \
......
......@@ -21,6 +21,7 @@
<file alias="BluetoothSettings.qml">src/ui/preferences/BluetoothSettings.qml</file>
<file alias="CameraComponent.qml">src/AutoPilotPlugins/PX4/CameraComponent.qml</file>
<file alias="CameraComponentSummary.qml">src/AutoPilotPlugins/PX4/CameraComponentSummary.qml</file>
<file alias="CameraControl.qml">src/Camera/CameraControl.qml</file>
<file alias="CustomCommandWidget.qml">src/ViewWidgets/CustomCommandWidget.qml</file>
<file alias="DebugWindow.qml">src/ui/preferences/DebugWindow.qml</file>
<file alias="ESP8266Component.qml">src/AutoPilotPlugins/Common/ESP8266Component.qml</file>
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Dialogs 1.2
import QtGraphicalEffects 1.0
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
Rectangle {
id: mainRect
height: mainRow.height + (ScreenTools.defaultFontPixelWidth * 2)
width: mainRow.width + (ScreenTools.defaultFontPixelWidth * 2)
radius: ScreenTools.defaultFontPixelWidth * 0.5
color: qgcPal.globalTheme === QGCPalette.Light ? Qt.rgba(1,1,1,0.95) : Qt.rgba(0,0,0,0.75)
border.width: 1
border.color: qgcPal.globalTheme === QGCPalette.Light ? Qt.rgba(0,0,0,0.35) : Qt.rgba(1,1,1,0.35)
QGCPalette { id: qgcPal; colorGroupEnabled: true }
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _dynamicCameras: _activeVehicle ? _activeVehicle.dynamicCameras : null
property bool _isCamera: _dynamicCameras ? _dynamicCameras.cameras.count > 0 : false
property bool _cameraModeUndefined: _isCamera ? _dynamicCameras.cameras.get(0).cameraMode === QGCCameraControl.CAMERA_MODE_UNDEFINED : true
property bool _cameraVideoMode: _isCamera ? _dynamicCameras.cameras.get(0).cameraMode === QGCCameraControl.CAMERA_MODE_VIDEO : false
property bool _cameraPhotoMode: _isCamera ? _dynamicCameras.cameras.get(0).cameraMode === QGCCameraControl.CAMERA_MODE_PHOTO : false
property var _camera: _isCamera ? _dynamicCameras.cameras.get(0) : null // Single camera support for the time being
property real _spacers: ScreenTools.defaultFontPixelHeight * 0.5
property real _labelFieldWidth: ScreenTools.defaultFontPixelWidth * 30
property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 30
property bool _communicationLost: _activeVehicle ? _activeVehicle.connectionLost : false
property bool _hasModes: _isCamera && _camera && _camera.hasModes
MouseArea {
anchors.fill: parent
onWheel: { wheel.accepted = true; }
onPressed: { mouse.accepted = true; }
onReleased: { mouse.accepted = true; }
}
Connections {
target: QGroundControl.multiVehicleManager.activeVehicle
onConnectionLostChanged: {
if(_communicationLost) {
if(rootLoader.sourceComponent === cameraSettingsComponent) {
rootLoader.sourceComponent = null
}
}
}
}
Row {
id: mainRow
spacing: _spacers
anchors.centerIn: parent
Column {
spacing: _spacers
anchors.verticalCenter: parent.verticalCenter
//-----------------------------------------------------------------
QGCLabel {
id: cameraLabel
text: _isCamera ? _dynamicCameras.cameras.get(0).modelName : qsTr("Camera")
font.pointSize: ScreenTools.smallFontPointSize
anchors.horizontalCenter: parent.horizontalCenter
}
//-- Camera Mode (visible only if camera has modes)
Rectangle {
width: _hasModes ? ScreenTools.defaultFontPixelWidth * 12 : 0
height: _hasModes ? ScreenTools.defaultFontPixelWidth * 4 : 0
color: qgcPal.window
radius: height * 0.5
visible: _hasModes
anchors.horizontalCenter: parent.horizontalCenter
//-- Video Mode
Rectangle {
width: parent.height * 0.9
height: parent.height * 0.9
color: qgcPal.windowShadeDark
radius: height * 0.5
anchors.left: parent.left
anchors.leftMargin: 4
anchors.verticalCenter: parent.verticalCenter
QGCColoredImage {
anchors.fill: parent
source: "/qmlimages/camera_video.svg"
fillMode: Image.PreserveAspectFit
sourceSize.height: height
color: _cameraVideoMode ? qgcPal.colorGreen : qgcPal.text
MouseArea {
anchors.fill: parent
enabled: _cameraPhotoMode
onClicked: {
_camera.setVideoMode()
}
}
}
}
//-- Photo Mode
Rectangle {
width: parent.height * 0.9
height: parent.height * 0.9
color: qgcPal.window
radius: height * 0.5
anchors.right: parent.right
anchors.rightMargin: 4
anchors.verticalCenter: parent.verticalCenter
QGCColoredImage {
anchors.fill: parent
source: "/qmlimages/camera_photo.svg"
fillMode: Image.PreserveAspectFit
sourceSize.height: height
color: _cameraPhotoMode ? qgcPal.colorGreen : qgcPal.text
MouseArea {
anchors.fill: parent
enabled: _cameraVideoMode
onClicked: {
_camera.setPhotoMode()
}
}
}
}
}
//-- Settings
QGCColoredImage {
width: ScreenTools.defaultFontPixelWidth * 3
height: width
sourceSize.width: width
source: "/qmlimages/camera_settings.svg"
fillMode: Image.PreserveAspectFit
color: _cameraModeUndefined ? qgcPal.colorGrey : qgcPal.text
anchors.horizontalCenter: parent.horizontalCenter
MouseArea {
anchors.fill: parent
enabled: !_cameraModeUndefined
onClicked: {
if(rootLoader.sourceComponent === null) {
rootLoader.sourceComponent = cameraSettingsComponent
} else {
rootLoader.sourceComponent = null
}
}
}
}
}
//-- Shutter
Rectangle {
color: Qt.rgba(0,0,0,0)
width: ScreenTools.defaultFontPixelWidth * 6
height: width
radius: width * 0.5
border.color: qgcPal.buttonText
border.width: 3
anchors.verticalCenter: parent.verticalCenter
Rectangle {
width: parent.width * 0.75
height: width
radius: width * 0.5
color: _cameraModeUndefined ? qgcPal.colorGrey : qgcPal.colorRed
anchors.centerIn: parent
}
MouseArea {
anchors.fill: parent
enabled: !_cameraModeUndefined
onClicked: {
if(_cameraVideoMode) {
//-- Start/Stop Video
} else {
_camera.takePhoto()
}
}
}
}
}
Component {
id: cameraSettingsComponent
Item {
id: cameraSettingsRect
width: mainWindow.width
height: mainWindow.height
anchors.centerIn: parent
MouseArea {
anchors.fill: parent
onClicked: {
rootLoader.sourceComponent = null
}
}
Rectangle {
id: camSettingsRect
width: _labelFieldWidth + _editFieldWidth + (ScreenTools.defaultFontPixelWidth * 8)
height: Math.max(mainWindow.height * 0.65, ScreenTools.defaultFontPixelHeight * 20)
radius: ScreenTools.defaultFontPixelWidth
color: qgcPal.globalTheme === QGCPalette.Light ? Qt.rgba(1,1,1,0.95) : Qt.rgba(0,0,0,0.75)
border.width: 1
border.color: qgcPal.globalTheme === QGCPalette.Light ? Qt.rgba(0,0,0,0.35) : Qt.rgba(1,1,1,0.35)
anchors.centerIn: parent
QGCLabel {
id: cameraSettingsLabel
text: _cameraVideoMode ? qsTr("Video Settings") : qsTr("Camera Settings")
font.family: ScreenTools.demiboldFontFamily
font.pointSize: ScreenTools.mediumFontPointSize
anchors.margins: ScreenTools.defaultFontPixelHeight * 0.5
anchors.top: parent.top
anchors.left: parent.left
}
QGCFlickable {
clip: true
anchors.top: cameraSettingsLabel.bottom
anchors.topMargin: ScreenTools.defaultFontPixelHeight
anchors.bottom: parent.bottom
width: cameraSettingsCol.width
contentHeight: cameraSettingsCol.height
contentWidth: cameraSettingsCol.width
anchors.horizontalCenter: parent.horizontalCenter
Column {
id: cameraSettingsCol
spacing: ScreenTools.defaultFontPixelHeight * 0.5
width: camSettingsRect.width
anchors.margins: ScreenTools.defaultFontPixelHeight
//-------------------------------------------
//-- Camera Settings
Repeater {
model: _camera ? _camera.activeSettings : []
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
text: _camera.getFact(modelData).shortDescription
width: _labelFieldWidth
anchors.verticalCenter: parent.verticalCenter
}
FactComboBox {
width: _editFieldWidth
fact: _camera.getFact(modelData)
indexModel: false
visible: !_camera.getFact(modelData).typeIsBool
anchors.verticalCenter: parent.verticalCenter
}
Item {
width: _editFieldWidth
height: factSwitch.height
visible: _camera.getFact(modelData).typeIsBool
anchors.verticalCenter: parent.verticalCenter
Switch {
id: factSwitch
anchors.left: parent.left
checked: fact ? fact.value : false
onClicked: fact.value = checked ? 1 : 0
property var fact: _camera.getFact(modelData)
}
}
}
}
//-------------------------------------------
//-- Reset Camera
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
text: qsTr("Reset Camera Defaults")
width: _labelFieldWidth
anchors.verticalCenter: parent.verticalCenter
}
QGCButton {
text: qsTr("Reset")
onClicked: resetPrompt.open()
width: _editFieldWidth
anchors.verticalCenter: parent.verticalCenter
MessageDialog {
id: resetPrompt
title: qsTr("Reset Camera to Factory Settings")
text: qsTr("Confirm resetting all settings?")
standardButtons: StandardButton.Yes | StandardButton.No
onNo: resetPrompt.close()
onYes: {
// TODO
resetPrompt.close()
}
}
}
}
//-------------------------------------------
//-- Format Storage
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
text: qsTr("Storage")
width: _labelFieldWidth
anchors.verticalCenter: parent.verticalCenter
}
QGCButton {
text: qsTr("Format")
enabled: false
onClicked: formatPrompt.open()
width: _editFieldWidth
anchors.verticalCenter: parent.verticalCenter
MessageDialog {
id: formatPrompt
title: qsTr("Format Camera Storage")
text: qsTr("Confirm erasing all files?")
standardButtons: StandardButton.Yes | StandardButton.No
onNo: formatPrompt.close()
onYes: {
// TODO
formatPrompt.close()
}
}
}
}
}
}
}
Component.onCompleted: {
rootLoader.width = cameraSettingsRect.width
rootLoader.height = cameraSettingsRect.height
}
Keys.onBackPressed: {
rootLoader.sourceComponent = null
}
Keys.onEscapePressed: {
rootLoader.sourceComponent = null
}
}
}
}
This diff is collapsed.
/*!
* @file
* @brief Camera Controller
* @author Gus Grubba <mavlink@grubba.com>
*
*/
#pragma once
#include "QGCApplication.h"
#include <QLoggingCategory>
class QDomNode;
class QDomNodeList;
class QGCCameraParamIO;
Q_DECLARE_LOGGING_CATEGORY(CameraControlLog)
Q_DECLARE_LOGGING_CATEGORY(CameraControlLogVerbose)
//-----------------------------------------------------------------------------
class QGCCameraOptionExclusion : public QObject
{
public:
QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
: QObject(parent)
, param(param_)
, value(value_)
, exclusions(exclusions_)
{
}
QString param;
QString value;
QStringList exclusions;
};
//-----------------------------------------------------------------------------
class QGCCameraOptionRange : public QObject
{
public:
QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_)
: QObject(parent)
, param(param_)
, value(value_)
, targetParam(targetParam_)
, condition(condition_)
, optNames(optNames_)
, optValues(optValues_)
{
}
QString param;
QString value;
QString targetParam;
QString condition;
QStringList optNames;
QStringList optValues;
QVariantList optVariants;
};
//-----------------------------------------------------------------------------
class QGCCameraControl : public FactGroup
{
Q_OBJECT
friend class QGCCameraParamIO;
public:
QGCCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL);
virtual ~QGCCameraControl();
//-- cam_mode
enum CameraMode {
CAM_MODE_UNDEFINED = -1,
CAM_MODE_PHOTO = 0,
CAM_MODE_VIDEO = 1,
};
//-- Video Capture Status
enum VideoStatus {
VIDEO_CAPTURE_STATUS_STOPPED = 0,
VIDEO_CAPTURE_STATUS_RUNNING,
VIDEO_CAPTURE_STATUS_LAST,
VIDEO_CAPTURE_STATUS_UNDEFINED = 255
};
//-- Photo Capture Status
enum PhotoStatus {
PHOTO_CAPTURE_IDLE = 0,
PHOTO_CAPTURE_IN_PROGRESS,
PHOTO_CAPTURE_INTERVAL_IDLE,
PHOTO_CAPTURE_INTERVAL_IN_PROGRESS,
PHOTO_CAPTURE_LAST,
PHOTO_CAPTURE_STATUS_UNDEFINED = 255
};
Q_ENUMS(CameraMode)
Q_ENUMS(VideoStatus)
Q_ENUMS(PhotoStatus)
Q_PROPERTY(int version READ version NOTIFY infoChanged)
Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged)
Q_PROPERTY(QString vendor READ vendor NOTIFY infoChanged)
Q_PROPERTY(QString firmwareVersion READ firmwareVersion NOTIFY infoChanged)
Q_PROPERTY(qreal focalLength READ focalLength NOTIFY infoChanged)
Q_PROPERTY(QSizeF sensorSize READ sensorSize NOTIFY infoChanged)
Q_PROPERTY(QSize resolution READ resolution NOTIFY infoChanged)
Q_PROPERTY(bool capturesVideo READ capturesVideo NOTIFY infoChanged)
Q_PROPERTY(bool capturesPhotos READ capturesPhotos NOTIFY infoChanged)
Q_PROPERTY(bool hasModes READ hasModes 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)
Q_PROPERTY(quint32 storageFree READ storageFree NOTIFY storageFreeChanged)
Q_PROPERTY(QString storageFreeStr READ storageFreeStr NOTIFY storageFreeChanged)
Q_PROPERTY(quint32 storageTotal READ storageTotal NOTIFY storageTotalChanged)
Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged)
Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged)
Q_PROPERTY(PhotoStatus photoStatus READ photoStatus NOTIFY photoStatusChanged)
Q_PROPERTY(CameraMode cameraMode READ cameraMode WRITE setCameraMode NOTIFY cameraModeChanged)
Q_INVOKABLE virtual void setVideoMode ();
Q_INVOKABLE virtual void setPhotoMode ();
Q_INVOKABLE virtual void toggleMode ();
Q_INVOKABLE virtual bool takePhoto ();
Q_INVOKABLE virtual bool startVideo ();
Q_INVOKABLE virtual bool stopVideo ();
Q_INVOKABLE virtual bool toggleVideo ();
Q_INVOKABLE virtual void resetSettings ();
Q_INVOKABLE virtual void formatCard (int id = 1);
virtual int version () { return _version; }
virtual QString modelName () { return _modelName; }
virtual QString vendor () { return _vendor; }
virtual QString firmwareVersion ();
virtual qreal focalLength () { return (qreal)_info.focal_length; }
virtual QSizeF sensorSize () { return QSizeF(_info.sensor_size_h, _info.sensor_size_v); }
virtual QSize resolution () { return QSize(_info.resolution_h, _info.resolution_v); }
virtual bool capturesVideo () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO; }
virtual bool capturesPhotos () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE; }
virtual bool hasModes () { return _info.flags & CAMERA_CAP_FLAGS_HAS_MODES; }
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 int compID () { return _compID; }
virtual bool isBasic () { return _settings.size() == 0; }
virtual VideoStatus videoStatus ();
virtual PhotoStatus photoStatus ();
virtual CameraMode cameraMode () { return _cameraMode; }
virtual QStringList activeSettings () { return _activeSettings; }
virtual quint32 storageFree () { return _storageFree; }
virtual QString storageFreeStr ();
virtual quint32 storageTotal () { return _storageTotal; }
virtual void setCameraMode (CameraMode mode);
virtual void handleSettings (const mavlink_camera_settings_t& settings);
virtual void handleCaptureStatus (const mavlink_camera_capture_status_t& capStatus);
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);
//-- Notify controller a parameter has changed
virtual void factChanged (Fact* pFact);
//-- Allow controller to modify or invalidate incoming parameter
virtual bool incomingParameter (Fact* pFact, QVariant& newValue);
//-- Allow controller to modify or invalidate parameter change
virtual bool validateParameter (Fact* pFact, QVariant& newValue);
signals:
void infoChanged ();
void videoStatusChanged ();
void photoStatusChanged ();
void cameraModeChanged ();
void activeSettingsChanged ();
void storageFreeChanged ();
void storageTotalChanged ();
void dataReady (QByteArray data);
void parametersReady ();
protected:
virtual void _setVideoStatus (VideoStatus status);
virtual void _setPhotoStatus (PhotoStatus status);
virtual void _setCameraMode (CameraMode mode);
protected slots:
void _initWhenReady ();
void _requestCameraSettings ();
void _requestAllParameters ();
void _requestParamUpdates ();
void _requestCaptureStatus ();
void _requestStorageInfo ();
void _downloadFinished ();
void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
void _dataReady (QByteArray data);
void _paramDone ();
private:
bool _handleLocalization (QByteArray& bytes);
bool _replaceLocaleStrings (const QDomNode node, QByteArray& bytes);
bool _loadCameraDefinitionFile (QByteArray& bytes);
bool _loadConstants (const QDomNodeList nodeList);
bool _loadSettings (const QDomNodeList nodeList);
void _processRanges ();
bool _processCondition (const QString condition);
bool _processConditionTest (const QString conditionTest);
bool _loadNameValue (QDomNode option, const QString factName, FactMetaData* metaData, QString& optName, QString& optValue, QVariant& optVariant);
bool _loadRanges (QDomNode option, const QString factName, QString paramValue);
void _updateActiveList ();
void _updateRanges (Fact* pFact);
void _httpRequest (const QString& url);
void _handleDefinitionFile (const QString& url);
QStringList _loadExclusions (QDomNode option);
QStringList _loadUpdates (QDomNode option);
QString _getParamName (const char* param_id);
protected:
Vehicle* _vehicle;
int _compID;
mavlink_camera_information_t _info;
int _version;
bool _cached;
uint32_t _storageFree;
uint32_t _storageTotal;
QNetworkAccessManager* _netManager;
QString _modelName;
QString _vendor;
QString _cacheFile;
CameraMode _cameraMode;
VideoStatus _video_status;
PhotoStatus _photo_status;
QStringList _activeSettings;
QStringList _settings;
QTimer _captureStatusTimer;
QList<QGCCameraOptionExclusion*> _valueExclusions;
QList<QGCCameraOptionRange*> _optionRanges;
QMap<QString, QStringList> _originalOptNames;
QMap<QString, QVariantList> _originalOptValues;
QMap<QString, QGCCameraParamIO*> _paramIO;
int _storageInfoRetries;
int _captureInfoRetries;
//-- Parameters that require a full update
QMap<QString, QStringList> _requestUpdates;
QStringList _updatesToRequest;
};
/*!
* @file
* @brief Camera Controller
* @author Gus Grubba <mavlink@grubba.com>
*
*/
#include "QGCCameraControl.h"
#include "QGCCameraIO.h"
QGC_LOGGING_CATEGORY(CameraIOLog, "CameraIOLog")
QGC_LOGGING_CATEGORY(CameraIOLogVerbose, "CameraIOLogVerbose")
//-----------------------------------------------------------------------------
QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicle *vehicle)
: QObject(control)
, _control(control)
, _fact(fact)
, _vehicle(vehicle)
, _sentRetries(0)
, _requestRetries(0)
, _done(false)
, _updateOnSet(false)
, _forceUIUpdate(false)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
_paramWriteTimer.setSingleShot(true);
_paramWriteTimer.setInterval(3000);
_paramRequestTimer.setSingleShot(true);
_paramRequestTimer.setInterval(3500);
connect(&_paramWriteTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout);
connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout);
connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged);
connect(_fact, &Fact::_containerRawValueChanged, this, &QGCCameraParamIO::_containerRawValueChanged);
_pMavlink = qgcApp()->toolbox()->mavlinkProtocol();
//-- TODO: Even though we don't use anything larger than 32-bit, this should
// probably be updated.
switch (_fact->type()) {
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeBool:
_mavParamType = MAV_PARAM_TYPE_UINT8;
break;
case FactMetaData::valueTypeInt8:
_mavParamType = MAV_PARAM_TYPE_INT8;
break;
case FactMetaData::valueTypeUint16:
_mavParamType = MAV_PARAM_TYPE_UINT16;
break;
case FactMetaData::valueTypeInt16:
_mavParamType = MAV_PARAM_TYPE_INT16;
break;
case FactMetaData::valueTypeUint32:
_mavParamType = MAV_PARAM_TYPE_UINT32;
break;
case FactMetaData::valueTypeFloat:
_mavParamType = MAV_PARAM_TYPE_REAL32;
break;
case FactMetaData::valueTypeCustom:
_mavParamType = (MAV_PARAM_TYPE)11; // MAV_PARAM_TYPE_CUSTOM;
break;
default:
qWarning() << "Unsupported fact type" << _fact->type() << "for" << _fact->name();
// Fall through
case FactMetaData::valueTypeInt32:
_mavParamType = MAV_PARAM_TYPE_INT32;
break;
}
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::setParamRequest()
{
_paramRequestReceived = false;
_requestRetries = 0;
_paramRequestTimer.start();
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_factChanged(QVariant value)
{
if(!_forceUIUpdate) {
Q_UNUSED(value);
qCDebug(CameraIOLog) << "UI Fact" << _fact->name() << "changed to" << value;
_control->factChanged(_fact);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_containerRawValueChanged(const QVariant value)
{
if(!_fact->readOnly()) {
Q_UNUSED(value);
qCDebug(CameraIOLog) << "Update Fact from camera" << _fact->name();
_sentRetries = 0;
_sendParameter();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::sendParameter(bool updateUI)
{
qCDebug(CameraIOLog) << "Send Fact" << _fact->name();
_sentRetries = 0;
_updateOnSet = updateUI;
_sendParameter();
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_sendParameter()
{
mavlink_param_ext_set_t p;
memset(&p, 0, sizeof(mavlink_param_ext_set_t));
param_ext_union_t union_value;
mavlink_message_t msg;
FactMetaData::ValueType_t factType = _fact->type();
p.param_type = _mavParamType;
switch (factType) {
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeBool:
union_value.param_uint8 = (uint8_t)_fact->rawValue().toUInt();
break;
case FactMetaData::valueTypeInt8:
union_value.param_int8 = (int8_t)_fact->rawValue().toInt();
break;
case FactMetaData::valueTypeUint16:
union_value.param_uint16 = (uint16_t)_fact->rawValue().toUInt();
break;
case FactMetaData::valueTypeInt16:
union_value.param_int16 = (int16_t)_fact->rawValue().toInt();
break;
case FactMetaData::valueTypeUint32:
union_value.param_uint32 = (uint32_t)_fact->rawValue().toUInt();
break;
case FactMetaData::valueTypeFloat:
union_value.param_float = _fact->rawValue().toFloat();
break;
case FactMetaData::valueTypeCustom:
{
QByteArray custom = _fact->rawValue().toByteArray();
memcpy(union_value.bytes, custom.data(), std::max(custom.size(), MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN));
}
break;
default:
qCritical() << "Unsupported fact type" << factType << "for" << _fact->name();
// fall through
case FactMetaData::valueTypeInt32:
union_value.param_int32 = (int32_t)_fact->rawValue().toInt();
break;
}
memcpy(&p.param_value[0], &union_value.bytes[0], MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN);
p.target_system = (uint8_t)_vehicle->id();
p.target_component = (uint8_t)_control->compID();
strncpy(p.param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_ID_LEN);
mavlink_msg_param_ext_set_encode_chan(
_pMavlink->getSystemId(),
_pMavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
&p);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
_paramWriteTimer.start();
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_paramWriteTimeout()
{
if(++_sentRetries > 3) {
qCWarning(CameraIOLog) << "No response for param set:" << _fact->name();
_updateOnSet = false;
} else {
//-- Send it again
qCDebug(CameraIOLog) << "Param set retry:" << _fact->name() << _sentRetries;
_sendParameter();
_paramWriteTimer.start();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack)
{
_paramWriteTimer.stop();
if(ack.param_result == PARAM_ACK_ACCEPTED) {
QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
if(_fact->rawValue() != val) {
_fact->_containerSetRawValue(val);
if(_updateOnSet) {
_updateOnSet = false;
_control->factChanged(_fact);
}
}
} else if(ack.param_result == PARAM_ACK_IN_PROGRESS) {
//-- Wait a bit longer for this one
qCDebug(CameraIOLogVerbose) << "Param set in progress:" << _fact->name();
_paramWriteTimer.start();
} else {
if(ack.param_result == PARAM_ACK_FAILED) {
if(++_sentRetries < 3) {
//-- Try again
qCWarning(CameraIOLog) << "Param set failed:" << _fact->name() << _sentRetries;
_paramWriteTimer.start();
}
return;
} else if(ack.param_result == PARAM_ACK_VALUE_UNSUPPORTED) {
qCWarning(CameraIOLog) << "Param set unsuported:" << _fact->name();
}
//-- If UI changed and value was not set, restore UI
QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
if(_fact->rawValue() != val) {
if(_control->validateParameter(_fact, val)) {
_fact->_containerSetRawValue(val);
}
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::handleParamValue(const mavlink_param_ext_value_t& value)
{
_paramRequestTimer.stop();
QVariant newValue = _valueFromMessage(value.param_value, value.param_type);
if(_control->incomingParameter(_fact, newValue)) {
_fact->_containerSetRawValue(newValue);
}
_paramRequestReceived = true;
if(_forceUIUpdate) {
emit _fact->rawValueChanged(_fact->rawValue());
emit _fact->valueChanged(_fact->rawValue());
_forceUIUpdate = false;
}
if(!_done) {
_done = true;
_control->_paramDone();
}
qCDebug(CameraIOLog) << QString("handleParamValue() %1 %2").arg(_fact->name()).arg(_fact->rawValueString());
}
//-----------------------------------------------------------------------------
QVariant
QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type)
{
QVariant var;
param_ext_union_t u;
memcpy(u.bytes, value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN);
switch (param_type) {
case MAV_PARAM_TYPE_REAL32:
var = QVariant(u.param_float);
break;
case MAV_PARAM_TYPE_UINT8:
var = QVariant(u.param_uint8);
break;
case MAV_PARAM_TYPE_INT8:
var = QVariant(u.param_int8);
break;
case MAV_PARAM_TYPE_UINT16:
var = QVariant(u.param_uint16);
break;
case MAV_PARAM_TYPE_INT16:
var = QVariant(u.param_int16);
break;
case MAV_PARAM_TYPE_UINT32:
var = QVariant(u.param_uint32);
break;
case MAV_PARAM_TYPE_INT32:
var = QVariant(u.param_int32);
break;
case 11: //MAV_PARAM_TYPE_CUSTOM:
var = QVariant(QByteArray(value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN));
break;
default:
var = QVariant(0);
qCritical() << "Invalid param_type used for camera setting:" << param_type;
}
return var;
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_paramRequestTimeout()
{
if(++_requestRetries > 3) {
qCWarning(CameraIOLog) << "No response for param request:" << _fact->name();
if(!_done) {
_done = true;
_control->_paramDone();
}
} else {
//-- Request it again
qCDebug(CameraIOLog) << "Param request retry:" << _fact->name();
paramRequest(false);
_paramRequestTimer.start();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::paramRequest(bool reset)
{
if(reset) {
_requestRetries = 0;
_forceUIUpdate = true;
}
qCDebug(CameraIOLog) << "Request parameter:" << _fact->name();
char param_id[MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
memset(param_id, 0, sizeof(param_id));
strncpy(param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN);
mavlink_message_t msg;
mavlink_msg_param_ext_request_read_pack_chan(
_pMavlink->getSystemId(),
_pMavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
_vehicle->id(),
_control->compID(),
param_id,
-1);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
_paramRequestTimer.start();
}
/*!
* @file
* @brief Camera Controller
* @author Gus Grubba <mavlink@grubba.com>
*
*/
#pragma once
#include "QGCApplication.h"
#include <QLoggingCategory>
class QGCCameraControl;
Q_DECLARE_LOGGING_CATEGORY(CameraIOLog)
Q_DECLARE_LOGGING_CATEGORY(CameraIOLogVerbose)
MAVPACKED(
typedef struct {
union {
float param_float;
int32_t param_int32;
uint32_t param_uint32;
int16_t param_int16;
uint16_t param_uint16;
int8_t param_int8;
uint8_t param_uint8;
uint8_t bytes[MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN];
};
uint8_t type;
}) param_ext_union_t;
//-----------------------------------------------------------------------------
class QGCCameraParamIO : public QObject
{
public:
QGCCameraParamIO(QGCCameraControl* control, Fact* fact, Vehicle* vehicle);
void handleParamAck (const mavlink_param_ext_ack_t& ack);
void handleParamValue (const mavlink_param_ext_value_t& value);
void setParamRequest ();
bool paramDone () { return _done; }
void paramRequest (bool reset = true);
void sendParameter (bool updateUI = false);
QStringList optNames;
QVariantList optVariants;
private slots:
void _paramWriteTimeout ();
void _paramRequestTimeout ();
void _factChanged (QVariant value);
void _containerRawValueChanged (const QVariant value);
private:
void _sendParameter ();
QVariant _valueFromMessage (const char* value, uint8_t param_type);
private:
QGCCameraControl* _control;
Fact* _fact;
Vehicle* _vehicle;
int _sentRetries;
int _requestRetries;
bool _paramRequestReceived;
QTimer _paramWriteTimer;
QTimer _paramRequestTimer;
bool _done;
bool _updateOnSet;
MAV_PARAM_TYPE _mavParamType;
MAVLinkProtocol* _pMavlink;
bool _forceUIUpdate;
};
/*!
* @file
* @brief Camera Controller
* @author Gus Grubba <mavlink@grubba.com>
*
*/
#include "QGCApplication.h"
#include "QGCCameraManager.h"
QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog")
//-----------------------------------------------------------------------------
QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
: _vehicle(vehicle)
, _vehicleReadyState(false)
, _currentTask(0)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qCDebug(CameraManagerLog) << "QGCCameraManager Created";
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady);
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived);
}
//-----------------------------------------------------------------------------
QGCCameraManager::~QGCCameraManager()
{
}
//-----------------------------------------------------------------------------
QString
QGCCameraManager::controllerSource()
{
return QStringLiteral("/qml/CameraControl.qml");
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_vehicleReady(bool ready)
{
qCDebug(CameraManagerLog) << "_vehicleReady(" << ready << ")";
if(ready) {
if(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle() == _vehicle) {
_vehicleReadyState = true;
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
if(message.sysid == _vehicle->id()) {
switch (message.msgid) {
case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS:
_handleCaptureStatus(message);
break;
case MAVLINK_MSG_ID_STORAGE_INFORMATION:
_handleStorageInfo(message);
break;
case MAVLINK_MSG_ID_HEARTBEAT:
_handleHeartbeat(message);
break;
case MAVLINK_MSG_ID_CAMERA_INFORMATION:
_handleCameraInfo(message);
break;
case MAVLINK_MSG_ID_CAMERA_SETTINGS:
_handleCameraSettings(message);
break;
case MAVLINK_MSG_ID_PARAM_EXT_ACK:
_handleParamAck(message);
break;
case MAVLINK_MSG_ID_PARAM_EXT_VALUE:
_handleParamValue(message);
break;
}
}
}
//-----------------------------------------------------------------------------
void
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(_vehicleReadyState && _vehicle->id() == message.sysid && _vehicle->defaultComponentId() != message.compid) {
if(!_cameraInfoRequested[message.compid]) {
_cameraInfoRequested[message.compid] = true;
//-- Request camera info
_requestCameraInfo(message.compid);
}
}
}
//-----------------------------------------------------------------------------
QGCCameraControl*
QGCCameraManager::_findCamera(int id)
{
for(int i = 0; i < _cameras.count(); i++) {
if(_cameras[i]) {
QGCCameraControl* pCamera = qobject_cast<QGCCameraControl*>(_cameras[i]);
if(pCamera) {
if(pCamera->compID() == id) {
return pCamera;
}
} else {
qCritical() << "Null QGCCameraControl instance";
}
}
}
qWarning() << "Camera component id not found:" << id;
return NULL;
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
{
mavlink_camera_information_t 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];
QGCCameraControl* pCamera = _vehicle->firmwarePlugin()->createCameraControl(&info, _vehicle, message.compid, this);
if(pCamera) {
QQmlEngine::setObjectOwnership(pCamera, QQmlEngine::CppOwnership);
_cameras.append(pCamera);
emit camerasChanged();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleCaptureStatus(const mavlink_message_t &message)
{
QGCCameraControl* pCamera = _findCamera(message.compid);
if(pCamera) {
mavlink_camera_capture_status_t cap;
mavlink_msg_camera_capture_status_decode(&message, &cap);
pCamera->handleCaptureStatus(cap);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleStorageInfo(const mavlink_message_t& message)
{
QGCCameraControl* pCamera = _findCamera(message.compid);
if(pCamera) {
mavlink_storage_information_t st;
mavlink_msg_storage_information_decode(&message, &st);
pCamera->handleStorageInfo(st);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleCameraSettings(const mavlink_message_t& message)
{
QGCCameraControl* pCamera = _findCamera(message.compid);
if(pCamera) {
mavlink_camera_settings_t settings;
mavlink_msg_camera_settings_decode(&message, &settings);
pCamera->handleSettings(settings);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleParamAck(const mavlink_message_t& message)
{
QGCCameraControl* pCamera = _findCamera(message.compid);
if(pCamera) {
mavlink_param_ext_ack_t ack;
mavlink_msg_param_ext_ack_decode(&message, &ack);
pCamera->handleParamAck(ack);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleParamValue(const mavlink_message_t& message)
{
QGCCameraControl* pCamera = _findCamera(message.compid);
if(pCamera) {
mavlink_param_ext_value_t value;
mavlink_msg_param_ext_value_decode(&message, &value);
pCamera->handleParamValue(value);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_requestCameraInfo(int compID)
{
qCDebug(CameraManagerLog) << "_requestCameraInfo(" << compID << ")";
if(_vehicle) {
_vehicle->sendMavCommand(
compID, // target component
MAV_CMD_REQUEST_CAMERA_INFORMATION, // command id
false, // showError
1); // Do Request
}
}
/*!
* @file
* @brief Camera Controller
* @author Gus Grubba <mavlink@grubba.com>
*
*/
#pragma once
#include "QGCApplication.h"
#include <QLoggingCategory>
#include "QmlObjectListModel.h"
#include "QGCCameraControl.h"
#include <QObject>
#include <QTimer>
Q_DECLARE_LOGGING_CATEGORY(CameraManagerLog)
//-----------------------------------------------------------------------------
class QGCCameraManager : public QObject
{
Q_OBJECT
public:
QGCCameraManager(Vehicle* vehicle);
virtual ~QGCCameraManager();
Q_PROPERTY(QmlObjectListModel* cameras READ cameras NOTIFY camerasChanged)
Q_PROPERTY(QString controllerSource READ controllerSource NOTIFY controllerSourceChanged)
//-- Return a list of cameras provided by this vehicle
virtual QmlObjectListModel* cameras () { return &_cameras; }
//-- Camera controller source (QML)
virtual QString controllerSource ();
signals:
void camerasChanged ();
void controllerSourceChanged ();
protected slots:
void _vehicleReady (bool ready);
void _mavlinkMessageReceived (const mavlink_message_t& message);
protected:
QGCCameraControl* _findCamera (int id);
void _requestCameraInfo (int compID);
void _handleHeartbeat (const mavlink_message_t& message);
void _handleCameraInfo (const mavlink_message_t& message);
void _handleStorageInfo (const mavlink_message_t& message);
void _handleCameraSettings (const mavlink_message_t& message);
void _handleParamAck (const mavlink_message_t& message);
void _handleParamValue (const mavlink_message_t& message);
void _handleCaptureStatus (const mavlink_message_t& message);
protected:
Vehicle* _vehicle;
bool _vehicleReadyState;
int _currentTask;
QmlObjectListModel _cameras;
QMap<int, bool> _cameraInfoRequested;
};
<?xml version="1.0" encoding="UTF-8" ?>
<mavlinkcamera>
<definition version="1">
<model>SD II</model>
<vendor>Super Dupper Industries</vendor>
</definition>
<parameters>
<parameter name="CAM_MODE" type="uint32" default="1">
<description>Camera Mode</description>
<options>
<option name="Photo" value="0">
<!-- This tells us when Camera Mode is set to Photo mode, the following parameters should be ignored (hidden from UI or disabled)-->
<exclusions>
<exclude>CAM_VIDRES</exclude>
<exclude>CAM_VIDFMT</exclude>
<exclude>CAM_AUDIOREC</exclude>
</exclusions>
</option>
<option name="Video" value="1">
<exclusions>
<exclude>CAM_PHOTOFMT</exclude>
<exclude>CAM_PHOTOQUAL</exclude>
<exclude>CAM_PHOTORES</exclude>
</exclusions>
<parameterranges>
<!-- This tells us when Camera Mode is set to Video mode, the CAM_ISO parameter has only a subset of its normal options. -->
<parameterrange parameter="CAM_ISO">
<roption name="100" value="100" />
<roption name="200" value="200" />
<roption name="400" value="400" />
<roption name="800" value="800" />
<roption name="1600" value="1600" />
<roption name="3200" value="3200" />
</parameterrange>
</parameterranges>
</option>
</options>
</parameter>
<parameter name="CAM_WBMODE" type="uint32" default="0">
<description>White Balance Mode</description>
<options>
<option name="Auto" value="0" />
<option name="Sunny" value="1" />
<option name="Cloudy" value="2" />
<option name="Fluorescent" value="3" />
<option name="Incandescent" value="4" />
<option name="Sunset" value="5" />
</options>
</parameter>
<parameter name="CAM_EXPMODE" type="uint32" default="0">
<description>Exposure Mode</description>
<options default="0">
<option name="Auto" value="0">
<exclusions>
<exclude>CAM_ISO</exclude>
<exclude>CAM_SHUTTERSPD</exclude>
<exclude>CAM_APERTURE</exclude>
</exclusions>
</option>
<option name="Manual" value="1">
<exclusions>
<exclude>CAM_EV</exclude>
</exclusions>
</option>
</options>
</parameter>
<parameter name="CAM_APERTURE" type="uint32" default="0">
<description>Aperture</description>
<options>
<option name="1.8" value="0" />
<option name="2.0" value="1" />
<option name="2.4" value="2" />
<option name="4" value="3" />
<option name="5.6" value="4" />
<option name="8" value="5" />
<option name="11" value="6" />
<option name="16" value="7" />
<option name="22" value="8" />
</options>
</parameter>
<parameter name="CAM_SHUTTERSPD" type="float" default="0.016666">
<description>Shutter Speed</description>
<options>
<option name="4" value="4" />
<option name="3" value="3" />
<option name="2" value="2" />
<option name="1" value="1" />
<option name="1/4" value="0.25" />
<option name="1/8" value="0.125" />
<option name="1/15" value="0.066666" />
<option name="1/30" value="0.033333" />
<option name="1/60" value="0.016666" />
<option name="1/125" value="0.008" />
<option name="1/250" value="0.004" />
<option name="1/500" value="0.002" />
<option name="1/1000" value="0.001" />
</options>
</parameter>
<parameter name="CAM_ISO" type="uint32" default="100">
<description>ISO</description>
<options>
<option name="100" value="100" />
<option name="200" value="200" />
<option name="400" value="400" />
<option name="800" value="800" />
<option name="1600" value="1600" />
<option name="3200" value="3200" />
<option name="6400" value="6400" />
</options>
</parameter>
<parameter name="CAM_EV" type="float" default="0">
<description>Exposure Compensation</description>
<options>
<option name="-2" value="-2" />
<option name="-1.5" value="-1.5" />
<option name="-1" value="-1" />
<option name="-0.5" value="-0.5" />
<option name="0" value="0" />
<option name="+0.5" value="0.5" />
<option name="+1" value="1" />
<option name="+1.5" value="1.5" />
<option name="+2" value="2" />
</options>
</parameter>
<parameter name="CAM_VIDRES" type="uint32" default="0">
<description>Video Resolution</description>
<options>
<option name="3840x2160 30P" value="0">
<parameterranges>
<!-- When Camera Mode is Video and Exposure Mode is Manual, Shutter Speed cannot be slower than the frame rate -->
<parameterrange parameter="CAM_SHUTTERSPD" condition="CAM_MODE=1 AND CAM_EXPMODE=1">
<roption name="1/30" value="0.033333" />
<roption name="1/60" value="0.016666" />
<roption name="1/125" value="0.008" />
<roption name="1/250" value="0.004" />
<roption name="1/500" value="0.002" />
<roption name="1/1000" value="0.001" />
</parameterrange>
</parameterranges>
</option>
<option name="3840x2160 24P" value="1">
<parameterranges>
<parameterrange parameter="CAM_SHUTTERSPD" condition="CAM_MODE=1 AND CAM_EXPMODE=1">
<roption name="1/30" value="0.033333" />
<roption name="1/60" value="0.016666" />
<roption name="1/125" value="0.008" />
<roption name="1/250" value="0.004" />
<roption name="1/500" value="0.002" />
<roption name="1/1000" value="0.001" />
</parameterrange>
</parameterranges>
</option>
<option name="1920x1080 60P" value="2">
<parameterranges>
<parameterrange parameter="CAM_SHUTTERSPD" condition="CAM_MODE=1 AND CAM_EXPMODE=1">
<roption name="1/60" value="0.016666" />
<roption name="1/125" value="0.008" />
<roption name="1/250" value="0.004" />
<roption name="1/500" value="0.002" />
<roption name="1/1000" value="0.001" />
</parameterrange>
</parameterranges>
</option>
<option name="1920x1080 30P" value="3">
<parameterranges>
<parameterrange parameter="CAM_SHUTTERSPD" condition="CAM_MODE=1 AND CAM_EXPMODE=1">
<roption name="1/30" value="0.033333" />
<roption name="1/60" value="0.016666" />
<roption name="1/125" value="0.008" />
<roption name="1/250" value="0.004" />
<roption name="1/500" value="0.002" />
<roption name="1/1000" value="0.001" />
</parameterrange>
</parameterranges>
</option>
<option name="1920x1080 24P" value="4">
<parameterranges>
<parameterrange parameter="CAM_SHUTTERSPD" condition="CAM_MODE=1 AND CAM_EXPMODE=1">
<roption name="1/30" value="0.033333" />
<roption name="1/60" value="0.016666" />
<roption name="1/125" value="0.008" />
<roption name="1/250" value="0.004" />
<roption name="1/500" value="0.002" />
<roption name="1/1000" value="0.001" />
</parameterrange>
</parameterranges>
</option>
</options>
</parameter>
<parameter name="CAM_VIDFMT" type="uint32" default="0">
<description>Video Format</description>
<options>
<option name="h.264" value="0" />
<option name="HEVC" value="1" />
</options>
</parameter>
<parameter name="CAM_AUDIOREC" type="bool" default="0">
<description>Record Audio</description>
</parameter>
<parameter name="CAM_METERING" type="uint32" default="0">
<description>Metering Mode</description>
<options>
<option name="Average" value="0" />
<option name="Center" value="1" />
<option name="Spot" value="2" />
</options>
</parameter>
<parameter name="CAM_COLORMODE" type="uint32" default="1">
<description>Color Mode</description>
<options>
<option name="Neutral" value="0" />
<option name="Enhanced" value="1" />
<option name="Unprocessed" value="2" />
<option name="Black &amp; White" value="3" />
</options>
</parameter>
<parameter name="CAM_PHOTORES" type="uint32" default="0">
<description>Photo Resolution</description>
<options>
<option name="Large" value="0" />
<option name="Medium" value="1" />
<option name="Small" value="2" />
</options>
</parameter>
<parameter name="CAM_PHOTOFMT" type="uint32" default="0">
<description>Image Format</description>
<options>
<option name="Jpeg" value="0" />
<option name="Raw" value="1">
<exclusions>
<exclude>CAM_PHOTOQUAL</exclude>
<exclude>CAM_PHOTORES</exclude>
</exclusions>
</option>
<option name="Jpeg+Raw" value="2" />
</options>
</parameter>
<parameter name="CAM_PHOTOQUAL" type="uint32" default="1">
<description>Image Quality</description>
<options>
<option name="Fine" value="0" />
<option name="Medium" value="1" />
<option name="Low" value="2" />
</options>
</parameter>
</parameters>
<!-- Video Streams (Optional. If not present, the standard MAVLink video stream discovery will be used instead) -->
<videostreams>
<!-- If exclusive is 0, all streams run at the same time. The layer defines the order. -->
<!-- If exclusive is 1, the user will select one of the availabe streams and only that one is shown. -->
<videostream exclusive="0" layer="0">
<description>Visible Light</description>
<url>rtsp://192.168.92.1:1525/live</url>
</videostream>
<videostream exclusive="0" layer="1">
<description>Thermal Imaging</description>
<url>rtsp://192.168.92.1:4525/live</url>
</videostream>
</videostreams>
<localization>
<!-- If no appropriate locale is found, the original (above) will be used -->
<!-- At runtime, the code will go through every "description" and "option name" looking for "original" and replace it with "translated" -->
<locale name="pt_BR">
<strings original="Aperture" translated="Abertura" />
<strings original="Auto" translated="Automático" />
<strings original="Average" translated="Média" />
<strings original="Black &amp; White" translated="Preto e Branco" />
<strings original="Camera Mode" translated="Modo de Operação" />
<strings original="Center" translated="Centro" />
<strings original="Cloudy" translated="Nublado" />
<strings original="Color Mode" translated="Processo de Cor" />
<strings original="Enhanced" translated="Realçado" />
<strings original="Exposure Compensation" translated="Compensação de Exposição" />
<strings original="Exposure Mode" translated="Modo de Exposição" />
<strings original="Fine" translated="Fino" />
<strings original="Fluorescent" translated="Fluorescente" />
<strings original="Image Format" translated="Formato de Imagem" />
<strings original="Image Quality" translated="Qualidade de Imagem" />
<strings original="Incandescent" translated="Incandescente" />
<strings original="Large" translated="Grande" />
<strings original="Low" translated="Baixa" />
<strings original="Manual" translated="Manual" />
<strings original="Medium" translated="Média" />
<strings original="Metering Mode" translated="Modo de Fotogrametria" />
<strings original="Neutral" translated="Neutro" />
<strings original="Photo Resolution" translated="Resolução de Foto" />
<strings original="Photo" translated="Foto" />
<strings original="Record Audio" translated="Gravar Áudio" />
<strings original="Shutter Priority" translated="Prioridade de Exposição" />
<strings original="Shutter Speed" translated="Velocidade" />
<strings original="Small" translated="Pequena" />
<strings original="Sunny" translated="Ensolarado" />
<strings original="Sunset" translated="Por do Sol" />
<strings original="Unprocessed" translated="Não Processado" />
<strings original="Video Format" translated="Format de Vídeo" />
<strings original="Video Resolution" translated="Resolução de Video" />
<strings original="Video" translated="Vídeo" />
<strings original="White Balance Mode" translated="Modo de Balanço Cromático" />
</locale>
</localization>
</mavlinkcamera>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 21.1.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
width="72px" height="72px" viewBox="0 0 72 72" style="enable-background:new 0 0 72 72;" xml:space="preserve">
<style type="text/css">
.st0{fill:#FFFFFF;}
</style>
<g>
<path class="st0" d="M63.4,16H51.6l-4.6-6c-0.3-0.3-0.7-0.5-1.1-0.5H26.7c-0.4,0-0.8,0.2-1.1,0.6L21.3,16H8.6c-2.8,0-5,2.2-5,5
v36.5c0,2.8,2.2,5,5,5h54.9c2.8,0,5-2.2,5-5V21C68.4,18.3,66.2,16,63.4,16L63.4,16L63.4,16z M36.7,54.8c-8.4,0-15.3-6.9-15.3-15.3
s6.9-15.3,15.3-15.3S52,31,52,39.5S45.1,54.8,36.7,54.8L36.7,54.8L36.7,54.8z"/>
</g>
</svg>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 21.1.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
width="72px" height="72px" viewBox="0 0 72 72" style="enable-background:new 0 0 72 72;" xml:space="preserve">
<style type="text/css">
.st0{display:none;}
.st1{display:inline;}
.st2{display:inline;stroke:#FFFFFF;stroke-width:1.1959;stroke-miterlimit:10;}
.st3{display:inline;fill:none;stroke:#FFFFFF;stroke-width:9.567;stroke-miterlimit:10;}
.st4{display:inline;stroke:#FFFFFF;stroke-width:0.9229;stroke-miterlimit:10;}
.st5{display:inline;fill:none;stroke:#FFFFFF;stroke-width:9.2289;stroke-miterlimit:10;}
.st6{display:inline;stroke:#FFFFFF;stroke-width:1.3383;stroke-miterlimit:10;}
.st7{display:inline;fill:#FFFFFF;}
.st8{display:inline;opacity:0.7;stroke:#FFFFFF;stroke-width:1.494;stroke-miterlimit:10;enable-background:new ;}
.st9{display:inline;opacity:0.7;stroke:#FFFFFF;stroke-width:0.9492;stroke-miterlimit:10;enable-background:new ;}
.st10{display:inline;fill:none;stroke:#000000;stroke-width:23.0795;stroke-miterlimit:10;}
.st11{enable-background:new ;}
.st12{fill:none;stroke:#000000;stroke-miterlimit:10;}
.st13{display:inline;fill:#FFFFFF;stroke:#000000;stroke-miterlimit:10;}
.st14{display:inline;stroke:#000000;stroke-width:19.9759;stroke-miterlimit:10;}
.st15{display:inline;stroke:#000000;stroke-width:20.4762;stroke-miterlimit:10;}
.st16{display:inline;stroke:#000000;stroke-miterlimit:10;}
.st17{fill:#FFFFFF;}
</style>
<g id="Media_play_icon" class="st0">
<polygon class="st1" points="275.5,-149.9 24.1,-4.8 24.1,-295 "/>
</g>
<g id="Document_icon" class="st0">
<rect x="39.8" y="-291.1" class="st2" width="219.9" height="282.3"/>
<line class="st3" x1="80.1" y1="-249.2" x2="220" y2="-249.2"/>
<line class="st3" x1="80.1" y1="-223.2" x2="183.3" y2="-223.2"/>
<line class="st3" x1="80.1" y1="-197.2" x2="196.8" y2="-197.2"/>
<line class="st3" x1="80.1" y1="-171.1" x2="220" y2="-171.1"/>
<line class="st3" x1="80.1" y1="-145.1" x2="138.4" y2="-145.1"/>
<line class="st3" x1="80.1" y1="-119" x2="183.3" y2="-119"/>
<line class="st3" x1="80.1" y1="-93" x2="196.8" y2="-93"/>
</g>
<g id="Contact_icon" class="st0">
<rect x="7.1" y="-258.8" class="st4" width="285.8" height="217.9"/>
<polyline class="st5" points="281.7,-248.9 150,-146.2 19,-248.9 "/>
</g>
<g id="Image_icon" class="st0">
<rect x="12.4" y="-291.4" class="st6" width="274.7" height="283"/>
<rect x="39" y="-262.5" class="st7" width="220.5" height="220.5"/>
<polygon class="st8" points="185.9,-55.5 48.5,-55.7 117.4,-174.6 "/>
<polygon class="st9" points="238.6,-56.1 151.3,-56.2 195,-131.8 "/>
<circle class="st9" cx="182.9" cy="-198.5" r="23.9"/>
</g>
<g id="Map_icon" class="st0">
<circle class="st1" cx="149.8" cy="-196.1" r="99.2"/>
<polygon class="st1" points="149.8,-4 77.3,-129.6 222.3,-129.6 "/>
<circle class="st7" cx="149.8" cy="-197" r="34.3"/>
</g>
<g id="Calendar_icon" class="st0">
<rect x="29.3" y="-268.8" class="st10" width="241.3" height="248.6"/>
<text transform="matrix(1 0 0 1 50.4731 -72.7944)" class="st1" style="font-family:'Futura-Medium'; font-size:172.5264px;">31</text>
<text transform="matrix(1 0 0 1 50.4731 -72.7944)" style="display:inline;fill:none;stroke:#000000;stroke-miterlimit:10; font-family:'Futura-Medium'; font-size:172.5264px;">31</text>
<polyline class="st1" points="192.1,-38.2 250.8,-38.2 250.8,-96.9 "/>
<rect x="18" y="-291" class="st1" width="263.7" height="66.4"/>
<circle class="st13" cx="98.4" cy="-256" r="11.9"/>
<circle class="st13" cx="199.1" cy="-257.8" r="11.9"/>
</g>
<g id="Company_icon" class="st0">
<circle class="st14" cx="149.8" cy="-221.3" r="51.5"/>
<path class="st15" d="M59.4-13.1c0-81.1,40.5-146.9,90.4-146.9s90.4,65.8,90.4,146.9"/>
<polygon class="st16" points="88.7,-12.9 102.3,-12.8 95.9,-69.5 "/>
<polygon class="st16" points="201.6,-12.8 215.2,-12.7 208.7,-69.3 "/>
</g>
<g id="Layer_8">
<g id="BOOUm1.tif">
<g>
<path class="st17" d="M27,18.4c1.5,0,3,0,4.5,0c1,0.8,1.5,1.9,1.7,3.2c0.2,1.2,0.9,1.9,2,2.4c0.8,0.3,1.6,0.6,2.3,1
c1.8,1.1,3.5,0.6,5.2-0.4c1.7-1,2.2-1,3.6,0.4c0.4,0.4,0.7,0.7,1.1,1.1c1.5,1.5,1.6,2.5,0.4,4.3c-0.5,0.7-1,1.4-0.8,2.2
c0.5,1.9,1.1,3.8,2.2,5.4c0.8,1.1,2.2,1.3,3.5,1.6c1.4,0.3,1.8,1.4,1.7,2.6c-0.1,1.7,0.7,3.8-1.3,5c-0.3,0.2-0.7,0.2-1.1,0.3
c-1,0.3-2,0.6-2.8,1.3c-2,2.1-2.4,5.8-0.8,8.3c0.7,1.1,0.6,2-0.2,2.9c-0.4,0.5-0.8,0.9-1.3,1.3c-1.7,1.7-2.6,1.8-4.6,0.5
c-1.2-0.8-2.3-0.9-3.6-0.3c-0.6,0.3-1.2,0.6-1.8,0.7c-2.3,0.6-3.4,2.1-3.7,4.3c-0.2,1.3-1,1.9-2.3,2c-0.6,0-1.1,0-1.7,0
c-2.5,0-3.3-0.6-3.7-3c-0.1-0.7-0.3-1.3-0.9-1.7c-1.6-1.2-3.6-1.9-5.5-2.4c-1.3-0.3-2.4,0.6-3.5,1.3c-1,0.7-1.9,0.5-2.8-0.2
c-0.5-0.4-0.9-0.8-1.3-1.3c-1.8-1.8-1.9-2.6-0.5-4.7c0.7-1.1,0.8-2.2,0.4-3.3c-0.3-0.7-0.6-1.4-0.8-2.1c-0.6-2.3-2.2-3.3-4.3-3.7
c-0.6-0.1-1.2-0.3-1.5-0.9c-1.5-2.4-0.2-6.1,2.6-6.8c1.3-0.3,2.2-1,2.6-2.3c0.2-0.6,0.4-1.3,0.8-1.8c1.2-2,0.9-3.9-0.5-5.8
c-0.8-1.1-0.6-2,0.2-2.9c0.4-0.5,0.8-0.9,1.3-1.3c1.7-1.6,2.6-1.8,4.6-0.5c1.1,0.8,2.2,0.9,3.4,0.4c0.7-0.3,1.4-0.7,2.1-0.8
c2.2-0.5,3.2-2.1,3.6-4.2C25.6,19.4,26.1,18.8,27,18.4z M29.3,52.2c5,0,8.9-3.9,8.9-8.9c0-4.8-4.1-8.8-8.9-8.8
c-4.8,0-8.7,4-8.7,8.8C20.6,48.3,24.4,52.2,29.3,52.2z"/>
</g>
</g>
<g id="BOOUm1.tif_1_">
<g>
<path class="st17" d="M51.6,4.3c0.7-0.2,1.3-0.5,2-0.7c0.6,0.2,1,0.6,1.2,1.1c0.3,0.5,0.7,0.7,1.2,0.7c0.4,0,0.8,0,1.2,0
c1,0.2,1.6-0.3,2.2-1C60,3.7,60.2,3.7,61,4c0.2,0.1,0.4,0.2,0.7,0.3c0.9,0.4,1.1,0.8,0.9,1.8c-0.1,0.4-0.2,0.8,0,1.1
c0.5,0.8,1.1,1.5,1.9,2c0.5,0.4,1.2,0.2,1.8,0.1c0.6-0.1,1,0.3,1.2,0.8c0.2,0.8,0.9,1.5,0.2,2.4c-0.1,0.1-0.3,0.2-0.4,0.3
c-0.4,0.3-0.8,0.6-1,1c-0.5,1.2-0.1,2.9,1,3.7c0.5,0.4,0.6,0.8,0.4,1.3c-0.1,0.3-0.2,0.5-0.3,0.8c-0.5,1-0.8,1.2-1.9,1
c-0.6-0.1-1.2,0-1.6,0.4c-0.2,0.2-0.4,0.4-0.7,0.6c-0.9,0.6-1.1,1.4-0.9,2.5c0.1,0.6-0.1,1-0.7,1.2c-0.2,0.1-0.5,0.2-0.7,0.3
c-1.1,0.4-1.5,0.3-2.1-0.7c-0.2-0.3-0.4-0.5-0.7-0.6c-0.9-0.3-1.9-0.3-2.8-0.1c-0.6,0.1-1,0.6-1.3,1.1c-0.3,0.5-0.8,0.5-1.3,0.4
c-0.3-0.1-0.5-0.2-0.8-0.3c-1.1-0.5-1.2-0.8-1-1.9c0.1-0.6,0-1.1-0.4-1.5c-0.2-0.3-0.5-0.5-0.7-0.8c-0.6-0.9-1.5-1.1-2.5-0.9
c-0.3,0.1-0.6,0.1-0.8-0.1c-1.1-0.8-1.1-2.6,0-3.4c0.5-0.3,0.8-0.8,0.8-1.4c0-0.3,0-0.6,0-0.9c0.2-1.1-0.3-1.9-1.1-2.4
c-0.5-0.3-0.6-0.8-0.4-1.3c0.1-0.3,0.2-0.5,0.3-0.8C46.6,9,47,8.7,48.1,9c0.6,0.1,1.1,0,1.6-0.4c0.2-0.2,0.5-0.5,0.8-0.7
c0.9-0.6,1.1-1.5,0.8-2.4C51.2,5,51.3,4.7,51.6,4.3z M58.1,18.6c2.1-0.8,3.2-3.2,2.4-5.3c-0.8-2.1-3.2-3.1-5.3-2.3
c-2.1,0.8-3.1,3.1-2.3,5.3C53.7,18.4,56,19.4,58.1,18.6z"/>
</g>
</g>
</g>
</svg>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 21.1.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
width="72px" height="72px" viewBox="0 0 72 72" style="enable-background:new 0 0 72 72;" xml:space="preserve">
<style type="text/css">
.st0{fill:#FFFFFF;}
</style>
<g>
<path class="st0" d="M44,17.1c-5.8,0-11.7,0-17.5,0c-5.8,0-11.6,0-17.4,0c-0.4,0-0.8,0-1.2,0.1c-2.4,0.4-4.2,2.5-4.2,4.9
c0,9.3,0,18.6,0,27.8c0,0.8,0.2,1.6,0.6,2.3C5.3,54,6.9,54.9,9,54.9c11.7,0,23.3,0,35,0c3,0,5.5-2.5,5.5-5.5c0-8.9,0-17.8,0-26.8
C49.5,19.6,47,17.1,44,17.1z"/>
<path class="st0" d="M68.1,22.5c-0.7,0-1.4,0-2.1,0c-0.2,0-0.4,0.1-0.5,0.1c-4.4,2.6-8.7,5.2-13.1,7.8c-0.2,0.1-0.2,0.2-0.2,0.4
c0,3.4,0,6.8,0,10.3c0,0.2,0.1,0.3,0.2,0.4c4.2,2.5,8.5,5.1,12.7,7.6c0.4,0.2,0.8,0.4,1.3,0.4c0.7,0,1.3,0,2,0c0-9,0-18,0-27
C68.3,22.5,68.2,22.5,68.1,22.5z"/>
</g>
</svg>
......@@ -17,6 +17,8 @@
#include <QtQml>
#include <QQmlEngine>
static const char* kMissingMetadata = "Meta data pointer missing";
Fact::Fact(QObject* parent)
: QObject(parent)
, _componentId(-1)
......@@ -29,7 +31,7 @@ Fact::Fact(QObject* parent)
FactMetaData* metaData = new FactMetaData(_type, this);
setMetaData(metaData);
// Better sage than sorry on object ownership
// Better safe than sorry on object ownership
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
}
......@@ -82,11 +84,12 @@ void Fact::forceSetRawValue(const QVariant& value)
if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) {
_rawValue.setValue(typedValue);
_sendValueChangedSignal(cookedValue());
//-- Must be in this order
emit _containerRawValueChanged(rawValue());
emit rawValueChanged(_rawValue);
}
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
}
}
......@@ -100,12 +103,13 @@ void Fact::setRawValue(const QVariant& value)
if (typedValue != _rawValue) {
_rawValue.setValue(typedValue);
_sendValueChangedSignal(cookedValue());
//-- Must be in this order
emit _containerRawValueChanged(rawValue());
emit rawValueChanged(_rawValue);
}
}
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
}
}
......@@ -114,7 +118,7 @@ void Fact::setCookedValue(const QVariant& value)
if (_metaData) {
setRawValue(_metaData->cookedTranslator()(value));
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
}
}
......@@ -126,7 +130,7 @@ void Fact::setEnumStringValue(const QString& value)
setCookedValue(_metaData->enumValues()[index]);
}
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
}
}
......@@ -135,16 +139,18 @@ void Fact::setEnumIndex(int index)
if (_metaData) {
setCookedValue(_metaData->enumValues()[index]);
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
}
}
void Fact::_containerSetRawValue(const QVariant& value)
{
_rawValue = value;
_sendValueChangedSignal(cookedValue());
emit vehicleUpdated(_rawValue);
emit rawValueChanged(_rawValue);
if(_rawValue != value) {
_rawValue = value;
_sendValueChangedSignal(cookedValue());
emit vehicleUpdated(_rawValue);
emit rawValueChanged(_rawValue);
}
}
QString Fact::name(void) const
......@@ -162,7 +168,7 @@ QVariant Fact::cookedValue(void) const
if (_metaData) {
return _metaData->rawTranslator()(_rawValue);
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return _rawValue;
}
}
......@@ -175,7 +181,7 @@ QString Fact::enumStringValue(void)
return _metaData->enumStrings()[enumIndex];
}
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
}
return QString();
......@@ -183,25 +189,32 @@ QString Fact::enumStringValue(void)
int Fact::enumIndex(void)
{
if (_metaData) {
int index = 0;
foreach (QVariant enumValue, _metaData->enumValues()) {
if (enumValue == rawValue()) {
return index;
static const double accuracy = 1.0 / 1000000.0;
if (_metaData) {
//-- Only enums have an index
if(_metaData->enumValues().count()) {
int index = 0;
foreach (QVariant enumValue, _metaData->enumValues()) {
if (enumValue == rawValue()) {
return index;
}
//-- Float comparissons don't always work
if(type() == FactMetaData::valueTypeFloat || type() == FactMetaData::valueTypeDouble) {
double diff = fabs(enumValue.toDouble() - rawValue().toDouble());
if(diff < accuracy) {
return index;
}
}
index ++;
}
index ++;
// Current value is not in list, add it manually
_metaData->addEnumInfo(QString("Unknown: %1").arg(rawValue().toString()), rawValue());
emit enumsChanged();
return index;
}
// Current value is not in list, add it manually
_metaData->addEnumInfo(QString("Unknown: %1").arg(rawValue().toString()), rawValue());
emit enumStringsChanged();
emit enumValuesChanged();
return index;
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
}
return -1;
}
......@@ -210,7 +223,7 @@ QStringList Fact::enumStrings(void) const
if (_metaData) {
return _metaData->enumStrings();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QStringList();
}
}
......@@ -220,17 +233,26 @@ QVariantList Fact::enumValues(void) const
if (_metaData) {
return _metaData->enumValues();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QVariantList();
}
}
void Fact::setEnumInfo(const QStringList& strings, const QVariantList& values)
{
if (_metaData) {
_metaData->setEnumInfo(strings, values);
} else {
qWarning() << kMissingMetadata;
}
}
QStringList Fact::bitmaskStrings(void) const
{
if (_metaData) {
return _metaData->bitmaskStrings();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QStringList();
}
}
......@@ -240,7 +262,7 @@ QVariantList Fact::bitmaskValues(void) const
if (_metaData) {
return _metaData->bitmaskValues();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QVariantList();
}
}
......@@ -314,7 +336,7 @@ QVariant Fact::rawDefaultValue(void) const
}
return _metaData->rawDefaultValue();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QVariant(0);
}
}
......@@ -327,7 +349,7 @@ QVariant Fact::cookedDefaultValue(void) const
}
return _metaData->cookedDefaultValue();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QVariant(0);
}
}
......@@ -347,7 +369,7 @@ QString Fact::shortDescription(void) const
if (_metaData) {
return _metaData->shortDescription();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QString();
}
}
......@@ -357,7 +379,7 @@ QString Fact::longDescription(void) const
if (_metaData) {
return _metaData->longDescription();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QString();
}
}
......@@ -367,7 +389,7 @@ QString Fact::rawUnits(void) const
if (_metaData) {
return _metaData->rawUnits();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QString();
}
}
......@@ -377,7 +399,7 @@ QString Fact::cookedUnits(void) const
if (_metaData) {
return _metaData->cookedUnits();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QString();
}
}
......@@ -387,7 +409,7 @@ QVariant Fact::rawMin(void) const
if (_metaData) {
return _metaData->rawMin();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QVariant(0);
}
}
......@@ -397,7 +419,7 @@ QVariant Fact::cookedMin(void) const
if (_metaData) {
return _metaData->cookedMin();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QVariant(0);
}
}
......@@ -412,7 +434,7 @@ QVariant Fact::rawMax(void) const
if (_metaData) {
return _metaData->rawMax();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QVariant(0);
}
}
......@@ -422,7 +444,7 @@ QVariant Fact::cookedMax(void) const
if (_metaData) {
return _metaData->cookedMax();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QVariant(0);
}
}
......@@ -437,7 +459,7 @@ bool Fact::minIsDefaultForType(void) const
if (_metaData) {
return _metaData->minIsDefaultForType();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return false;
}
}
......@@ -447,7 +469,7 @@ bool Fact::maxIsDefaultForType(void) const
if (_metaData) {
return _metaData->maxIsDefaultForType();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return false;
}
}
......@@ -457,7 +479,7 @@ int Fact::decimalPlaces(void) const
if (_metaData) {
return _metaData->decimalPlaces();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return FactMetaData::defaultDecimalPlaces;
}
}
......@@ -467,7 +489,7 @@ QString Fact::group(void) const
if (_metaData) {
return _metaData->group();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QString();
}
}
......@@ -487,7 +509,7 @@ bool Fact::valueEqualsDefault(void) const
return false;
}
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return false;
}
}
......@@ -497,7 +519,7 @@ bool Fact::defaultValueAvailable(void) const
if (_metaData) {
return _metaData->defaultValueAvailable();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return false;
}
}
......@@ -512,17 +534,33 @@ QString Fact::validate(const QString& cookedValue, bool convertOnly)
return errorString;
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return QString("Internal error: Meta data pointer missing");
}
}
QVariant Fact::clamp(const QString& cookedValue)
{
if (_metaData) {
QVariant typedValue;
if(_metaData->clampValue(cookedValue, typedValue)) {
return typedValue;
} else {
//-- If conversion failed, return current value
return rawValue();
}
} else {
qWarning() << kMissingMetadata;
}
return QVariant();
}
bool Fact::rebootRequired(void) const
{
if (_metaData) {
return _metaData->rebootRequired();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
return false;
}
}
......@@ -562,7 +600,7 @@ QString Fact::enumOrValueString(void)
return cookedValueString();
}
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
}
return QString();
}
......@@ -572,7 +610,27 @@ double Fact::increment(void) const
if (_metaData) {
return _metaData->increment();
} else {
qWarning() << "Meta data pointer missing";
qWarning() << kMissingMetadata;
}
return std::numeric_limits<double>::quiet_NaN();
}
bool Fact::hasControl(void) const
{
if (_metaData) {
return _metaData->hasControl();
} else {
qWarning() << kMissingMetadata;
return false;
}
}
bool Fact::readOnly(void) const
{
if (_metaData) {
return _metaData->readOnly();
} else {
qWarning() << kMissingMetadata;
return false;
}
}
......@@ -41,9 +41,9 @@ public:
Q_PROPERTY(QString defaultValueString READ cookedDefaultValueString CONSTANT)
Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT)
Q_PROPERTY(int enumIndex READ enumIndex WRITE setEnumIndex NOTIFY valueChanged)
Q_PROPERTY(QStringList enumStrings READ enumStrings NOTIFY enumStringsChanged)
Q_PROPERTY(QStringList enumStrings READ enumStrings NOTIFY enumsChanged)
Q_PROPERTY(QString enumStringValue READ enumStringValue WRITE setEnumStringValue NOTIFY valueChanged)
Q_PROPERTY(QVariantList enumValues READ enumValues NOTIFY enumValuesChanged)
Q_PROPERTY(QVariantList enumValues READ enumValues NOTIFY enumsChanged)
Q_PROPERTY(QString group READ group CONSTANT)
Q_PROPERTY(QString longDescription READ longDescription CONSTANT)
Q_PROPERTY(QVariant max READ cookedMax CONSTANT)
......@@ -64,10 +64,14 @@ public:
Q_PROPERTY(double increment READ increment CONSTANT)
Q_PROPERTY(bool typeIsString READ typeIsString CONSTANT)
Q_PROPERTY(bool typeIsBool READ typeIsBool CONSTANT)
Q_PROPERTY(bool hasControl READ hasControl CONSTANT)
Q_PROPERTY(bool readOnly READ readOnly CONSTANT)
/// Convert and validate value
/// @param convertOnly true: validate type conversion only, false: validate against meta data as well
Q_INVOKABLE QString validate(const QString& cookedValue, bool convertOnly);
/// Convert and clamp value
Q_INVOKABLE QVariant clamp(const QString& cookedValue);
QVariant cookedValue (void) const; /// Value after translation
QVariant rawValue (void) const { return _rawValue; } /// value prior to translation, careful
......@@ -106,6 +110,8 @@ public:
double increment (void) const;
bool typeIsString (void) const { return type() == FactMetaData::valueTypeString; }
bool typeIsBool (void) const { return type() == FactMetaData::valueTypeBool; }
bool hasControl (void) const;
bool readOnly (void) const;
/// Returns the values as a string with full 18 digit precision if float/double.
QString rawValueStringFullPrecision(void) const;
......@@ -132,17 +138,21 @@ public:
/// Sets the meta data associated with the Fact.
void setMetaData(FactMetaData* metaData);
FactMetaData* metaData() { return _metaData; }
//-- Value coming from Vehicle. This does NOT send a _containerRawValueChanged signal.
void _containerSetRawValue(const QVariant& value);
/// Generally you should not change the name of a fact. But if you know what you are doing, you can.
void _setName(const QString& name) { _name = name; }
/// Generally this is done during parsing. But if you know what you are doing, you can.
void setEnumInfo(const QStringList& strings, const QVariantList& values);
signals:
void bitmaskStringsChanged(void);
void bitmaskValuesChanged(void);
void enumStringsChanged(void);
void enumValuesChanged(void);
void enumsChanged(void);
void sendValueChangedSignalsChanged(bool sendValueChangedSignals);
/// QObject Property System signal for value property changes
......@@ -156,7 +166,7 @@ signals:
/// Signalled when property has been changed by a call to the property write accessor
///
/// This signal is meant for use by Fact container implementations.
/// This signal is meant for use by Fact container implementations. Used to send changed values to vehicle.
void _containerRawValueChanged(const QVariant& value);
protected:
......
......@@ -23,14 +23,30 @@ QGC_LOGGING_CATEGORY(FactGroupLog, "FactGroupLog")
FactGroup::FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent)
: QObject(parent)
, _updateRateMSecs(updateRateMsecs)
{
_setupTimer();
_nameToFactMetaDataMap = FactMetaData::createMapFromJsonFile(metaDataFile, this);
}
FactGroup::FactGroup(int updateRateMsecs, QObject* parent)
: QObject(parent)
, _updateRateMSecs(updateRateMsecs)
{
_setupTimer();
}
void FactGroup::_loadFromJsonArray(const QJsonArray jsonArray)
{
_nameToFactMetaDataMap = FactMetaData::createMapFromJsonArray(jsonArray, this);
}
void FactGroup::_setupTimer()
{
if (_updateRateMSecs > 0) {
connect(&_updateTimer, &QTimer::timeout, this, &FactGroup::_updateAllValues);
_updateTimer.setSingleShot(false);
_updateTimer.start(_updateRateMSecs);
}
_loadMetaData(metaDataFile);
}
Fact* FactGroup::getFact(const QString& name)
......@@ -107,8 +123,3 @@ void FactGroup::_updateAllValues(void)
fact->sendDeferredValueChangedSignal();
}
}
void FactGroup::_loadMetaData(const QString& jsonFilename)
{
_nameToFactMetaDataMap = FactMetaData::createMapFromJsonFile(jsonFilename, this);
}
......@@ -27,6 +27,7 @@ class FactGroup : public QObject
public:
FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent = NULL);
FactGroup(int updateRateMsecs, QObject* parent = NULL);
Q_PROPERTY(QStringList factNames READ factNames CONSTANT)
Q_PROPERTY(QStringList factGroupNames READ factGroupNames CONSTANT)
......@@ -39,10 +40,11 @@ public:
QStringList factNames(void) const { return _nameToFactMap.keys(); }
QStringList factGroupNames(void) const { return _nameToFactGroupMap.keys(); }
protected:
void _addFact(Fact* fact, const QString& name);
void _addFactGroup(FactGroup* factGroup, const QString& name);
void _loadFromJsonArray(const QJsonArray jsonArray);
int _updateRateMSecs; ///< Update rate for Fact::valueChanged signals, 0: immediate update
......@@ -50,13 +52,14 @@ private slots:
void _updateAllValues(void);
private:
void _loadMetaData(const QString& filename);
void _setupTimer();
QTimer _updateTimer;
protected:
QMap<QString, Fact*> _nameToFactMap;
QMap<QString, FactGroup*> _nameToFactGroupMap;
QMap<QString, FactMetaData*> _nameToFactMetaDataMap;
QTimer _updateTimer;
};
#endif
Supports Markdown
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