Commit 2995ae9f authored by Gus Grubba's avatar Gus Grubba

Broadcast camera parameter loading done.

parent 2eeee80e
......@@ -117,9 +117,9 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
{
memcpy(&_info, &info, sizeof(mavlink_camera_information_t));
connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady);
if(_info.cam_definition_uri[0]) {
const char* url = (const char*)info->cam_definition_uri;
if(url[0] != 0) {
//-- Process camera definition file
const char* url = (const char*)info->cam_definition_uri;
_httpRequest(url);
} else {
_initWhenReady();
......@@ -1114,6 +1114,21 @@ QGCCameraControl::_dataReady(QByteArray data)
if(data.size()) {
qCDebug(CameraControlLog) << "Parsing camera definition";
_loadCameraDefinitionFile(data);
} else {
qCDebug(CameraControlLog) << "No camera definition";
}
_initWhenReady();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_paramDone()
{
foreach(QString param, _paramIO.keys()) {
if(!_paramIO[param]->paramDone()) {
return;
}
}
//-- All parameters loaded (or timed out)
paramLoadCompleted();
}
......@@ -60,6 +60,7 @@ public:
class QGCCameraControl : public FactGroup
{
Q_OBJECT
friend class QGCCameraParamIO;
public:
QGCCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL);
virtual ~QGCCameraControl();
......@@ -142,6 +143,7 @@ public:
virtual void handleParamValue (const mavlink_param_ext_value_t& value);
virtual void handleStorageInfo (const mavlink_storage_information_t& st);
virtual void factChanged (Fact* pFact);
virtual void paramLoadCompleted () {;}
signals:
void infoChanged ();
......@@ -165,6 +167,7 @@ private slots:
void _downloadFinished ();
void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
void _dataReady (QByteArray data);
void _paramDone ();
private:
bool _handleLocalization (QByteArray& bytes);
......
......@@ -19,6 +19,7 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
, _vehicle(vehicle)
, _sentRetries(0)
, _requestRetries(0)
, _done(false)
{
_paramWriteTimer.setSingleShot(true);
_paramWriteTimer.setInterval(3000);
......@@ -177,6 +178,10 @@ QGCCameraParamIO::handleParamValue(const mavlink_param_ext_value_t& value)
_paramRequestTimer.stop();
_fact->_containerSetRawValue(_valueFromMessage(value.param_value, value.param_type));
_paramRequestReceived = true;
if(!_done) {
_done = true;
_control->_paramDone();
}
qCDebug(CameraIOLog) << QString("handleParamValue() %1 %2").arg(_fact->name()).arg(_fact->rawValueString());
}
......@@ -224,6 +229,10 @@ QGCCameraParamIO::_paramRequestTimeout()
{
if(++_requestRetries > 3) {
qCWarning(CameraIOLog) << "No response for param request:" << _fact->name();
if(!_done) {
_done = true;
_control->_paramDone();
}
} else {
//-- Request it again
qCDebug(CameraIOLog) << "Param request retry:" << _fact->name();
......
......@@ -24,6 +24,7 @@ public:
void handleParamAck (const mavlink_param_ext_ack_t& ack);
void handleParamValue (const mavlink_param_ext_value_t& value);
void setParamRequest ();
bool paramDone () { return _done; }
private slots:
void _factChanged (QVariant value);
......@@ -46,5 +47,6 @@ private:
mavlink_message_t _msg;
QTimer _paramWriteTimer;
QTimer _paramRequestTimer;
bool _done;
};
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