Commit 94624aa3 authored by Gus Grubba's avatar Gus Grubba

Various fixes and optimizations.

parent 3065d1a9
......@@ -118,8 +118,16 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
, _cameraMode(CAMERA_MODE_UNDEFINED)
, _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED)
{
memcpy(&_info, &info, sizeof(mavlink_camera_information_t));
memcpy(&_info, info, sizeof(mavlink_camera_information_t));
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);
if(info->cam_definition_uri[0] != 0) {
//-- Process camera definition file
_handleDefinitionFile(info->cam_definition_uri);
......@@ -131,12 +139,6 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
//-----------------------------------------------------------------------------
QGCCameraControl::~QGCCameraControl()
{
//-- Clear param IO queue (if any)
foreach(QString paramName, _paramIO.keys()) {
if(_paramIO[paramName]) {
delete _paramIO[paramName];
}
}
if(_netManager) {
delete _netManager;
}
......@@ -458,11 +460,10 @@ QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
}
//-- If this is new, cache it
if(!_cached) {
QString cacheFile = _cacheFile();
qCDebug(CameraControlLog) << "Saving camera definition file" << cacheFile;
QFile file(cacheFile);
qCDebug(CameraControlLog) << "Saving camera definition file" << _cacheFile;
QFile file(_cacheFile);
if (!file.open(QIODevice::WriteOnly)) {
qWarning() << QString("Could not save cache file %1. Error: %2").arg(cacheFile).arg(file.errorString());
qWarning() << QString("Could not save cache file %1. Error: %2").arg(_cacheFile).arg(file.errorString());
} else {
file.write(originalData);
}
......@@ -1075,45 +1076,31 @@ QGCCameraControl::_loadNameValue(QDomNode option, const QString factName, FactMe
return true;
}
//-----------------------------------------------------------------------------
QString
QGCCameraControl::_cacheFile()
{
QString cacheFile;
cacheFile.sprintf("%s/%s_%s_%03d.xml",
qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(),
_info.vendor_name,
_info.model_name,
_info.cam_definition_version);
return cacheFile;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_handleDefinitionFile(const QString &url)
{
//-- First check and see if we have it cached
QString cacheFile = _cacheFile();
QFile xmlFile(cacheFile);
QFile xmlFile(_cacheFile);
if (!xmlFile.exists()) {
qCDebug(CameraControlLog) << "No camera definition file cached";
_httpRequest(url);
return;
}
if (!xmlFile.open(QIODevice::ReadOnly)) {
qWarning() << "Could not read cached camera definition file:" << cacheFile;
qWarning() << "Could not read cached camera definition file:" << _cacheFile;
_httpRequest(url);
return;
}
QByteArray bytes = xmlFile.readAll();
QDomDocument doc;
if(!doc.setContent(bytes, false)) {
qWarning() << "Could not parse cached camera definition file:" << cacheFile;
qWarning() << "Could not parse cached camera definition file:" << _cacheFile;
_httpRequest(url);
return;
}
//-- We have it
qCDebug(CameraControlLog) << "Using cached camera definition file:" << cacheFile;
qCDebug(CameraControlLog) << "Using cached camera definition file:" << _cacheFile;
_cached = true;
emit dataReady(bytes);
}
......
......@@ -187,7 +187,6 @@ private:
QStringList _loadExclusions (QDomNode option);
QString _getParamName (const char* param_id);
QString _cacheFile ();
protected:
Vehicle* _vehicle;
......@@ -200,6 +199,7 @@ protected:
QNetworkAccessManager* _netManager;
QString _modelName;
QString _vendor;
QString _cacheFile;
CameraMode _cameraMode;
VideoStatus _video_status;
QStringList _activeSettings;
......
......@@ -22,13 +22,42 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
, _done(false)
{
_paramWriteTimer.setSingleShot(true);
_paramWriteTimer.setInterval(3000);
_paramWriteTimer.setInterval(1000);
_paramRequestTimer.setSingleShot(true);
_paramRequestTimer.setInterval(3000);
_paramRequestTimer.setInterval(2000);
connect(&_paramWriteTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout);
connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout);
connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged);
connect(_fact, &Fact::_containerRawValueChanged, this, &QGCCameraParamIO::_containerRawValueChanged);
_pMavlink = qgcApp()->toolbox()->mavlinkProtocol();
//-- TODO: Even though we don't use anything larger than 32-bit, this should
// probably be updated.
switch (_fact->type()) {
case FactMetaData::valueTypeUint8:
_mavParamType = MAV_PARAM_TYPE_UINT8;
break;
case FactMetaData::valueTypeInt8:
_mavParamType = MAV_PARAM_TYPE_INT8;
break;
case FactMetaData::valueTypeUint16:
_mavParamType = MAV_PARAM_TYPE_UINT16;
break;
case FactMetaData::valueTypeInt16:
_mavParamType = MAV_PARAM_TYPE_INT16;
break;
case FactMetaData::valueTypeUint32:
_mavParamType = MAV_PARAM_TYPE_UINT32;
break;
case FactMetaData::valueTypeFloat:
_mavParamType = MAV_PARAM_TYPE_REAL32;
break;
default:
qWarning() << "Unsupported fact type" << _fact->type();
// Fall through
case FactMetaData::valueTypeInt32:
_mavParamType = MAV_PARAM_TYPE_INT32;
break;
}
}
//-----------------------------------------------------------------------------
......@@ -45,7 +74,7 @@ void
QGCCameraParamIO::_factChanged(QVariant value)
{
Q_UNUSED(value);
qCDebug(CameraIOLog) << "UI Fact" << _fact->name() << "changed";
qCDebug(CameraControlLog) << "UI Fact" << _fact->name() << "changed";
//-- TODO: Do we really want to update the UI now or only when we receive the ACK?
_control->factChanged(_fact);
}
......@@ -55,7 +84,8 @@ void
QGCCameraParamIO::_containerRawValueChanged(const QVariant value)
{
Q_UNUSED(value);
qCDebug(CameraIOLog) << "Send Fact" << _fact->name() << "changed";
qCDebug(CameraControlLog) << "Send Fact" << _fact->name();
_sentRetries = 0;
_sendParameter();
}
......@@ -63,12 +93,14 @@ QGCCameraParamIO::_containerRawValueChanged(const QVariant value)
void
QGCCameraParamIO::_sendParameter()
{
qDebug() << "_sendParameter()" << _fact->name();
//-- 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));
mavlink_message_t msg;
memset(&p, 0, sizeof(mavlink_param_ext_set_t));
FactMetaData::ValueType_t factType = _fact->type();
p.param_type = _factTypeToMavType(factType);
p.param_type = _mavParamType;
switch (factType) {
case FactMetaData::valueTypeUint8:
union_value.param_uint8 = (uint8_t)_fact->rawValue().toUInt();
......@@ -95,18 +127,19 @@ QGCCameraParamIO::_sendParameter()
union_value.param_int32 = (int32_t)_fact->rawValue().toInt();
break;
}
memcpy(&p.param_value, &union_value.param_float, sizeof(float));
memcpy(&p.param_value[0], &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);
strncpy(p.param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_ID_LEN);
mavlink_msg_param_ext_set_encode_chan(
_pMavlink->getSystemId(),
_pMavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
&p);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
_paramWriteTimer.start();
qDebug() << "_sendParameter()" << _fact->name() << "sent";
}
//-----------------------------------------------------------------------------
......@@ -118,47 +151,22 @@ QGCCameraParamIO::_paramWriteTimeout()
} else {
//-- Send it again
qCDebug(CameraIOLog) << "Param set retry:" << _fact->name();
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), _msg);
_sendParameter();
_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->_containerSetRawValue(_valueFromMessage(ack.param_value, ack.param_type));
}
if(ack.param_result == PARAM_ACK_IN_PROGRESS) {
QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
if(_fact->rawValue() != val) {
_fact->_containerSetRawValue(val);
}
} else 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();
......@@ -168,6 +176,11 @@ QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack)
} else if(ack.param_result == PARAM_ACK_VALUE_UNSUPPORTED) {
qCWarning(CameraIOLog) << "Param set unsuported:" << _fact->name();
}
//-- If UI changed and value was not set, restore UI
QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
if(_fact->rawValue() != val) {
_fact->_containerSetRawValue(val);
}
}
}
......@@ -236,11 +249,10 @@ QGCCameraParamIO::_paramRequestTimeout()
} 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(),
_pMavlink->getSystemId(),
_pMavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
_vehicle->id(),
......
......@@ -21,21 +21,21 @@ class QGCCameraParamIO : public QObject
public:
QGCCameraParamIO(QGCCameraControl* control, Fact* fact, Vehicle* vehicle);
void handleParamAck (const mavlink_param_ext_ack_t& ack);
void handleParamValue (const mavlink_param_ext_value_t& value);
void setParamRequest ();
bool paramDone () { return _done; }
void handleParamAck (const mavlink_param_ext_ack_t& ack);
void handleParamValue (const mavlink_param_ext_value_t& value);
void setParamRequest ();
void sendChange ();
bool paramDone () { return _done; }
private slots:
void _factChanged (QVariant value);
void _containerRawValueChanged(const QVariant value);
void _paramWriteTimeout ();
void _paramRequestTimeout();
void _paramWriteTimeout ();
void _paramRequestTimeout ();
void _factChanged (QVariant value);
void _containerRawValueChanged (const QVariant value);
private:
void _sendParameter ();
QVariant _valueFromMessage (const char* value, uint8_t param_type);
MAV_PARAM_TYPE _factTypeToMavType (FactMetaData::ValueType_t factType);
void _sendParameter ();
QVariant _valueFromMessage (const char* value, uint8_t param_type);
private:
QGCCameraControl* _control;
......@@ -44,9 +44,10 @@ private:
int _sentRetries;
int _requestRetries;
bool _paramRequestReceived;
mavlink_message_t _msg;
QTimer _paramWriteTimer;
QTimer _paramRequestTimer;
bool _done;
MAV_PARAM_TYPE _mavParamType;
MAVLinkProtocol* _pMavlink;
};
......@@ -392,6 +392,7 @@ const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle)
false,
0,
this);
_cameraList.append(QVariant::fromValue(metaData));
metaData = new CameraMetaData(tr("Canon EOS-M 22mm"),
22.3,
......
......@@ -369,6 +369,9 @@ void ScrollZoomer::layoutScrollBars(const QRect &rect)
hScrollBar->setGeometry(x, y, w, hdim);
}
if ( vScrollBar && vScrollBar->isVisible() ) {
//-- TODO: What is this "pos"? It only gets
// assigned but never used within this
// scope.
int pos = yAxis();
if ( vScrollBarPosition() == OppositeToScale )
pos = oppositeAxis(pos);
......
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