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)