Skip to content
QGCCameraControl.cc 57.1 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"

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* 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";

//-----------------------------------------------------------------------------
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)
    , _version(0)
Gus Grubba's avatar
Gus Grubba committed
    , _cached(false)
Gus Grubba's avatar
Gus Grubba committed
    , _storageFree(0)
    , _storageTotal(0)
    , _netManager(NULL)
    , _cameraMode(CAM_MODE_UNDEFINED)
Gus Grubba's avatar
Gus Grubba committed
    , _photoMode(PHOTO_CAPTURE_SINGLE)
    , _photoLapse(1.0)
    , _photoLapseCount(0)
Gus Grubba's avatar
Gus Grubba committed
    , _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED)
    , _photo_status(PHOTO_CAPTURE_STATUS_UNDEFINED)
    , _storageInfoRetries(0)
    , _captureInfoRetries(0)
    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);
    _vendor = QString((const char*)(void*)&info->vendor_name[0]);
    _modelName = QString((const char*)(void*)&info->model_name[0]);
    int ver = (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;
    _photoMode = (PhotoMode)settings.value(kPhotoMode, (int)PHOTO_CAPTURE_SINGLE).toInt();
    _photoLapse = settings.value(kPhotoLapse, 1.0).toDouble();
    _photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt();
}

//-----------------------------------------------------------------------------
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();
    } else {
        _requestAllParameters();
        //-- Give some time to load the parameters before going after the camera settings
        QTimer::singleShot(2000, this, &QGCCameraControl::_requestCameraSettings);
    }
    connect(_vehicle, &Vehicle::mavCommandResult, this, &QGCCameraControl::_mavCommandResult);
    connect(&_captureStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_requestCaptureStatus);
    _captureStatusTimer.setSingleShot(true);
    QTimer::singleShot(2500, this, &QGCCameraControl::_requestStorageInfo);
    _captureStatusTimer.start(2750);
    emit infoChanged();
    if(_netManager) {
        delete _netManager;
        _netManager = NULL;
    }
}

//-----------------------------------------------------------------------------
QString
QGCCameraControl::firmwareVersion()
{
    int major = (_info.firmware_version >> 24) & 0xFF;
    int minor = (_info.firmware_version >> 16) & 0xFF;
Loading
Loading full blame...