Commit 33056108 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #5713 from mavlink/camControl

Camera control
parents df93b9d7 880ee75d
......@@ -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
......
Subproject commit 6bbc8a51d8f37537732d3f5170093d49e64c6f4b
Subproject commit 5be9f5bf6002d58199cafafb5d416929fb8d8bcd
......@@ -47,6 +47,8 @@
<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_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 \
......@@ -566,7 +571,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 \
......@@ -661,7 +665,6 @@ HEADERS += \
iOSBuild {
OBJECTIVE_SOURCES += \
src/audio/QGCAudioWorker_iOS.mm \
src/MobileScreenMgr.mm \
}
......@@ -674,6 +677,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 \
......@@ -750,7 +756,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 \
......
......@@ -588,7 +588,10 @@ void APMSensorsComponentController::nextClicked(void)
&msg,
0, // command
1, // result
0); // progress
0, // progress
0, // result_param2
0, // target_system
0); // target_component
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
/*!
* @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()
{
}
//-----------------------------------------------------------------------------
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] << "Comp ID:" << message.compid;
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)
//-- Return a list of cameras provided by this vehicle
virtual QmlObjectListModel* cameras () { return &_cameras; }
signals:
void camerasChanged ();
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;
};
This diff is collapsed.
<?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{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>
This diff is collapsed.
......@@ -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
This diff is collapsed.
......@@ -41,15 +41,18 @@ public:
valueTypeString,
valueTypeBool,
valueTypeElapsedTimeInSeconds, // Internally stored as double, valueString displays as HH:MM:SS
valueTypeCustom, // Internally stored as a QByteArray
} ValueType_t;
typedef QVariant (*Translator)(const QVariant& from);
FactMetaData(QObject* parent = NULL);
FactMetaData(ValueType_t type, QObject* parent = NULL);
FactMetaData(ValueType_t type, const QString name, QObject* parent = NULL);
FactMetaData(const FactMetaData& other, QObject* parent = NULL);
static QMap<QString, FactMetaData*> createMapFromJsonFile(const QString& jsonFilename, QObject* metaDataParent);
static QMap<QString, FactMetaData*> createMapFromJsonArray(const QJsonArray jsonArray, QObject* metaDataParent);
static FactMetaData* createFromJsonObject(const QJsonObject& json, QObject* metaDataParent);
......@@ -95,6 +98,8 @@ public:
QString rawUnits (void) const { return _rawUnits; }
QString cookedUnits (void) const { return _cookedUnits; }
bool rebootRequired (void) const { return _rebootRequired; }
bool hasControl (void) const { return _hasControl; }
bool readOnly (void) const { return _readOnly; }
/// Amount to increment value when used in controls such as spin button or slider with detents.
/// NaN for no increment available.
......@@ -122,6 +127,8 @@ public:
void setRawUnits (const QString& rawUnits);
void setRebootRequired (bool rebootRequired) { _rebootRequired = rebootRequired; }
void setIncrement (double increment) { _increment = increment; }
void setHasControl (bool bValue) { _hasControl = bValue; }
void setReadOnly (bool bValue) { _readOnly = bValue; }
void setTranslators(Translator rawTranslator, Translator cookedTranslator);
......@@ -139,6 +146,12 @@ public:
/// Same as convertAndValidateRaw except for cookedValue input
bool convertAndValidateCooked(const QVariant& cookedValue, bool convertOnly, QVariant& typedValue, QString& errorString);
/// Converts the specified cooked value and clamps it (max/min)
/// @param cookedValue Value to convert, can be string
/// @param typeValue Converted value, correctly typed and clamped
/// @returns false: Convertion failed
bool clampValue(const QVariant& cookedValue, QVariant& typedValue);
static const int defaultDecimalPlaces = 3; ///< Default value for decimal places if not specified/known
static const int unknownDecimalPlaces = -1; ///< Number of decimal places to specify is not known
......@@ -216,6 +229,8 @@ private:
Translator _cookedTranslator;
bool _rebootRequired;
double _increment;
bool _hasControl;
bool _readOnly;
// Exact conversion constants
static const struct UnitConsts_s {
......@@ -248,6 +263,7 @@ private:
static const char* _mobileDefaultValueJsonKey;
static const char* _minJsonKey;
static const char* _maxJsonKey;
static const char* _hasControlJsonKey;
};
#endif
......@@ -18,6 +18,8 @@
#include <QDebug>
#include <QStack>
static const char* kInvalidConverstion = "Internal Error: No support for string parameters";
QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog")
QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVerboseLog")
......@@ -57,13 +59,17 @@ QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string,
convertTo = QVariant::Double;
break;
case FactMetaData::valueTypeString:
qWarning() << "Internal Error: No support for string parameters";
qWarning() << kInvalidConverstion;
convertTo = QVariant::String;
break;
case FactMetaData::valueTypeBool:
qWarning() << "Internal Error: No support for string parameters";
qWarning() << kInvalidConverstion;
convertTo = QVariant::Bool;
break;
case FactMetaData::valueTypeCustom:
qWarning() << kInvalidConverstion;
convertTo = QVariant::ByteArray;
break;
}
*convertOk = var.convert(convertTo);
......
......@@ -393,6 +393,7 @@ const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle)
false,
0,
this);
_cameraList.append(QVariant::fromValue(metaData));
metaData = new CameraMetaData(tr("Canon EOS-M 22mm"),
22.3,
......@@ -541,3 +542,20 @@ bool FirmwarePlugin::isVtol(const Vehicle* vehicle) const
return false;
}
}
QGCCameraManager* FirmwarePlugin::createCameraManager(Vehicle* vehicle)
{
Q_UNUSED(vehicle);
return NULL;
}
QGCCameraControl* FirmwarePlugin::createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject* parent)
{
Q_UNUSED(info);
Q_UNUSED(vehicle);
Q_UNUSED(compID);
Q_UNUSED(parent);
return NULL;
}
......@@ -25,6 +25,8 @@
#include <QVariantList>
class Vehicle;
class QGCCameraControl;
class QGCCameraManager;
/// This is the base class for Firmware specific plugins
///
......@@ -259,8 +261,15 @@ public:
virtual const QVariantList& toolBarIndicators(const Vehicle* vehicle);
/// Returns a list of CameraMetaData objects for available cameras on the vehicle.
/// TODO: This should go into QGCCameraManager
virtual const QVariantList& cameraList(const Vehicle* vehicle);
/// Creates vehicle camera manager. Returns NULL if not supported.
virtual QGCCameraManager* createCameraManager(Vehicle *vehicle);
/// Camera control. Returns NULL if not supported.
virtual QGCCameraControl* createCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL);
/// Returns a pointer to a dictionary of firmware-specific FactGroups
virtual QMap<QString, FactGroup*>* factGroups(void);
......
......@@ -21,6 +21,7 @@
#include "SensorsComponentController.h"
#include "PowerComponentController.h"
#include "RadioComponentController.h"
#include "QGCCameraManager.h"
#include <QDebug>
......@@ -125,6 +126,10 @@ PX4FirmwarePlugin::PX4FirmwarePlugin(void)
}
}
PX4FirmwarePlugin::~PX4FirmwarePlugin()
{
}
AutoPilotPlugin* PX4FirmwarePlugin::autopilotPlugin(Vehicle* vehicle)
{
return new PX4AutoPilotPlugin(vehicle, vehicle);
......@@ -546,3 +551,15 @@ bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicl
}
return true;
}
QGCCameraManager* PX4FirmwarePlugin::createCameraManager(Vehicle* vehicle)
{
return new QGCCameraManager(vehicle);
}
QGCCameraControl* PX4FirmwarePlugin::createCameraControl(const mavlink_camera_information_t* info, Vehicle *vehicle, int compID, QObject* parent)
{
return new QGCCameraControl(info, vehicle, compID, parent);
}
......@@ -24,6 +24,7 @@ class PX4FirmwarePlugin : public FirmwarePlugin
public:
PX4FirmwarePlugin(void);
~PX4FirmwarePlugin();
// Overrides from FirmwarePlugin
......@@ -65,6 +66,8 @@ public:
QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); }
bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const override;
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("COM_DISARM_LAND"); }
QGCCameraManager* createCameraManager (Vehicle* vehicle) override;
QGCCameraControl* createCameraControl (const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL) override;
protected:
typedef struct {
......
......@@ -20,6 +20,8 @@
#include <QDir>
#include <QDebug>
static const char* kInvalidConverstion = "Internal Error: No support for string parameters";
QGC_LOGGING_CATEGORY(PX4ParameterMetaDataLog, "PX4ParameterMetaDataLog")
PX4ParameterMetaData::PX4ParameterMetaData(void)
......@@ -57,13 +59,17 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact
convertTo = QVariant::Double;
break;
case FactMetaData::valueTypeString:
qWarning() << "Internal Error: No support for string parameters";
qWarning() << kInvalidConverstion;
convertTo = QVariant::String;
break;
case FactMetaData::valueTypeBool:
qWarning() << "Internal Error: No support for string parameters";
qWarning() << kInvalidConverstion;
convertTo = QVariant::Bool;
break;
case FactMetaData::valueTypeCustom:
qWarning() << kInvalidConverstion;
convertTo = QVariant::ByteArray;
break;
}
*convertOk = var.convert(convertTo);
......
......@@ -54,6 +54,8 @@ QGCView {
property alias _altitudeSlider: altitudeSlider
readonly property var _dynamicCameras: _activeVehicle ? _activeVehicle.dynamicCameras : null
readonly property bool _isCamera: _dynamicCameras ? _dynamicCameras.cameras.count > 0 : false
readonly property bool isBackgroundDark: _mainIsMap ? (_flightMap ? _flightMap.isSatelliteMap : true) : true
readonly property real _defaultRoll: 0
readonly property real _defaultPitch: 0
......@@ -196,7 +198,7 @@ QGCView {
z: _mainIsMap ? _panel.z + 1 : _panel.z + 2
anchors.left: _panel.left
anchors.bottom: _panel.bottom
visible: _mainIsMap || _isPipVisible
visible: _mainIsMap || _isPipVisible && !QGroundControl.videoManager.fullScreen
width: _mainIsMap ? _panel.width : _pipSize
height: _mainIsMap ? _panel.height : _pipSize * (9/16)
states: [
......@@ -275,7 +277,7 @@ QGCView {
anchors.left: _panel.left
anchors.bottom: _panel.bottom
anchors.margins: ScreenTools.defaultFontPixelHeight
visible: QGroundControl.videoManager.hasVideo
visible: QGroundControl.videoManager.hasVideo && !QGroundControl.videoManager.fullScreen
isHidden: !_isPipVisible
isDark: isBackgroundDark
onActivated: {
......@@ -327,7 +329,7 @@ QGCView {
qgcView: root
useLightColors: isBackgroundDark
missionController: _missionController
visible: singleVehicleView.checked
visible: singleVehicleView.checked && !QGroundControl.videoManager.fullScreen
}
//-------------------------------------------------------------------------
......@@ -335,6 +337,7 @@ QGCView {
Loader {
id: flyViewOverlay
z: flightDisplayViewWidgets.z + 1
visible: !QGroundControl.videoManager.fullScreen
height: ScreenTools.availableHeight
anchors.left: parent.left
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
......@@ -351,7 +354,7 @@ QGCView {
anchors.right: _flightVideo.right
height: ScreenTools.defaultFontPixelHeight * 2
width: height
visible: _videoReceiver && _videoReceiver.videoRunning && QGroundControl.settingsManager.videoSettings.showRecControl.rawValue && _flightVideo.visible
visible: _videoReceiver && _videoReceiver.videoRunning && QGroundControl.settingsManager.videoSettings.showRecControl.rawValue && _flightVideo.visible && !_isCamera && !QGroundControl.videoManager.fullScreen
opacity: 0.75
readonly property string recordBtnBackground: "BackgroundName"
......@@ -401,14 +404,13 @@ QGCView {
}
MultiVehicleList {
anchors.margins: _margins
anchors.top: singleMultiSelector.bottom
anchors.right: parent.right
anchors.bottom: parent.bottom
width: ScreenTools.defaultFontPixelWidth * 30
visible: !singleVehicleView.checked
z: _panel.z + 4
guidedActionsController: _guidedController
anchors.margins: _margins
anchors.top: singleMultiSelector.bottom
anchors.right: parent.right
anchors.bottom: parent.bottom
width: ScreenTools.defaultFontPixelWidth * 30
visible: !singleVehicleView.checked && !QGroundControl.videoManager.fullScreen
z: _panel.z + 4
}
//-- Virtual Joystick
......@@ -417,7 +419,7 @@ QGCView {
z: _panel.z + 5
width: parent.width - (_flightVideoPipControl.width / 2)
height: Math.min(ScreenTools.availableHeight * 0.25, ScreenTools.defaultFontPixelWidth * 16)
visible: _virtualJoystick ? _virtualJoystick.value : false
visible: (_virtualJoystick ? _virtualJoystick.value : false) && !QGroundControl.videoManager.fullScreen
anchors.bottom: _flightVideoPipControl.top
anchors.bottomMargin: ScreenTools.defaultFontPixelHeight * 2
anchors.horizontalCenter: flightDisplayViewWidgets.horizontalCenter
......@@ -430,7 +432,7 @@ QGCView {
}
ToolStrip {
visible: _activeVehicle ? _activeVehicle.guidedModeSupported : true
visible: (_activeVehicle ? _activeVehicle.guidedModeSupported : true) && !QGroundControl.videoManager.fullScreen
id: toolStrip
anchors.leftMargin: ScreenTools.defaultFontPixelWidth
anchors.left: _panel.left
......@@ -572,6 +574,7 @@ QGCView {
/// Close all dialogs
function closeAll() {
mainWindow.enableToolbar()
rootLoader.sourceComponent = null
guidedActionConfirm.visible = false
guidedActionList.visible = false
......
......@@ -8,25 +8,26 @@
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QGroundControl 1.0
import QGroundControl.FlightDisplay 1.0
import QGroundControl.FlightMap 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 QtQuick 2.3
import QtQuick.Controls 1.2
import QGroundControl 1.0
import QGroundControl.FlightDisplay 1.0
import QGroundControl.FlightMap 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
Item {
id: root
property double _ar: QGroundControl.settingsManager.videoSettings.aspectRatio.rawValue
property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0
property var _videoReceiver: QGroundControl.videoManager.videoReceiver
property double _ar: QGroundControl.settingsManager.videoSettings.aspectRatio.rawValue
property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0
property var _videoReceiver: QGroundControl.videoManager.videoReceiver
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _dynamicCameras: _activeVehicle ? _activeVehicle.dynamicCameras : null
property bool _connected: _activeVehicle ? !_activeVehicle.connectionLost : false
Rectangle {
id: noVideo
anchors.fill: parent
......@@ -39,6 +40,12 @@ Item {
font.pointSize: _mainIsMap ? ScreenTools.smallFontPointSize : ScreenTools.largeFontPointSize
anchors.centerIn: parent
}
MouseArea {
anchors.fill: parent
onDoubleClicked: {
QGroundControl.videoManager.fullScreen = !QGroundControl.videoManager.fullScreen
}
}
}
Rectangle {
anchors.fill: parent
......@@ -67,28 +74,34 @@ Item {
height: parent.height
width: 1
x: parent.width * 0.33
visible: _showGrid
visible: _showGrid && !QGroundControl.videoManager.fullScreen
}
Rectangle {
color: Qt.rgba(1,1,1,0.5)
height: parent.height
width: 1
x: parent.width * 0.66
visible: _showGrid
visible: _showGrid && !QGroundControl.videoManager.fullScreen
}
Rectangle {
color: Qt.rgba(1,1,1,0.5)
width: parent.width
height: 1
y: parent.height * 0.33
visible: _showGrid
visible: _showGrid && !QGroundControl.videoManager.fullScreen
}
Rectangle {
color: Qt.rgba(1,1,1,0.5)
width: parent.width
height: 1
y: parent.height * 0.66
visible: _showGrid
visible: _showGrid && !QGroundControl.videoManager.fullScreen
}
}
MouseArea {
anchors.fill: parent
onDoubleClicked: {
QGroundControl.videoManager.fullScreen = !QGroundControl.videoManager.fullScreen
}
}
}
......
......@@ -129,7 +129,7 @@ Item {
property bool __flightMode: _flightMode
function _outputState() {
console.log(qsTr("_activeVehicle(%1) _vehicleArmed(%2) guidedModeSupported(%3) _vehicleFlying(%4) _vehicleInRTLMode(%5) pauseVehicleSupported(%6) _vehiclePaused(%7) _flightMode(%8)").arg(_activeVehicle ? 1 : 0).arg(_vehicleArmed ? 1 : 0).arg(__guidedModeSupported ? 1 : 0).arg(_vehicleFlying ? 1 : 0).arg(_vehicleInRTLMode ? 1 : 0).arg(__pauseVehicleSupported ? 1 : 0).arg(_vehiclePaused ? 1 : 0).arg(_flightMode))
//console.log(qsTr("_activeVehicle(%1) _vehicleArmed(%2) guidedModeSupported(%3) _vehicleFlying(%4) _vehicleInRTLMode(%5) pauseVehicleSupported(%6) _vehiclePaused(%7) _flightMode(%8)").arg(_activeVehicle ? 1 : 0).arg(_vehicleArmed ? 1 : 0).arg(__guidedModeSupported ? 1 : 0).arg(_vehicleFlying ? 1 : 0).arg(_vehicleInRTLMode ? 1 : 0).arg(__pauseVehicleSupported ? 1 : 0).arg(_vehiclePaused ? 1 : 0).arg(_flightMode))
}
Component.onCompleted: _outputState()
......@@ -170,10 +170,10 @@ Item {
property var _actionData
on_FlightModeChanged: {
_vehiclePaused = _flightMode === _activeVehicle.pauseFlightMode
_vehicleInRTLMode = _flightMode === _activeVehicle.rtlFlightMode
_vehicleInLandMode = _flightMode === _activeVehicle.landFlightMode
_vehicleInMissionMode = _flightMode === _activeVehicle.missionFlightMode // Must be last to get correct signalling for showStartMission popups
_vehiclePaused = _activeVehicle ? _flightMode === _activeVehicle.pauseFlightMode : false
_vehicleInRTLMode = _activeVehicle ? _flightMode === _activeVehicle.rtlFlightMode : false
_vehicleInLandMode = _activeVehicle ? _flightMode === _activeVehicle.landFlightMode : false
_vehicleInMissionMode = _activeVehicle ? _flightMode === _activeVehicle.missionFlightMode : false // Must be last to get correct signalling for showStartMission popups
}
// Called when an action is about to be executed in order to confirm
......
......@@ -25,8 +25,8 @@ Rectangle {
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property real _vehicleAltitude: _activeVehicle ? _activeVehicle.altitudeRelative.rawValue : 0
property bool _fixedWing: _activeVehicle ? _activeVehicle.fixedWing : false
property real _sliderMaxAlt: _fixedWing ? _guidedSettings.fixedWingMaximumAltitude.rawValue : _guidedSettings.vehicleMaximumAltitude.rawValue
property real _sliderMinAlt: _fixedWing ? _guidedSettings.fixedWingMinimumAltitude.rawValue : _guidedSettings.vehicleMinimumAltitude.rawValue
property real _sliderMaxAlt: _guidedSettings ? (_fixedWing ? _guidedSettings.fixedWingMaximumAltitude.rawValue : _guidedSettings.vehicleMaximumAltitude.rawValue) : 0
property real _sliderMinAlt: _guidedSettings ? (_fixedWing ? _guidedSettings.fixedWingMinimumAltitude.rawValue : _guidedSettings.vehicleMinimumAltitude.rawValue) : 0
function reset() {
altSlider.value = 0
......
......@@ -34,6 +34,7 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
, _videoReceiver(NULL)
, _videoSettings(NULL)
, _fullScreen(false)
{
}
......
......@@ -35,10 +35,12 @@ public:
Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged)
Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged)
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged)
Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT)
bool hasVideo ();
bool isGStreamer ();
bool fullScreen () { return _fullScreen; }
QString videoSourceID () { return _videoSourceID; }
VideoReceiver* videoReceiver () { return _videoReceiver; }
......@@ -49,6 +51,8 @@ public:
bool uvcEnabled ();
#endif
void setfullScreen (bool f) { _fullScreen = f; emit fullScreenChanged(); }
// Override from QGCTool
void setToolbox (QGCToolbox *toolbox);
......@@ -56,6 +60,7 @@ signals:
void hasVideoChanged ();
void isGStreamerChanged ();
void videoSourceIDChanged ();
void fullScreenChanged ();
private slots:
void _videoSourceChanged ();
......@@ -70,6 +75,7 @@ private:
VideoReceiver* _videoReceiver;
VideoSettings* _videoSettings;
QString _videoSourceID;
bool _fullScreen;
};
#endif
This diff is collapsed.
......@@ -7,73 +7,132 @@
*
****************************************************************************/
/**
* @file
* @brief Implementation of audio output
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
* @author Thomas Gubler <thomasgubler@gmail.com>
*
*/
#include <QApplication>
#include <QDebug>
#include <QRegularExpression>
#include "GAudioOutput.h"
#include "QGCApplication.h"
#include "QGC.h"
#include "SettingsManager.h"
#if defined __android__
#include <QtAndroidExtras/QtAndroidExtras>
#include <QtAndroidExtras/QAndroidJniObject>
#endif
GAudioOutput::GAudioOutput(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
#ifndef __android__
, thread(new QThread())
, worker(new QGCAudioWorker())
#endif
{
#ifndef __android__
worker->moveToThread(thread);
connect(this, &GAudioOutput::textToSpeak, worker, &QGCAudioWorker::say);
connect(thread, &QThread::finished, thread, &QObject::deleteLater);
connect(thread, &QThread::finished, worker, &QObject::deleteLater);
thread->start();
#endif
_tts = new QTextToSpeech(this);
connect(_tts, &QTextToSpeech::stateChanged, this, &GAudioOutput::_stateChanged);
}
GAudioOutput::~GAudioOutput()
{
#ifndef __android__
thread->quit();
#endif
}
bool GAudioOutput::say(const QString& inText)
{
bool muted = qgcApp()->toolbox()->settingsManager()->appSettings()->audioMuted()->rawValue().toBool();
muted |= qgcApp()->runningUnitTests();
if (!muted && !qgcApp()->runningUnitTests()) {
#if defined __android__
#if defined QGC_SPEECH_ENABLED
static const char V_jniClassName[] {"org/mavlink/qgroundcontrol/QGCActivity"};
QAndroidJniEnvironment env;
if (env->ExceptionCheck()) {
env->ExceptionDescribe();
env->ExceptionClear();
QString text = fixTextMessageForAudio(inText);
if(_tts->state() == QTextToSpeech::Speaking) {
if(!_texts.contains(text)) {
//-- Some arbitrary limit
if(_texts.size() > 20) {
_texts.removeFirst();
}
_texts.append(text);
}
} else {
_tts->say(text);
}
QString text = QGCAudioWorker::fixTextMessageForAudio(inText);
QAndroidJniObject javaMessage = QAndroidJniObject::fromString(text);
QAndroidJniObject::callStaticMethod<void>(V_jniClassName, "say", "(Ljava/lang/String;)V", javaMessage.object<jstring>());
#endif
#else
emit textToSpeak(inText);
#endif
}
return true;
}
void GAudioOutput::_stateChanged(QTextToSpeech::State state)
{
if(state == QTextToSpeech::Ready) {
if(_texts.size()) {
QString text = _texts.first();
_texts.removeFirst();
_tts->say(text);
}
}
}
bool GAudioOutput::getMillisecondString(const QString& string, QString& match, int& number) {
static QRegularExpression re("([0-9]+ms)");
QRegularExpressionMatchIterator i = re.globalMatch(string);
while (i.hasNext()) {
QRegularExpressionMatch qmatch = i.next();
if (qmatch.hasMatch()) {
match = qmatch.captured(0);
number = qmatch.captured(0).replace("ms", "").toInt();
return true;
}
}
return false;
}
QString GAudioOutput::fixTextMessageForAudio(const QString& string) {
QString match;
QString newNumber;
QString result = string;
//-- Look for codified terms
if(result.contains("ERR ", Qt::CaseInsensitive)) {
result.replace("ERR ", "error ", Qt::CaseInsensitive);
}
if(result.contains("ERR:", Qt::CaseInsensitive)) {
result.replace("ERR:", "error.", Qt::CaseInsensitive);
}
if(result.contains("POSCTL", Qt::CaseInsensitive)) {
result.replace("POSCTL", "Position Control", Qt::CaseInsensitive);
}
if(result.contains("ALTCTL", Qt::CaseInsensitive)) {
result.replace("ALTCTL", "Altitude Control", Qt::CaseInsensitive);
}
if(result.contains("AUTO_RTL", Qt::CaseInsensitive)) {
result.replace("AUTO_RTL", "auto Return To Launch", Qt::CaseInsensitive);
} else if(result.contains("RTL", Qt::CaseInsensitive)) {
result.replace("RTL", "Return To Launch", Qt::CaseInsensitive);
}
if(result.contains("ACCEL ", Qt::CaseInsensitive)) {
result.replace("ACCEL ", "accelerometer ", Qt::CaseInsensitive);
}
if(result.contains("RC_MAP_MODE_SW", Qt::CaseInsensitive)) {
result.replace("RC_MAP_MODE_SW", "RC mode switch", Qt::CaseInsensitive);
}
if(result.contains("REJ.", Qt::CaseInsensitive)) {
result.replace("REJ.", "Rejected", Qt::CaseInsensitive);
}
if(result.contains("WP", Qt::CaseInsensitive)) {
result.replace("WP", "way point", Qt::CaseInsensitive);
}
if(result.contains("CMD", Qt::CaseInsensitive)) {
result.replace("CMD", "command", Qt::CaseInsensitive);
}
if(result.contains("COMPID", Qt::CaseInsensitive)) {
result.replace("COMPID", "component eye dee", Qt::CaseInsensitive);
}
if(result.contains(" params ", Qt::CaseInsensitive)) {
result.replace(" params ", " parameters ", Qt::CaseInsensitive);
}
if(result.contains(" id ", Qt::CaseInsensitive)) {
result.replace(" id ", " eye dee ", Qt::CaseInsensitive);
}
if(result.contains(" ADSB ", Qt::CaseInsensitive)) {
result.replace(" ADSB ", " Hey Dee Ess Bee ", Qt::CaseInsensitive);
}
int number;
if(getMillisecondString(string, match, number) && number > 1000) {
if(number < 60000) {
int seconds = number / 1000;
newNumber = QString("%1 second%2").arg(seconds).arg(seconds > 1 ? "s" : "");
} else {
int minutes = number / 60000;
int seconds = (number - (minutes * 60000)) / 1000;
if (!seconds) {
newNumber = QString("%1 minute%2").arg(minutes).arg(minutes > 1 ? "s" : "");
} else {
newNumber = QString("%1 minute%2 and %3 second%4").arg(minutes).arg(minutes > 1 ? "s" : "").arg(seconds).arg(seconds > 1 ? "s" : "");
}
}
result.replace(match, newNumber);
}
return result;
}
......@@ -7,75 +7,35 @@
*
****************************************************************************/
/**
* @file
* @brief Definition of audio output
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef GAUDIOOUTPUT_H
#define GAUDIOOUTPUT_H
#pragma once
#include <QObject>
#include <QTimer>
#include <QThread>
#include <QStringList>
#include <QTextToSpeech>
#include "QGCAudioWorker.h"
#include "QGCToolbox.h"
class QGCApplication;
/**
* @brief Audio Output (speech synthesizer and "beep" output)
* This class follows the singleton design pattern
* @see http://en.wikipedia.org/wiki/Singleton_pattern
*/
class GAudioOutput : public QGCTool
{
Q_OBJECT
public:
GAudioOutput(QGCApplication* app, QGCToolbox* toolbox);
~GAudioOutput();
/** @brief List available voices */
QStringList listVoices(void);
enum
{
VOICE_MALE = 0,
VOICE_FEMALE
} QGVoice;
enum AUDIO_SEVERITY
{
AUDIO_SEVERITY_EMERGENCY = 0,
AUDIO_SEVERITY_ALERT = 1,
AUDIO_SEVERITY_CRITICAL = 2,
AUDIO_SEVERITY_ERROR = 3,
AUDIO_SEVERITY_WARNING = 4,
AUDIO_SEVERITY_NOTICE = 5,
AUDIO_SEVERITY_INFO = 6,
AUDIO_SEVERITY_DEBUG = 7
};
static bool getMillisecondString (const QString& string, QString& match, int& number);
static QString fixTextMessageForAudio (const QString& string);
public slots:
/** @brief Say this text */
bool say(const QString& text);
bool say (const QString& text);
signals:
bool textToSpeak(QString text);
void beepOnce();
private slots:
void _stateChanged (QTextToSpeech::State state);
protected:
#if !defined __android__
QThread* thread;
QGCAudioWorker* worker;
#endif
QTextToSpeech* _tts;
QStringList _texts;
};
#endif // AUDIOOUTPUT_H
......@@ -111,13 +111,36 @@ bool JsonHelper::validateKeyTypes(const QJsonObject& jsonObject, const QStringLi
return true;
}
bool JsonHelper::parseEnum(const QJsonObject& jsonObject, QStringList& enumStrings, QStringList& enumValues, QString& errorString)
bool JsonHelper::parseEnum(const QJsonObject& jsonObject, QStringList& enumStrings, QStringList& enumValues, QString& errorString, QString valueName)
{
enumStrings = jsonObject.value(_enumStringsJsonKey).toString().split(",", QString::SkipEmptyParts);
enumValues = jsonObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts);
if(jsonObject.value(_enumStringsJsonKey).isArray()) {
// "enumStrings": ["Auto" , "Manual", "Shutter Priority", "Aperture Priority"],
QJsonArray jArray = jsonObject.value(_enumStringsJsonKey).toArray();
for(int i = 0; i < jArray.count(); ++i) {
enumStrings << jArray.at(i).toString();
}
} else {
// "enumStrings": "Auto,Manual,Shutter Priority,Aperture Priority",
enumStrings = jsonObject.value(_enumStringsJsonKey).toString().split(",", QString::SkipEmptyParts);
}
if(jsonObject.value(_enumValuesJsonKey).isArray()) {
// "enumValues": [0, 1, 2, 3, 4, 5],
QJsonArray jArray = jsonObject.value(_enumValuesJsonKey).toArray();
// This should probably be a variant list and not a string list.
for(int i = 0; i < jArray.count(); ++i) {
if(jArray.at(i).isString())
enumValues << jArray.at(i).toString();
else
enumValues << QString::number(jArray.at(i).toDouble());
}
} else {
// "enumValues": "0,1,2,3,4,5",
enumValues = jsonObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts);
}
if (enumStrings.count() != enumValues.count()) {
errorString = QObject::tr("enum strings/values count mismatch strings:values %1:%2").arg(enumStrings.count()).arg(enumValues.count());
errorString = QObject::tr("enum strings/values count mismatch in %3 strings:values %1:%2").arg(enumStrings.count()).arg(enumValues.count()).arg(valueName);
return false;
}
......
......@@ -104,7 +104,7 @@ public:
static void savePolygon(QmlObjectListModel& list, ///< List which contains vertices
QJsonArray& polygonArray); ///< Array to save into
static bool parseEnum(const QJsonObject& jsonObject, QStringList& enumStrings, QStringList& enumValues, QString& errorString);
static bool parseEnum(const QJsonObject& jsonObject, QStringList& enumStrings, QStringList& enumValues, QString& errorString, QString valueName = QString());
/// Returns NaN if the value is null, or it not the double value
static double possibleNaNJsonValue(const QJsonValue& value);
......
......@@ -47,10 +47,10 @@
},
{
"name": "CameraMode",
"shortDescription": "Specify whether the camera should switch to photo or video mode",
"shortDescription": "Specify whether the camera should switch to Photo, Video or Survey mode",
"type": "uint32",
"enumStrings": "Photo,Video",
"enumValues": "0,1",
"enumStrings": "Photo,Video,Survey",
"enumValues": "0,1,2",
"defaultValue": 0
}
]
......@@ -120,10 +120,9 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
MissionItem* item = new MissionItem(nextSequenceNumber++,
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
0, // camera id, all cameras
0, // Reserved (Set to 0)
_cameraModeFact.rawValue().toDouble(),
NAN, // Audio off/on
NAN, NAN, NAN, NAN, // param 4-7 reserved
NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autoContinue
false, // isCurrentItem
missionItemParent);
......@@ -153,7 +152,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item = new MissionItem(nextSequenceNumber++,
MAV_CMD_IMAGE_START_CAPTURE,
MAV_FRAME_MISSION,
0, // Camera ID, all cameras
0, // Reserved (Set to 0)
_cameraPhotoIntervalTimeFact.rawValue().toInt(), // Interval
0, // Unlimited photo count
NAN, NAN, NAN, NAN, // param 4-7 reserved
......@@ -179,7 +178,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item = new MissionItem(nextSequenceNumber++,
MAV_CMD_VIDEO_START_CAPTURE,
MAV_FRAME_MISSION,
0, // camera id = 0, all cameras
0, // Reserved (Set to 0)
0, // No CAMERA_CAPTURE_STATUS streaming
NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autoContinue
......@@ -191,7 +190,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item = new MissionItem(nextSequenceNumber++,
MAV_CMD_VIDEO_STOP_CAPTURE,
MAV_FRAME_MISSION,
0, // Camera ID, all cameras
0, // Reserved (Set to 0)
NAN, NAN, NAN, NAN, NAN, NAN, // param 2-7 reserved
true, // autoContinue
false, // isCurrentItem
......@@ -211,7 +210,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item = new MissionItem(nextSequenceNumber++,
MAV_CMD_IMAGE_STOP_CAPTURE,
MAV_FRAME_MISSION,
0, // camera id, all cameras
0, // Reserved (Set to 0)
NAN, NAN, NAN, NAN, NAN, NAN, // param 2-7 reserved
true, // autoContinue
false, // isCurrentItem
......@@ -222,7 +221,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item = new MissionItem(nextSequenceNumber++,
MAV_CMD_IMAGE_START_CAPTURE,
MAV_FRAME_MISSION,
0, // camera id = 0, all cameras
0, // Reserved (Set to 0)
0, // Interval (none)
1, // Take 1 photo
NAN, NAN, NAN, NAN, // param 4-7 reserved
......@@ -394,7 +393,7 @@ bool CameraSection::_scanSetCameraMode(QmlObjectListModel* visualItems, int scan
MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_SET_CAMERA_MODE) {
// We specifically don't test param 5/6/7 since we don't have NaN persistence for those fields
if (missionItem.param1() == 0 && (missionItem.param2() == 0 || missionItem.param2() == 1) && qIsNaN(missionItem.param3())) {
if (missionItem.param1() == 0 && (missionItem.param2() == CAMERA_MODE_IMAGE || missionItem.param2() == CAMERA_MODE_VIDEO || missionItem.param2() == CAMERA_MODE_IMAGE_SURVEY) && qIsNaN(missionItem.param3())) {
setSpecifyCameraMode(true);
cameraMode()->setRawValue(missionItem.param2());
visualItems->removeAt(scanIndex)->deleteLater();
......
......@@ -34,12 +34,6 @@ public:
};
Q_ENUMS(CameraAction)
enum CameraMode {
CameraModePhoto,
CameraModeVideo
};
Q_ENUMS(CameraMode)
Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged)
Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT)
Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT)
......
This diff is collapsed.
......@@ -72,5 +72,6 @@ private:
SimpleMissionItem* _validStopTimeItem;
SimpleMissionItem* _validCameraPhotoModeItem;
SimpleMissionItem* _validCameraVideoModeItem;
SimpleMissionItem* _validCameraSurveyPhotoModeItem;
SimpleMissionItem* _validTakePhotoItem;
};
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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