Skip to content
QGCCameraControl.cc 76.9 KiB
Newer Older
/*!
 * @file
 *   @brief Camera Controller
 *   @author Gus Grubba <mavlink@grubba.com>
 *
 */

#include "QGCCameraControl.h"
#include "QGCCameraIO.h"
Gus Grubba's avatar
Gus Grubba committed
#include "SettingsManager.h"
#include "VideoManager.h"
#include "QGCMapEngine.h"
#include "QGCCameraManager.h"
Gus Grubba's avatar
Gus Grubba committed

Gus Grubba's avatar
Gus Grubba committed
#include <QDir>
Gus Grubba's avatar
Gus Grubba committed
#include <QStandardPaths>
#include <QDomDocument>
#include <QDomNodeList>

QGC_LOGGING_CATEGORY(CameraControlLog, "CameraControlLog")
QGC_LOGGING_CATEGORY(CameraControlLogVerbose, "CameraControlLogVerbose")

static const char* kCondition       = "condition";
static const char* kControl         = "control";
static const char* kDefault         = "default";
static const char* kDefnition       = "definition";
static const char* kDescription     = "description";
static const char* kExclusion       = "exclude";
static const char* kExclusions      = "exclusions";
static const char* kLocale          = "locale";
static const char* kLocalization    = "localization";
static const char* kMax             = "max";
static const char* kMin             = "min";
static const char* kModel           = "model";
static const char* kName            = "name";
static const char* kOption          = "option";
static const char* kOptions         = "options";
static const char* kOriginal        = "original";
static const char* kParameter       = "parameter";
static const char* kParameterrange  = "parameterrange";
static const char* kParameterranges = "parameterranges";
static const char* kParameters      = "parameters";
static const char* kReadOnly        = "readonly";
static const char* kWriteOnly       = "writeonly";
static const char* kRoption         = "roption";
static const char* kStep            = "step";
static const char* kDecimalPlaces   = "decimalPlaces";
static const char* kStrings         = "strings";
static const char* kTranslated      = "translated";
static const char* kUnit            = "unit";
static const char* kUpdate          = "update";
static const char* kUpdates         = "updates";
static const char* kValue           = "value";
static const char* kVendor          = "vendor";
static const char* kVersion         = "version";
Gus Grubba's avatar
Gus Grubba committed
static const char* kPhotoMode       = "PhotoMode";
static const char* kPhotoLapse      = "PhotoLapse";
static const char* kPhotoLapseCount = "PhotoLapseCount";

//-----------------------------------------------------------------------------
// Known Parameters
Gus Grubba's avatar
Gus Grubba committed
const char* QGCCameraControl::kCAM_EV          = "CAM_EV";
const char* QGCCameraControl::kCAM_EXPMODE     = "CAM_EXPMODE";
const char* QGCCameraControl::kCAM_ISO         = "CAM_ISO";
const char* QGCCameraControl::kCAM_SHUTTERSPD  = "CAM_SHUTTERSPD";
const char* QGCCameraControl::kCAM_APERTURE    = "CAM_APERTURE";
const char* QGCCameraControl::kCAM_WBMODE      = "CAM_WBMODE";
const char* QGCCameraControl::kCAM_MODE        = "CAM_MODE";
Gus Grubba's avatar
Gus Grubba committed
//-----------------------------------------------------------------------------
QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
    : QObject(parent)
    , param(param_)
    , value(value_)
    , exclusions(exclusions_)
{
}

//-----------------------------------------------------------------------------
QGCCameraOptionRange::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_)
{
}

//-----------------------------------------------------------------------------
static bool
read_attribute(QDomNode& node, const char* tagName, bool& target)
{
    QDomNamedNodeMap attrs = node.attributes();
    if(!attrs.count()) {
        return false;
    }
    QDomNode subNode = attrs.namedItem(tagName);
    if(subNode.isNull()) {
        return false;
    }
    target = subNode.nodeValue() != "0";
    return true;
}

//-----------------------------------------------------------------------------
static bool
read_attribute(QDomNode& node, const char* tagName, int& target)
{
    QDomNamedNodeMap attrs = node.attributes();
    if(!attrs.count()) {
        return false;
    }
    QDomNode subNode = attrs.namedItem(tagName);
    if(subNode.isNull()) {
        return false;
    }
    target = subNode.nodeValue().toInt();
    return true;
}

//-----------------------------------------------------------------------------
static bool
read_attribute(QDomNode& node, const char* tagName, QString& target)
{
    QDomNamedNodeMap attrs = node.attributes();
    if(!attrs.count()) {
        return false;
    }
    QDomNode subNode = attrs.namedItem(tagName);
    if(subNode.isNull()) {
        return false;
    }
    target = subNode.nodeValue();
    return true;
}

//-----------------------------------------------------------------------------
static bool
read_value(QDomNode& element, const char* tagName, QString& target)
{
    QDomElement de = element.firstChildElement(tagName);
    if(de.isNull()) {
        return false;
    }
    target = de.text();
    return true;
}

//-----------------------------------------------------------------------------
QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Vehicle* vehicle, int compID, QObject* parent)
    : FactGroup(0, parent)
    , _vehicle(vehicle)
    , _compID(compID)
{
    QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
    memcpy(&_info, info, sizeof(mavlink_camera_information_t));
Gus Grubba's avatar
Gus Grubba committed
    connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady);
Gus Grubba's avatar
Gus Grubba committed
    _vendor = QString(reinterpret_cast<const char*>(info->vendor_name));
    _modelName = QString(reinterpret_cast<const char*>(info->model_name));
    int ver = static_cast<int>(_info.cam_definition_version);
    _cacheFile.sprintf("%s/%s_%s_%03d.xml",
        qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(),
        _vendor.toStdString().c_str(),
        _modelName.toStdString().c_str(),
        ver);
Gus Grubba's avatar
Gus Grubba committed
    if(info->cam_definition_uri[0] != 0) {
Gus Grubba's avatar
Gus Grubba committed
        //-- Process camera definition file
Gus Grubba's avatar
Gus Grubba committed
        _handleDefinitionFile(info->cam_definition_uri);
Gus Grubba's avatar
Gus Grubba committed
    } else {
        _initWhenReady();
    }
Gus Grubba's avatar
Gus Grubba committed
    QSettings settings;
Gus Grubba's avatar
Gus Grubba committed
    _photoMode  = static_cast<PhotoMode>(settings.value(kPhotoMode, static_cast<int>(PHOTO_CAPTURE_SINGLE)).toInt());
Gus Grubba's avatar
Gus Grubba committed
    _photoLapse = settings.value(kPhotoLapse, 1.0).toDouble();
    _photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt();
    _recTimer.setSingleShot(false);
    _recTimer.setInterval(333);
    connect(&_recTimer, &QTimer::timeout, this, &QGCCameraControl::_recTimerHandler);
}

//-----------------------------------------------------------------------------
QGCCameraControl::~QGCCameraControl()
{
Gus Grubba's avatar
Gus Grubba committed
    if(_netManager) {
        delete _netManager;
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_initWhenReady()
{
    qCDebug(CameraControlLog) << "_initWhenReady()";
    if(isBasic()) {
        qCDebug(CameraControlLog) << "Basic, MAVLink only messages.";
        _requestCameraSettings();
Loading
Loading full blame...