Commit a0321b80 authored by Gus Grubba's avatar Gus Grubba

Camera definition implementation

parent 00384b83
Subproject commit 6bbc8a51d8f37537732d3f5170093d49e64c6f4b
Subproject commit 05c8fa042e67888f98ce63e2a76bb35f38dd218f
......@@ -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>
......
......@@ -327,6 +327,7 @@ INCLUDEPATH += \
src \
src/api \
src/AnalyzeView \
src/Camera \
src/AutoPilotPlugins \
src/FlightDisplay \
src/FlightMap \
......@@ -479,6 +480,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 \
......@@ -660,6 +664,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 \
......
......@@ -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>
......
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 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
public:
QGCCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL);
~QGCCameraControl();
//-- cam_mode
enum CameraMode {
CAMERA_MODE_UNDEFINED = -1,
CAMERA_MODE_PHOTO = 0,
CAMERA_MODE_VIDEO = 1,
};
Q_ENUMS(CameraMode)
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(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged)
Q_PROPERTY(CameraMode cameraMode READ cameraMode WRITE setCameraMode NOTIFY cameraModeChanged)
Q_INVOKABLE void setVideoMode ();
Q_INVOKABLE void setPhotoMode ();
Q_INVOKABLE void toggleMode ();
Q_INVOKABLE void takePhoto ();
Q_INVOKABLE void startVideo ();
Q_INVOKABLE void stopVideo ();
Q_INVOKABLE void resetSettings ();
Q_INVOKABLE void formatCard (int id = 1);
int version () { return _version; }
QString modelName () { return _modelName; }
QString vendor () { return _vendor; }
QString firmwareVersion ();
qreal focalLength () { return (qreal)_info.focal_length; }
QSizeF sensorSize () { return QSizeF(_info.sensor_size_h, _info.sensor_size_v); }
QSize resolution () { return QSize(_info.resolution_h, _info.resolution_v); }
bool capturesVideo () { return true /*_info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO*/ ; }
bool capturesPhotos () { return true /*_info.flags & CAMERA_CAP_FLAGS_CAPTURE_PHOTO*/ ; }
bool hasModes () { return true /*_info.flags & CAMERA_CAP_FLAGS_HAS_MODES*/ ; }
bool photosInVideoMode () { return true /*_info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_PHOTO_IN_VIDEO_MODE*/ ; }
bool videoInPhotoMode () { return false /*_info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_PHOTO_MODE*/ ; }
int compID () { return _compID; }
bool isBasic () { return _settings.size() == 0; }
CameraMode cameraMode () { return _cameraMode; }
QStringList activeSettings () { return _activeSettings; }
void setCameraMode (CameraMode mode);
void handleSettings (const mavlink_camera_settings_t& settings);
void handleParamAck (const mavlink_param_ext_ack_t& ack);
void handleParamValue (const mavlink_param_ext_value_t& value);
void factChanged (Fact* pFact);
signals:
void infoChanged ();
void cameraModeChanged ();
void activeSettingsChanged ();
private slots:
void _requestCameraSettings ();
void _requestAllParameters ();
private:
bool _handleLocalization (QByteArray& bytes);
bool _replaceLocaleStrings (const QDomNode node, QByteArray& bytes);
bool _loadCameraDefinitionFile (const QString& file);
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);
QStringList _loadExclusions (QDomNode option);
QString _getParamName (const char* param_id);
private:
Vehicle* _vehicle;
int _compID;
mavlink_camera_information_t _info;
int _version;
QString _modelName;
QString _vendor;
CameraMode _cameraMode;
QStringList _activeSettings;
QStringList _settings;
QList<QGCCameraOptionExclusion*> _valueExclusions;
QList<QGCCameraOptionRange*> _optionRanges;
QMap<QString, QStringList> _originalOptNames;
QMap<QString, QVariantList> _originalOptValues;
QMap<QString, QGCCameraParamIO*> _paramIO;
};
/*!
* @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)
{
_paramWriteTimer.setSingleShot(true);
_paramWriteTimer.setInterval(3000);
_paramRequestTimer.setSingleShot(true);
_paramRequestTimer.setInterval(3000);
connect(&_paramWriteTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout);
connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout);
connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged);
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::setParamRequest()
{
_paramRequestReceived = false;
_requestRetries = 0;
_paramRequestTimer.start();
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_factChanged(QVariant value)
{
Q_UNUSED(value);
qCDebug(CameraIOLog) << "Fact" << _fact->name() << "changed";
_sendParameter();
//-- TODO: Do we really want to update the UI now or only when we receive the ACK?
_control->factChanged(_fact);
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_sendParameter()
{
//-- TODO: We should use something other than mavlink_param_union_t for PARAM_EXT_SET
mavlink_param_ext_set_t p;
mavlink_param_union_t union_value;
memset(&p, 0, sizeof(p));
FactMetaData::ValueType_t factType = _fact->type();
p.param_type = _factTypeToMavType(factType);
switch (factType) {
case FactMetaData::valueTypeUint8:
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;
default:
qCritical() << "Unsupported fact type" << factType;
// fall through
case FactMetaData::valueTypeInt32:
union_value.param_int32 = (int32_t)_fact->rawValue().toInt();
break;
}
memcpy(&p.param_value, &union_value.param_float, sizeof(float));
p.target_system = (uint8_t)_vehicle->id();
p.target_component = (uint8_t)_control->compID();
strncpy(p.param_id, _fact->name().toStdString().c_str(), sizeof(p.param_id));
MAVLinkProtocol* pMavlink = qgcApp()->toolbox()->mavlinkProtocol();
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();
} else {
//-- Send it again
qCDebug(CameraIOLog) << "Param set retry:" << _fact->name();
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), _msg);
_paramWriteTimer.start();
}
}
//-----------------------------------------------------------------------------
MAV_PARAM_TYPE
QGCCameraParamIO::_factTypeToMavType(FactMetaData::ValueType_t factType)
{
//-- TODO: Even though we don't use anything larger than 32-bit, this should
// probably be updated.
switch (factType) {
case FactMetaData::valueTypeUint8:
return MAV_PARAM_TYPE_UINT8;
case FactMetaData::valueTypeInt8:
return MAV_PARAM_TYPE_INT8;
case FactMetaData::valueTypeUint16:
return MAV_PARAM_TYPE_UINT16;
case FactMetaData::valueTypeInt16:
return MAV_PARAM_TYPE_INT16;
case FactMetaData::valueTypeUint32:
return MAV_PARAM_TYPE_UINT32;
case FactMetaData::valueTypeFloat:
return MAV_PARAM_TYPE_REAL32;
default:
qWarning() << "Unsupported fact type" << factType;
// fall through
case FactMetaData::valueTypeInt32:
return MAV_PARAM_TYPE_INT32;
}
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack)
{
_paramWriteTimer.stop();
if(ack.param_result == PARAM_ACK_ACCEPTED) {
_fact->setRawValue(_valueFromMessage(ack.param_value, ack.param_type), true);
}
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) {
qCWarning(CameraIOLog) << "Param set failed:" << _fact->name();
} else if(ack.param_result == PARAM_ACK_VALUE_UNSUPPORTED) {
qCWarning(CameraIOLog) << "Param set unsuported:" << _fact->name();
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::handleParamValue(const mavlink_param_ext_value_t& value)
{
_paramRequestTimer.stop();
_fact->setRawValue(_valueFromMessage(value.param_value, value.param_type), true);
_paramRequestReceived = true;
qCDebug(CameraIOLog) << QString("handleParamValue() %1 %2").arg(_fact->name()).arg(_fact->rawValueString());
}
//-----------------------------------------------------------------------------
QVariant
QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type)
{
//-- TODO: Even though we don't use anything larger than 32-bit, this should
// probably be updated.
QVariant var;
mavlink_param_union_t u;
memcpy(&u.param_float, value, sizeof(float));
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;
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();
} else {
//-- Request it again
qCDebug(CameraIOLog) << "Param request retry:" << _fact->name();
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_message_t msg;
mavlink_msg_param_ext_request_read_pack_chan(
mavlink->getSystemId(),
mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
_vehicle->id(),
_control->compID(),
_fact->name().toStdString().c_str(),
-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)
//-----------------------------------------------------------------------------
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 ();
private slots:
void _factChanged (QVariant value);
void _paramWriteTimeout ();
void _paramRequestTimeout();
private:
void _sendParameter ();
QVariant _valueFromMessage (const char* value, uint8_t param_type);
MAV_PARAM_TYPE _factTypeToMavType (FactMetaData::ValueType_t factType);
private:
QGCCameraControl* _control;
Fact* _fact;
Vehicle* _vehicle;
int _sentRetries;
int _requestRetries;
bool _paramRequestReceived;
mavlink_message_t _msg;
QTimer _paramWriteTimer;
QTimer _paramRequestTimer;
};
/*!
* @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)
, _cameraCount(0)
, _currentTask(0)
{
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)
{
switch (message.msgid) {
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 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];
_cameraCount = info.camera_count;
QGCCameraControl* pCamera = _vehicle->firmwarePlugin()->createCameraControl(&info, _vehicle, message.compid, this);
if(pCamera) {
_cameras.append(pCamera);
emit camerasChanged();
}
}
//-----------------------------------------------------------------------------
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
0, // Camera ID (0 for all, 1 for first, 2 for second, etc.)
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);
~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 ();
private slots:
void _vehicleReady (bool ready);
void _mavlinkMessageReceived (const mavlink_message_t& message);
signals:
void camerasChanged ();
void controllerSourceChanged ();
private:
QGCCameraControl* _findCamera (int id);
void _requestCameraInfo (int compID);
void _handleHeartbeat (const mavlink_message_t& message);
void _handleCameraInfo (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);
private:
Vehicle* _vehicle;
bool _vehicleReadyState;
int _cameraCount;
int _currentTask;
QmlObjectListModel _cameras;
QMap<int, bool> _cameraInfoRequested;
};
{
"definition": {
"version": 1,
"schema_version": 1,
"model": "SD II",
"manufacturer": "Super Dupper Industries",
"minFocalLength": 9.2,
"maxFocalLength": 9.2,
"sensorWidthPix": 4000,
"sensorHeightPix": 3000,
"sensorWidth": 12.4,
"sensorHeight": 9.3,
"capturePhoto": 1,
"captureVideo": 1,
"hasSeparateModes": 1,
"spotWsize": 0.1,
"spotHsize": 0.1,
"centerWSize": 0.1,
"centerHSize": 0.1
},
"settings":
[
{
"name": "CAM_MODE",
"shortDescription": "Camera Mode",
"type": "uint32",
"enumStrings": ["Photo" , "Video"],
"enumValues": [0, 1],
"defaultValue": 1
},
{
"name": "CAM_WBMODE",
"shortDescription": "White Balance Mode",
"type": "uint32",
"enumStrings": ["Auto" , "Sunny", "Cloudy", "Fluorescent", "Incandescent", "Sunset"],
"enumValues": [0, 1, 2, 3 , 4, 5],
"defaultValue": 0
},
{
"name": "CAM_EXPMODE",
"shortDescription": "Exposure Mode",
"type": "uint32",
"enumStrings": ["Auto" , "Manual", "Shutter Priority", "Aperture Priority"],
"enumValues": [0, 1, 2, 3],
"defaultValue": 0
},
{
"name": "CAM_APERTURE",
"shortDescription": "Aperture",
"type": "uint32",
"enumStrings": ["1.8", "2.0", "2.4", "2.8"],
"enumValues": [0, 1, 2, 3],
"defaultValue": 0
},
{
"name": "CAM_SHUTTERSPD",
"shortDescription": "Shutter Speed",
"type": "float",
"enumStrings": ["4", "3", "2", "1", "1/4", "1/8", "1/15", "1/30", "1/60", "1/125", "1/250", "1/500", "1/1000"],
"enumValues": [4.0, 3.0, 2.0, 1.0, 0.25, 0.125, 0.066666, 0.033333, 0.016666, 0.008, 0.004, 0.002, 0.001],
"defaultValue": 8
},
{
"name": "CAM_ISO",
"shortDescription": "ISO",
"type": "uint32",
"enumStrings": ["100", "200", "400", "800", "1600", "3200", "6400"],
"enumValues": [100, 200, 400, 800, 1600, 3200, 6400],
"defaultValue": 100
},
{
"name": "CAM_EV",
"shortDescription": "Exposure Compensation",
"type": "float",
"enumStrings": ["-2.0", "-1.5", "-1.0", "-0.5", "0", "+0.5", "+1.0", "+1.5", "+2.0"],
"enumValues": [-2.0, -1.5, -1.0, -0.5, 0, 0.5, 1.0, 1.5, 2.0],
"defaultValue": 0
},
{
"name": "CAM_VIDRES",
"shortDescription": "Video Resolution",
"type": "uint32",
"enumStrings": ["3840x2160 30P", "3840x2160 24P", "1920x1080 60P", "1920x1080 30P", "1920x1080 24P"],
"enumValues": [0, 1, 2, 3, 4],
"defaultValue": 0
},
{
"name": "CAM_VIDFMT",
"shortDescription": "Video Format",
"type": "uint32",
"enumStrings": ["h.264", "HEVC"],
"enumValues": [0, 1],
"defaultValue": 0
},
{
"name": "CAM_AUDIOREC",
"shortDescription": "Record Audio",
"type": "bool",
"defaultValue": 0
},
{
"name": "CAM_METERING",
"shortDescription": "Metering Mode",
"type": "uint32",
"enumStrings": ["Average", "Center", "Spot"],
"enumValues": [0, 1, 2],
"defaultValue": 0
},
{
"name": "CAM_SPOTX",
"shortDescription": "Spot Metering X Coordinate",
"type": "double",
"defaultValue": 0.45,
"min": 0,
"max": 0.9,
"control": false
},
{
"name": "CAM_SPOTY",
"shortDescription": "Spot Metering Y Coordinate",
"type": "double",
"defaultValue": 0.45,
"min": 0,
"max": 0.9,
"control": false
},
{
"name": "CAM_COLORMODE",
"shortDescription": "Color Mode",
"type": "uint32",
"enumStrings": ["Neutral", "Enhanced", "Unprocessed", "Night"],
"enumValues": [0, 1, 2, 4],
"defaultValue": 1
},
{
"name": "CAM_PHOTORES",
"shortDescription": "Photo Resolution",
"type": "uint32",
"enumStrings": ["Large", "Medium", "Small"],
"enumValues": [0, 1, 2],
"defaultValue": 0
},
{
"name": "CAM_PHOTOFMT",
"shortDescription": "Image Format",
"type": "uint32",
"enumStrings": ["Jpeg", "Raw", "Jpeg+Raw"],
"enumValues": [0, 1, 2],
"defaultValue": 0
},
{
"name": "CAM_PHOTOQUAL",
"shortDescription": "Image Quality",
"type": "uint32",
"enumStrings": ["Fine", "Medium", "Low"],
"enumValues": [0, 1, 2],
"defaultValue": 1
},
{
"name": "CAM_FLICKER",
"shortDescription": "Flickering Mode",
"type": "uint32",
"enumStrings": ["Auto", "50Hz", "60Hz"],
"enumValues": [0, 1, 2],
"defaultValue": 0
}
],
"videoStreams":
[
{
"VisibleLight":
{
"description": "Visible Light",
"url": "rtsp://192.168.92.1:1525/live",
"exclusive": 0,
"layer": 0
}
},
{
"ThermalImaging":
{
"description": "Thermal Imaging",
"url": "rtsp://192.168.92.1:4525/live",
"exclusive": 0,
"layer": 1
}
}
],
"settingRangeComment1": "Example: If CAM_MODE is set to 1, the valid enum range for CAM_ISO is 0-5",
"settingRangeComment2": "Example: If CAM_VIDRES is set to 0 and CAM_EXPMODE is 1-3 and CAM_MODE is 1, the valid enum range for CAM_SHUTTERSPD is 7-12",
"settingRange":
{
"CAM_MODE":
{
"options":
{
"1":
{
"CAM_ISO": [0, 1, 2, 3, 4, 5]
}
}
},
"CAM_VIDRES":
{
"conditions":
[
{
"parameter": "CAM_EXPMODE",
"operator": ">",
"value": 0
},
{
"parameter": "CAM_MODE",
"operator": "=",
"value": 1
}
],
"options":
{
"0":
{
"CAM_SHUTTERSPD": [7, 8, 9, 10, 11, 12]
},
"1":
{
"CAM_SHUTTERSPD": [7, 8, 9, 10, 11, 12]
},
"2":
{
"CAM_SHUTTERSPD": [8, 9, 10, 11, 12]
},
"3":
{
"CAM_SHUTTERSPD": [7, 8, 9, 10, 11, 12]
},
"4":
{
"CAM_SHUTTERSPD": [7, 8, 9, 10, 11, 12]
}
}
}
},
"settingExclusionComment": "Example: If CAM_EXPMODE is set to 0, CAM_ISO, CAM_SHUTTERSPD and CAM_APERTURE are excluded (not shown)",
"settingExclusions":
{
"CAM_EXPMODE":
{
"0": ["CAM_ISO", "CAM_SHUTTERSPD", "CAM_APERTURE"],
"1": ["CAM_EV"]
},
"CAM_MODE":
{
"0": ["CAM_VIDRES", "CAM_VIDFMT", "CAM_AUDIOREC"],
"1": ["CAM_PHOTOFMT", "CAM_PHOTOQUAL", "CAM_PHOTORES"]
},
"CAM_PHOTOFMT":
{
"1": ["CAM_PHOTOQUAL", "CAM_PHOTORES"]
}
},
"localization":
[
{
"locale": "pt_BR",
"strings":
{
"Exposure Mode": "Modo de Exposição",
"Auto": "Automático",
"Manual": "Manual",
"Shutter Priority": "Prioridade de Exposição",
"Aperture Priority": "Prioridade de Abertura",
"Aperture": "Abertura",
"Shutter Speed": "Velocidade",
"Exposure Compensation": "Compensação de Exposição",
"Video Resolution": "Resolução de Video"
}
}
]
}
\ No newline at end of file
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{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>
This diff is collapsed.
......@@ -64,6 +64,7 @@ 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)
/// Convert and validate value
/// @param convertOnly true: validate type conversion only, false: validate against meta data as well
......@@ -106,11 +107,12 @@ 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;
/// Returns the values as a string with full 18 digit precision if float/double.
QString rawValueStringFullPrecision(void) const;
void setRawValue (const QVariant& value);
void setRawValue (const QVariant& value, bool skipSignal = false);
void setCookedValue (const QVariant& value);
void setEnumIndex (int index);
void setEnumStringValue (const QString& value);
......@@ -132,12 +134,15 @@ public:
/// Sets the meta data associated with the Fact.
void setMetaData(FactMetaData* metaData);
FactMetaData* metaData() { return _metaData; }
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);
......
......@@ -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
......@@ -70,6 +70,7 @@ const char* FactMetaData::_unitsJsonKey = "units";
const char* FactMetaData::_defaultValueJsonKey = "defaultValue";
const char* FactMetaData::_minJsonKey = "min";
const char* FactMetaData::_maxJsonKey = "max";
const char* FactMetaData::_hasControlJsonKey = "control";
FactMetaData::FactMetaData(QObject* parent)
: QObject(parent)
......@@ -86,6 +87,7 @@ FactMetaData::FactMetaData(QObject* parent)
, _cookedTranslator(_defaultTranslator)
, _rebootRequired(false)
, _increment(std::numeric_limits<double>::quiet_NaN())
, _hasControl(true)
{
}
......@@ -105,6 +107,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
, _cookedTranslator(_defaultTranslator)
, _rebootRequired(false)
, _increment(std::numeric_limits<double>::quiet_NaN())
, _hasControl(true)
{
}
......@@ -115,6 +118,27 @@ FactMetaData::FactMetaData(const FactMetaData& other, QObject* parent)
*this = other;
}
FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent)
: QObject(parent)
, _type(type)
, _decimalPlaces(unknownDecimalPlaces)
, _rawDefaultValue(0)
, _defaultValueAvailable(false)
, _group("*Default Group")
, _rawMax(_maxForType())
, _maxIsDefaultForType(true)
, _rawMin(_minForType())
, _minIsDefaultForType(true)
, _name(name)
, _rawTranslator(_defaultTranslator)
, _cookedTranslator(_defaultTranslator)
, _rebootRequired(false)
, _increment(std::numeric_limits<double>::quiet_NaN())
, _hasControl(true)
{
}
const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
{
_decimalPlaces = other._decimalPlaces;
......@@ -139,6 +163,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
_cookedTranslator = other._cookedTranslator;
_rebootRequired = other._rebootRequired;
_increment = other._increment;
_hasControl = other._hasControl;
return *this;
}
......@@ -817,8 +842,8 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec
// Validate key types
QStringList keys;
QList<QJsonValue::Type> types;
keys << _nameJsonKey << _decimalPlacesJsonKey << _typeJsonKey << _shortDescriptionJsonKey << _longDescriptionJsonKey << _unitsJsonKey << _minJsonKey << _maxJsonKey;
types << QJsonValue::String << QJsonValue::Double << QJsonValue::String << QJsonValue::String << QJsonValue::String << QJsonValue::String << QJsonValue::Double << QJsonValue::Double;
keys << _nameJsonKey << _decimalPlacesJsonKey << _typeJsonKey << _shortDescriptionJsonKey << _longDescriptionJsonKey << _unitsJsonKey << _minJsonKey << _maxJsonKey << _hasControlJsonKey;
types << QJsonValue::String << QJsonValue::Double << QJsonValue::String << QJsonValue::String << QJsonValue::String << QJsonValue::String << QJsonValue::Double << QJsonValue::Double << QJsonValue::Bool;
if (!JsonHelper::validateKeyTypes(json, keys, types, errorString)) {
qWarning() << errorString;
return new FactMetaData(valueTypeUint32, metaDataParent);
......@@ -836,7 +861,7 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec
metaData->_name = json[_nameJsonKey].toString();
QStringList enumValues, enumStrings;
if (JsonHelper::parseEnum(json, enumStrings, enumValues, errorString)) {
if (JsonHelper::parseEnum(json, enumStrings, enumValues, errorString, metaData->name())) {
for (int i=0; i<enumValues.count(); i++) {
QVariant enumVariant;
QString errorString;
......@@ -876,6 +901,11 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec
metaData->convertAndValidateRaw(json[_maxJsonKey].toVariant(), true /* convertOnly */, typedValue, errorString);
metaData->setRawMax(typedValue);
}
if (json.contains(_hasControlJsonKey)) {
metaData->setHasControl(json[_hasControlJsonKey].toBool());
} else {
metaData->setHasControl(true);
}
return metaData;
}
......@@ -905,23 +935,27 @@ QMap<QString, FactMetaData*> FactMetaData::createMapFromJsonFile(const QString&
}
QJsonArray jsonArray = doc.array();
for (int i=0; i<jsonArray.count(); i++) {
QJsonValueRef jsonValue = jsonArray[i];
return createMapFromJsonArray(jsonArray, metaDataParent);
}
QMap<QString, FactMetaData*> FactMetaData::createMapFromJsonArray(const QJsonArray jsonArray, QObject* metaDataParent)
{
QMap<QString, FactMetaData*> metaDataMap;
for (int i=0; i<jsonArray.count(); i++) {
QJsonValue jsonValue = jsonArray.at(i);
if (!jsonValue.isObject()) {
qWarning() << QStringLiteral("JsonValue at index %1 not an object").arg(i);
continue;
}
QJsonObject jsonObject = jsonValue.toObject();
FactMetaData* metaData = createFromJsonObject(jsonObject, metaDataParent);
if (metaDataMap.contains(metaData->name())) {
qWarning() << QStringLiteral("Duplicate fact name:") << metaData->name();
delete metaData;
} else {
metaDataMap[metaData->name()] = metaData;
}
}
return metaDataMap;
}
......
......@@ -47,9 +47,11 @@ public:
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 +97,7 @@ 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; }
/// Amount to increment value when used in controls such as spin button or slider with detents.
/// NaN for no increment available.
......@@ -122,6 +125,7 @@ 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 setTranslators(Translator rawTranslator, Translator cookedTranslator);
......@@ -216,6 +220,7 @@ private:
Translator _cookedTranslator;
bool _rebootRequired;
double _increment;
bool _hasControl;
// Exact conversion constants
static const struct UnitConsts_s {
......@@ -247,6 +252,7 @@ private:
static const char* _defaultValueJsonKey;
static const char* _minJsonKey;
static const char* _maxJsonKey;
static const char* _hasControlJsonKey;
};
#endif
......@@ -517,3 +517,20 @@ bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitc
yawSupported = false;
return false;
}
QGCCameraManager* FirmwarePlugin::cameraManager(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
///
......@@ -267,8 +269,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);
/// Vehicle camera manager. Returns NULL if not supported.
virtual QGCCameraManager* cameraManager(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>
......@@ -34,7 +35,8 @@ PX4FirmwarePluginInstanceData::PX4FirmwarePluginInstanceData(QObject* parent)
}
PX4FirmwarePlugin::PX4FirmwarePlugin(void)
: _manualFlightMode(tr("Manual"))
: _cameraManager(NULL)
, _manualFlightMode(tr("Manual"))
, _acroFlightMode(tr("Acro"))
, _stabilizedFlightMode(tr("Stabilized"))
, _rattitudeFlightMode(tr("Rattitude"))
......@@ -124,6 +126,12 @@ PX4FirmwarePlugin::PX4FirmwarePlugin(void)
}
}
PX4FirmwarePlugin::~PX4FirmwarePlugin()
{
if(_cameraManager)
delete _cameraManager;
}
AutoPilotPlugin* PX4FirmwarePlugin::autopilotPlugin(Vehicle* vehicle)
{
return new PX4AutoPilotPlugin(vehicle, vehicle);
......@@ -545,3 +553,18 @@ bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicl
}
return true;
}
QGCCameraManager* PX4FirmwarePlugin::cameraManager(Vehicle* vehicle)
{
if(!_cameraManager) {
_cameraManager = new QGCCameraManager(vehicle);
}
return _cameraManager;
}
QGCCameraControl* PX4FirmwarePlugin::createCameraControl(const mavlink_camera_information_t* info, Vehicle *vehicle, int compID, QObject* parent)
{
return new QGCCameraControl(info, vehicle, compID, parent);
}
......@@ -25,6 +25,7 @@ class PX4FirmwarePlugin : public FirmwarePlugin
public:
PX4FirmwarePlugin(void);
~PX4FirmwarePlugin();
// Overrides from FirmwarePlugin
......@@ -68,6 +69,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* cameraManager (Vehicle* vehicle) override;
QGCCameraControl* createCameraControl (const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL) override;
protected:
typedef struct {
......@@ -80,6 +83,7 @@ protected:
} FlightModeInfo_t;
QList<FlightModeInfo_t> _flightModeInfoList;
QGCCameraManager* _cameraManager;
// Use these constants to set flight modes using setFlightMode method. Don't use hardcoded string names since the
// names may change.
......
......@@ -52,6 +52,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
......@@ -370,7 +372,7 @@ QGCView {
anchors.right: _flightVideo.right
height: ScreenTools.defaultFontPixelHeight * 2
width: height
visible: QGroundControl.videoManager.videoReceiver.videoRunning && QGroundControl.settingsManager.videoSettings.showRecControl.rawValue
visible: QGroundControl.videoManager.videoReceiver.videoRunning && QGroundControl.settingsManager.videoSettings.showRecControl.rawValue && !_isCamera
opacity: 0.75
Rectangle {
......
......@@ -8,23 +8,25 @@
****************************************************************************/
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 _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property double _ar: QGroundControl.settingsManager.videoSettings.aspectRatio.rawValue
property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0
property var _dynamicCameras: _activeVehicle ? _activeVehicle.dynamicCameras : null
property bool _connected: _activeVehicle ? !_activeVehicle.connectionLost : false
Rectangle {
id: noVideo
anchors.fill: parent
......@@ -90,4 +92,13 @@ Item {
}
}
}
//-- Camera Controller
Loader {
source: _dynamicCameras ? _dynamicCameras.controllerSource : ""
visible: !_mainIsMap && _dynamicCameras && _dynamicCameras.cameras.count && _connected
anchors.right: parent.right
anchors.rightMargin: ScreenTools.defaultFontPixelWidth
anchors.bottom: parent.bottom
anchors.bottomMargin: ScreenTools.defaultFontPixelHeight * 2
}
}
......@@ -119,7 +119,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()
......
......@@ -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);
......
......@@ -121,8 +121,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
MAV_FRAME_MISSION,
0, // camera id, all cameras
_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);
......
......@@ -77,8 +77,7 @@ void CameraSectionTest::init(void)
MAV_FRAME_MISSION,
0, // camera id = 0, all cameras
CameraSection::CameraModePhoto,
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
this);
......@@ -88,8 +87,7 @@ void CameraSectionTest::init(void)
MAV_FRAME_MISSION,
0, // camera id = 0, all cameras
CameraSection::CameraModeVideo,
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
this);
......@@ -670,13 +668,12 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
MAV_CMD_SET_CAMERA_MODE
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Camera mode (0: photo mode, 1: video mode)
Mission Param #3 Audio recording enabled (0: off 1: on)
Mission Param #4 Reserved (all remaining params)
Mission Param #3 Reserved (all remaining params)
*/
// Mode command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validCameraPhotoModeItem->missionItem());
invalidSimpleItem.missionItem().setParam3(1); // Audio should be NaN
invalidSimpleItem.missionItem().setParam3(1); // Param3 should be NaN
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
......
......@@ -983,12 +983,6 @@
"enumStrings": "Take photos,Record video",
"enumValues": "0,1",
"default": 0
},
"param3": {
"label": "Audio",
"enumStrings": "Recording disabled,Recording enabled",
"enumValues": "0,1",
"default": 0
}
},
{
......
......@@ -30,15 +30,15 @@ Rectangle {
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property var _cameraList: [ qsTr("Manual Grid (no camera specs)"), qsTr("Custom Camera Grid") ]
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
property var _vehicleCameraList: _vehicle.cameraList
property var _vehicleCameraList: _vehicle.staticCcameraList
readonly property int _gridTypeManual: 0
readonly property int _gridTypeCustomCamera: 1
readonly property int _gridTypeCamera: 2
Component.onCompleted: {
for (var i=0; i<_vehicle.cameraList.length; i++) {
_cameraList.push(_vehicle.cameraList[i].name)
for (var i=0; i<_vehicle.staticCcameraList.length; i++) {
_cameraList.push(_vehicle.staticCcameraList[i].name)
}
gridTypeCombo.model = _cameraList
if (missionItem.manualGrid.value) {
......
......@@ -80,6 +80,7 @@
#include "ParameterManager.h"
#include "SettingsManager.h"
#include "QGCCorePlugin.h"
#include "QGCCameraManager.h"
#ifndef NO_SERIAL_LINK
#include "SerialLink.h"
......@@ -344,9 +345,9 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<QGCPalette> ("QGroundControl.Palette", 1, 0, "QGCPalette");
qmlRegisterType<QGCMapPalette> ("QGroundControl.Palette", 1, 0, "QGCMapPalette");
qmlRegisterUncreatableType<CoordinateVector> ("QGroundControl", 1, 0, "CoordinateVector", "Reference only");
qmlRegisterUncreatableType<QmlObjectListModel> ("QGroundControl", 1, 0, "QmlObjectListModel", "Reference only");
qmlRegisterUncreatableType<MissionCommandTree> ("QGroundControl", 1, 0, "MissionCommandTree", "Reference only");
qmlRegisterUncreatableType<CoordinateVector> ("QGroundControl", 1, 0, "CoordinateVector", "Reference only");
qmlRegisterUncreatableType<QmlObjectListModel> ("QGroundControl", 1, 0, "QmlObjectListModel", "Reference only");
qmlRegisterUncreatableType<MissionCommandTree> ("QGroundControl", 1, 0, "MissionCommandTree", "Reference only");
qmlRegisterUncreatableType<AutoPilotPlugin> ("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", "Reference only");
qmlRegisterUncreatableType<VehicleComponent> ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Reference only");
......@@ -354,13 +355,15 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType<MissionItem> ("QGroundControl.Vehicle", 1, 0, "MissionItem", "Reference only");
qmlRegisterUncreatableType<MissionManager> ("QGroundControl.Vehicle", 1, 0, "MissionManager", "Reference only");
qmlRegisterUncreatableType<ParameterManager> ("QGroundControl.Vehicle", 1, 0, "ParameterManager", "Reference only");
qmlRegisterUncreatableType<QGCCameraManager> ("QGroundControl.Vehicle", 1, 0, "QGCCameraManager", "Reference only");
qmlRegisterUncreatableType<QGCCameraControl> ("QGroundControl.Vehicle", 1, 0, "QGCCameraControl", "Reference only");
qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only");
qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only");
qmlRegisterUncreatableType<QGCPositionManager> ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only");
qmlRegisterUncreatableType<QGCMapPolygon> ("QGroundControl.FlightMap", 1, 0, "QGCMapPolygon", "Reference only");
qmlRegisterUncreatableType<MissionController> ("QGroundControl.Controllers", 1, 0, "MissionController", "Reference only");
qmlRegisterUncreatableType<GeoFenceController> ("QGroundControl.Controllers", 1, 0, "GeoFenceController", "Reference only");
qmlRegisterUncreatableType<RallyPointController>("QGroundControl.Controllers", 1, 0, "RallyPointController", "Reference only");
qmlRegisterUncreatableType<RallyPointController>("QGroundControl.Controllers", 1, 0, "RallyPointController", "Reference only");
qmlRegisterType<ParameterEditorController> ("QGroundControl.Controllers", 1, 0, "ParameterEditorController");
qmlRegisterType<ESP8266ComponentController> ("QGroundControl.Controllers", 1, 0, "ESP8266ComponentController");
......
......@@ -114,7 +114,7 @@ Item {
minTouchPixels = defaultFontPixelHeight * 3
}
console.log(minTouchPixels / Screen.height)
//console.log(minTouchPixels / Screen.height)
toolbarHeight = isMobile ? minTouchPixels : defaultFontPixelHeight * 3
}
......
......@@ -71,7 +71,7 @@ Rectangle {
property bool dragActive: drag.active
property real _dragOffset: 1
Component.onCompleted: console.log(height, ScreenTools.minTouchPixels)
//Component.onCompleted: console.log(height, ScreenTools.minTouchPixels)
onPressed: {
mouse.x
......
......@@ -30,6 +30,7 @@
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
#include "QGCQGeoCoordinate.h"
#include "QGCCameraManager.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
......@@ -113,6 +114,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _telemetryRNoise(0)
, _vehicleCapabilitiesKnown(false)
, _supportsMissionItemInt(false)
, _cameras(NULL)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _initialPlanRequestComplete(false)
......@@ -225,6 +227,10 @@ Vehicle::Vehicle(LinkInterface* link,
_mapTrajectoryTimer.setInterval(_mapTrajectoryMsecsBetweenPoints);
connect(&_mapTrajectoryTimer, &QTimer::timeout, this, &Vehicle::_addNewMapTrajectoryPoint);
// Create camera manager instance
_cameras = _firmwarePlugin->cameraManager(this);
emit dynamicCamerasChanged();
}
// Disconnected Vehicle for offline editing
......@@ -271,6 +277,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _vehicleCapabilitiesKnown(true)
, _supportsMissionItemInt(false)
, _cameras(NULL)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _initialPlanRequestComplete(false)
......@@ -2576,7 +2583,7 @@ const QVariantList& Vehicle::toolBarIndicators()
return emptyList;
}
const QVariantList& Vehicle::cameraList(void) const
const QVariantList& Vehicle::staticCcameraList(void) const
{
if (_firmwarePlugin) {
return _firmwarePlugin->cameraList(this);
......
......@@ -38,6 +38,7 @@ class ParameterManager;
class JoystickManager;
class UASMessage;
class SettingsManager;
class QGCCameraManager;
Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
......@@ -310,7 +311,8 @@ public:
Q_PROPERTY(int telemetryLNoise READ telemetryLNoise NOTIFY telemetryLNoiseChanged)
Q_PROPERTY(int telemetryRNoise READ telemetryRNoise NOTIFY telemetryRNoiseChanged)
Q_PROPERTY(QVariantList toolBarIndicators READ toolBarIndicators CONSTANT)
Q_PROPERTY(QVariantList cameraList READ cameraList CONSTANT)
Q_PROPERTY(QVariantList staticCcameraList READ staticCcameraList CONSTANT)
Q_PROPERTY(QGCCameraManager* dynamicCameras READ dynamicCameras NOTIFY dynamicCamerasChanged)
/// true: Vehicle is flying, false: Vehicle is on ground
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged)
......@@ -670,8 +672,10 @@ public:
QString vehicleImageOutline () const;
QString vehicleImageCompass () const;
const QVariantList& toolBarIndicators ();
const QVariantList& cameraList (void) const;
const QVariantList& toolBarIndicators ();
const QVariantList& staticCcameraList (void) const;
QGCCameraManager* dynamicCameras () { return _cameras; }
bool supportsMissionItemInt(void) const { return _supportsMissionItemInt; }
......@@ -712,6 +716,7 @@ signals:
void defaultHoverSpeedChanged(double hoverSpeed);
void firmwareTypeChanged(void);
void vehicleTypeChanged(void);
void dynamicCamerasChanged();
void messagesReceivedChanged ();
void messagesSentChanged ();
......@@ -907,6 +912,8 @@ private:
bool _vehicleCapabilitiesKnown;
bool _supportsMissionItemInt;
QGCCameraManager* _cameras;
typedef struct {
int component;
MAV_CMD command;
......
......@@ -36,16 +36,16 @@ public:
QGCCorePlugin(QGCApplication* app, QGCToolbox* toolbox);
~QGCCorePlugin();
Q_PROPERTY(QVariantList settingsPages READ settingsPages NOTIFY settingsPagesChanged)
Q_PROPERTY(int defaultSettings READ defaultSettings CONSTANT)
Q_PROPERTY(QGCOptions* options READ options CONSTANT)
Q_PROPERTY(QVariantList settingsPages READ settingsPages NOTIFY settingsPagesChanged)
Q_PROPERTY(int defaultSettings READ defaultSettings CONSTANT)
Q_PROPERTY(QGCOptions* options READ options CONSTANT)
Q_PROPERTY(bool showTouchAreas READ showTouchAreas WRITE setShowTouchAreas NOTIFY showTouchAreasChanged)
Q_PROPERTY(bool showAdvancedUI READ showAdvancedUI WRITE setShowAdvancedUI NOTIFY showAdvancedUIChanged)
Q_PROPERTY(QString showAdvancedUIMessage READ showAdvancedUIMessage CONSTANT)
Q_PROPERTY(bool showTouchAreas READ showTouchAreas WRITE setShowTouchAreas NOTIFY showTouchAreasChanged)
Q_PROPERTY(bool showAdvancedUI READ showAdvancedUI WRITE setShowAdvancedUI NOTIFY showAdvancedUIChanged)
Q_PROPERTY(QString showAdvancedUIMessage READ showAdvancedUIMessage CONSTANT)
Q_PROPERTY(QString brandImageIndoor READ brandImageIndoor CONSTANT)
Q_PROPERTY(QString brandImageOutdoor READ brandImageOutdoor CONSTANT)
Q_PROPERTY(QString brandImageIndoor READ brandImageIndoor CONSTANT)
Q_PROPERTY(QString brandImageOutdoor READ brandImageOutdoor CONSTANT)
/// The list of settings under the Settings Menu
/// @return A list of QGCSettings
......
......@@ -246,8 +246,8 @@ Item {
currentPopUp.close()
}
if(oldIndicator !== dropItem) {
console.log(oldIndicator)
console.log(dropItem)
//console.log(oldIndicator)
//console.log(dropItem)
indicatorDropdown.centerX = centerX
indicatorDropdown.sourceComponent = dropItem
indicatorDropdown.visible = true
......
......@@ -333,13 +333,13 @@ Rectangle {
onActivated: {
saveItems();
QGroundControl.mavlinkLogManager.windSpeed = windItems.get(index).value
console.log('Set Wind: ' + windItems.get(index).value)
//console.log('Set Wind: ' + windItems.get(index).value)
}
Component.onCompleted: {
for(var i = 0; i < windItems.count; i++) {
if(windItems.get(i).value === QGroundControl.mavlinkLogManager.windSpeed) {
windCombo.currentIndex = i;
console.log('Wind: ' + windItems.get(i).value)
//console.log('Wind: ' + windItems.get(i).value)
break;
}
}
......@@ -370,13 +370,13 @@ Rectangle {
onActivated: {
saveItems();
QGroundControl.mavlinkLogManager.rating = ratingItems.get(index).value
console.log('Set Rating: ' + ratingItems.get(index).value)
//console.log('Set Rating: ' + ratingItems.get(index).value)
}
Component.onCompleted: {
for(var i = 0; i < ratingItems.count; i++) {
if(ratingItems.get(i).value === QGroundControl.mavlinkLogManager.rating) {
ratingCombo.currentIndex = i;
console.log('Rating: ' + ratingItems.get(i).value)
//console.log('Rating: ' + ratingItems.get(i).value)
break;
}
}
......
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