diff --git a/libs/eigen/Eigen/src/Core/BandMatrix.h b/libs/eigen/Eigen/src/Core/BandMatrix.h index dda8efba3671ac46f1875f3f9d4679617e5b106d..e6922b50f5f6d3c40b55e0179958dc09c5e9ae16 100644 --- a/libs/eigen/Eigen/src/Core/BandMatrix.h +++ b/libs/eigen/Eigen/src/Core/BandMatrix.h @@ -285,6 +285,7 @@ class BandMatrixWrapper : public BandMatrixBase 100)) { + qDebug() << "linkErrorCount too high: disconnecting!"; linkErrorCount = 0; + communicationError("SerialLink", tr("Disconnecting on too many link errors")); disconnect(); } @@ -210,7 +212,7 @@ void SerialLink::run() } } else { linkErrorCount++; - qDebug() << "Wait read response timeout" << QTime::currentTime().toString(); + //qDebug() << "Wait read response timeout" << QTime::currentTime().toString(); } if (bytes != m_bytesRead) // i.e things are good and data is being read. @@ -370,6 +372,8 @@ bool SerialLink::disconnect() return true; } + m_transmitBuffer.clear(); //clear the output buffer to avoid sending garbage at next connect + qDebug() << "already disconnected"; return true; } diff --git a/src/uas/QGCUASParamManager.cc b/src/uas/QGCUASParamManager.cc index 6e137b6329d77c5c902c3e89f9e8550649e94042..569daebb671d19db3f7b0f7eed0d556e6c366405 100644 --- a/src/uas/QGCUASParamManager.cc +++ b/src/uas/QGCUASParamManager.cc @@ -1,26 +1,113 @@ #include "QGCUASParamManager.h" + +#include > +#include + #include "UASInterface.h" +#include "UASParameterCommsMgr.h" QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) : QWidget(parent), mav(uas), - transmissionListMode(false), - transmissionActive(false), - transmissionTimeout(0), - retransmissionTimeout(350), - rewriteTimeout(500), - retransmissionBurstRequestSize(5) + paramDataModel(NULL), + paramCommsMgr(NULL) +{ + paramDataModel = uas->getParamDataModel(); + paramCommsMgr = uas->getParamCommsMgr(); + mav->setParamManager(this); + + // Load default values and tooltips + loadParamMetaInfoCSV(); +} + + +bool QGCUASParamManager::getParameterValue(int component, const QString& parameter, QVariant& value) const +{ + return paramDataModel->getOnboardParamValue(component,parameter,value); +} + + +void QGCUASParamManager::requestParameterUpdate(int component, const QString& parameter) { - uas->setParamManager(this); + if (mav) { + paramCommsMgr->requestParameterUpdate(component,parameter); + } } + /** - * The .. signal is emitted + * Send a request to deliver the list of onboard parameters + * to the MAV. */ -void QGCUASParamManager::requestParameterListUpdate(int component) +void QGCUASParamManager::requestParameterList() +{ + if (!mav) { + return; + } + //paramDataModel->forgetAllOnboardParameters(); //TODO really?? + setParameterStatusMsg(tr("Requested param list.. waiting")); + paramCommsMgr->requestParameterList(); +} + + +void QGCUASParamManager::setParameterStatusMsg(const QString& msg) { - Q_UNUSED(component); + qDebug() << "parameterStatusMsg: " << msg; + parameterStatusMsg = msg; } +void QGCUASParamManager::setParamDescriptions(const QMap& paramInfo) { + paramDataModel->setParamDescriptions(paramInfo); +} + + +void QGCUASParamManager::setParameter(int compId, QString paramName, QVariant value) +{ + //paramCommsMgr->setParameter(compId,paramName,value); + paramDataModel->updatePendingParamWithValue(compId,paramName,value); +} +void QGCUASParamManager::sendPendingParameters() +{ + paramCommsMgr->sendPendingParameters(); +} + +void QGCUASParamManager::setPendingParam(int compId, QString& paramName, const QVariant& value) +{ + paramDataModel->updatePendingParamWithValue(compId,paramName,value); +} + + + +void QGCUASParamManager::loadParamMetaInfoCSV() +{ + // Load default values and tooltips + QString autopilot(mav->getAutopilotTypeName()); + + QDir appDir = QApplication::applicationDirPath(); + appDir.cd("files"); + QString fileName = QString("%1/%2/parameter_tooltips/tooltips.txt").arg(appDir.canonicalPath()).arg(autopilot.toLower()); + QFile paramMetaFile(fileName); + + qDebug() << "loadParamMetaInfoCSV for autopilot: " << autopilot << " from file: " << fileName; + + if (!paramMetaFile.open(QIODevice::ReadOnly | QIODevice::Text)) { + qWarning() << "loadParamMetaInfoCSV couldn't open:" << fileName; + return; + } + + QTextStream in(¶mMetaFile); + paramDataModel->loadParamMetaInfoFromStream(in); + paramMetaFile.close(); + +} + +/** + * @return The MAV of this mgr. Unless the MAV object has been destroyed, this + * pointer is never zero. + */ +UASInterface* QGCUASParamManager::getUAS() +{ + return mav; +} diff --git a/src/uas/QGCUASParamManager.h b/src/uas/QGCUASParamManager.h index 69dee9eb444e6253cee3f3cc80b718b6ea1c938c..6c910509cd7f74375ae335731d4894d02ff9a58c 100644 --- a/src/uas/QGCUASParamManager.h +++ b/src/uas/QGCUASParamManager.h @@ -6,7 +6,10 @@ #include #include +//forward declarations class UASInterface; +class UASParameterCommsMgr; +class UASParameterDataModel; class QGCUASParamManager : public QWidget { @@ -14,68 +17,56 @@ class QGCUASParamManager : public QWidget public: QGCUASParamManager(UASInterface* uas, QWidget *parent = 0); - QList getParameterNames(int component) const { - return parameters.value(component)->keys(); - } - QList getParameterValues(int component) const { - return parameters.value(component)->values(); - } - bool getParameterValue(int component, const QString& parameter, QVariant& value) const { - if (!parameters.contains(component)) - { - return false; - } - - if (!parameters.value(component)->contains(parameter)) - { - return false; - } - - value = parameters.value(component)->value(parameter); - - return true; - } - - virtual bool isParamMinKnown(const QString& param) = 0; - virtual bool isParamMaxKnown(const QString& param) = 0; - virtual bool isParamDefaultKnown(const QString& param) = 0; - virtual double getParamMin(const QString& param) = 0; - virtual double getParamMax(const QString& param) = 0; - virtual double getParamDefault(const QString& param) = 0; - virtual QString getParamInfo(const QString& param) = 0; - virtual void setParamInfo(const QMap& param) = 0; - - /** @brief Request an update for the parameter list */ - void requestParameterListUpdate(int component = 0); - /** @brief Request an update for this specific parameter */ - virtual void requestParameterUpdate(int component, const QString& parameter) = 0; + /** @brief Get the known, confirmed value of a parameter */ + virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const; + + /** @brief Provide tooltips / user-visible descriptions for parameters */ + virtual void setParamDescriptions(const QMap& paramDescs); + + /** @brief Get the UAS of this widget + * @return The MAV of this mgr. Unless the MAV object has been destroyed, this is never null. + */ + UASInterface* getUAS(); + +protected: + //TODO decouple this UI message display further? + virtual void setParameterStatusMsg(const QString& msg); + /** @brief Load parameter meta information from appropriate CSV file */ + virtual void loadParamMetaInfoCSV(); + signals: void parameterChanged(int component, QString parameter, QVariant value); void parameterChanged(int component, int parameterIndex, QVariant value); - void parameterListUpToDate(int component); public slots: - /** @brief Write one parameter to the MAV */ - virtual void setParameter(int component, QString parameterName, QVariant value) = 0; + /** @brief Send one parameter to the MAV: changes value in transient memory of MAV */ + virtual void setParameter(int component, QString parameterName, QVariant value); + + /** @brief Send all pending parameters to the MAV, for storage in transient (RAM) memory */ + virtual void sendPendingParameters(); + /** @brief Request list of parameters from MAV */ - virtual void requestParameterList() = 0; + virtual void requestParameterList(); + + virtual void setPendingParam(int componentId, QString& key, const QVariant& value); + + /** @brief Request a single parameter by name from the MAV */ + virtual void requestParameterUpdate(int component, const QString& parameter); + + virtual void handleParameterUpdate(int component, const QString& parameterName, QVariant value) = 0; + virtual void handleParameterListUpToDate() = 0; + protected: - UASInterface* mav; ///< The MAV this widget is controlling - QMap* > changedValues; ///< Changed values - QMap* > parameters; ///< All parameters - QVector received; ///< Successfully received parameters - QMap* > transmissionMissingPackets; ///< Missing packets - QMap* > transmissionMissingWriteAckPackets; ///< Missing write ACK packets - bool transmissionListMode; ///< Currently requesting list - QMap transmissionListSizeKnown; ///< List size initialized? - bool transmissionActive; ///< Missing packets, working on list? - quint64 transmissionTimeout; ///< Timeout - QTimer retransmissionTimer; ///< Timer handling parameter retransmission - int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds - int rewriteTimeout; ///< Write request timeout, in milliseconds - int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst + + // Parameter data model + UASInterface* mav; ///< The MAV this manager is controlling + UASParameterDataModel* paramDataModel;///< Shared data model of parameters + UASParameterCommsMgr* paramCommsMgr; ///< Shared comms mgr for parameters + + // Status + QString parameterStatusMsg; }; diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 8dd3395506316429e104ebd765506b31fefa1757..d21f55343d70cfab0491b3bc8209ab9278bde60f 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -26,6 +26,7 @@ #include "QGCMAVLink.h" #include "LinkManager.h" #include "SerialLink.h" +#include "UASParameterCommsMgr.h" #include #ifdef QGC_PROTOBUF_ENABLED @@ -131,6 +132,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), paramsOnceRequested(false), paramManager(NULL), + paramDataModel(NULL), + paramCommsMgr(NULL), simulation(0), @@ -151,6 +154,11 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), componentMulti[i] = false; } + paramDataModel = new UASParameterDataModel(this); + paramDataModel->setUASID(this->getUASID()); + + paramCommsMgr = new UASParameterCommsMgr(this,this); + // Store a list of available actions for this UAS. // Basically everything exposted as a SLOT with no return value or arguments. @@ -226,6 +234,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), */ UAS::~UAS() { + delete paramCommsMgr; + delete paramDataModel; writeSettings(); delete links; delete statusTimeout; @@ -1991,7 +2001,7 @@ void UAS::sendMessage(mavlink_message_t message) if (LinkManager::instance()->getLinks().contains(link)) { sendMessage(link, message); - qDebug() << "SENT MESSAGE!"; + qDebug() << "SENT MESSAGE id" << message.msgid << "component" << message.compid; } else { @@ -2021,8 +2031,10 @@ void UAS::forwardMessage(mavlink_message_t message) { if(serial != links->at(i)) { - qDebug()<<"Antenna tracking: Forwarding Over link: "<getName()<<" "<isConnected()) { + qDebug()<<"Antenna tracking: Forwarding Over link: "<getName()<<" "<getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL); sendMessage(msg); - qDebug() << __FILE__ << ":" << __LINE__ << "LOADING PARAM LIST"; + + QDateTime time = QDateTime::currentDateTime(); + qDebug() << __FILE__ << ":" << __LINE__ << time.toString() << "LOADING PARAM LIST"; } void UAS::writeParametersToStorage() @@ -2533,7 +2547,7 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v // TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling. if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - switch (value.type()) + switch ((int)value.type()) { case QVariant::Char: union_value.param_float = (unsigned char)value.toChar().toAscii(); @@ -2558,7 +2572,7 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v } else { - switch (value.type()) + switch ((int)value.type()) { case QVariant::Char: union_value.param_int8 = (unsigned char)value.toChar().toAscii(); diff --git a/src/uas/UAS.h b/src/uas/UAS.h index b1c027bd1f55cb9039a0c0351322702ff0237d38..5acd2c9ef495b7fe2ff7529ea8a94a10a95ced4b 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -41,6 +41,7 @@ This file is part of the QGROUNDCONTROL project #include "QGCJSBSimLink.h" #include "QGCXPlaneLink.h" + /** * @brief A generic MAVLINK-connected MAV/UAV * @@ -492,6 +493,8 @@ protected: //COMMENTS FOR TEST UNIT QMap* > parameters; ///< All parameters bool paramsOnceRequested; ///< If the parameter list has been read at least once QGCUASParamManager* paramManager; ///< Parameter manager class + UASParameterDataModel* paramDataModel; ///< The parameter data model for this UAS + UASParameterCommsMgr* paramCommsMgr; /// SIMULATION QGCHilLink* simulation; ///< Hardware in the loop simulation link @@ -519,10 +522,24 @@ public: QGCUASParamManager* getParamManager() const { return paramManager; } + + /** @brief Get reference to the parameter data model (same one shared with the parameter manager) **/ + UASParameterDataModel* getParamDataModel() { + return paramDataModel; + } + + UASParameterCommsMgr* getParamCommsMgr() { + return paramCommsMgr; + } + + /** @brief Get the HIL simulation */ QGCHilLink* getHILSimulation() const { return simulation; } + + + // TODO Will be removed /** @brief Set reference to the param manager **/ void setParamManager(QGCUASParamManager* manager) { @@ -949,6 +966,7 @@ protected: quint64 lastSendTimeSensors; QList actions; ///< A list of actions that this UAS can perform. + protected slots: /** @brief Write settings to disk */ void writeSettings(); diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 37382e3eb4197f0e077298bace9698f52549d6a1..6e6fe2fb3396f5e1cea793d98175c42d942f671f 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -40,6 +40,7 @@ This file is part of the QGROUNDCONTROL project #include "LinkInterface.h" #include "ProtocolInterface.h" +#include "UASParameterDataModel.h" #include "UASWaypointManager.h" #include "QGCUASParamManager.h" #include "RadioCalibration/RadioCalibrationData.h" @@ -152,8 +153,16 @@ public: /** @brief Get reference to the waypoint manager **/ virtual UASWaypointManager* getWaypointManager(void) = 0; + + /** @brief Access the parameter data model for this UAS (sans widget). This is the same parameter data model used by the parameter manager. **/ + virtual UASParameterDataModel* getParamDataModel() = 0; + + + virtual UASParameterCommsMgr* getParamCommsMgr() = 0; + /** @brief Get reference to the param manager **/ virtual QGCUASParamManager* getParamManager() const = 0; + // TODO Will be removed /** @brief Set reference to the param manager **/ virtual void setParamManager(QGCUASParamManager* manager) = 0; diff --git a/src/uas/UASManager.cc b/src/uas/UASManager.cc index 072c7aea7a7a317b6ec19854a88b47615d20d80d..8ee92242db1ba16a988521e72f80416b33d8a940 100644 --- a/src/uas/UASManager.cc +++ b/src/uas/UASManager.cc @@ -280,6 +280,7 @@ void UASManager::addUAS(UASInterface* uas) // Only execute if there is no UAS at this index if (!systems.contains(uas)) { + qDebug() << "Add new UAS: " << uas->getUASID(); systems.append(uas); // Set home position on UAV if set in UI // - this is done on a per-UAV basis diff --git a/src/uas/UASParameterCommsMgr.cc b/src/uas/UASParameterCommsMgr.cc new file mode 100644 index 0000000000000000000000000000000000000000..db741861145ef4c55b40e4901a71ffdbfe81a4ce --- /dev/null +++ b/src/uas/UASParameterCommsMgr.cc @@ -0,0 +1,615 @@ +#include "UASParameterCommsMgr.h" + +#include + +#include "QGCUASParamManager.h" +#include "UASInterface.h" + +#define RC_CAL_CHAN_MAX 8 + +UASParameterCommsMgr::UASParameterCommsMgr(QObject *parent, UASInterface *uas) : + QObject(parent), + mav(uas), + paramDataModel(NULL), + transmissionListMode(false), + transmissionActive(false), + transmissionTimeout(0), + retransmissionTimeout(1000), + rewriteTimeout(1000), + retransmissionBurstRequestSize(5) +{ + paramDataModel = mav->getParamDataModel(); + loadParamCommsSettings(); + + + //Requesting parameters one-by-one from mav + connect(this, SIGNAL(parameterUpdateRequestedById(int,int)), + mav, SLOT(requestParameter(int,int))); + + // Sending params to the UAS + connect(this, SIGNAL(commitPendingParameter(int,QString,QVariant)), + mav, SLOT(setParameter(int,QString,QVariant))); + + // Received parameter updates from UAS + connect(mav, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), + this, SLOT(receivedParameterUpdate(int,int,int,int,QString,QVariant))); + + //connecto retransmissionTimer + connect(&retransmissionTimer, SIGNAL(timeout()), + this, SLOT(retransmissionGuardTick())); + +} + + + +void UASParameterCommsMgr::loadParamCommsSettings() +{ + QSettings settings; + settings.beginGroup("QGC_MAVLINK_PROTOCOL"); + bool ok; + int val = settings.value("PARAMETER_RETRANSMISSION_TIMEOUT", retransmissionTimeout).toInt(&ok); + if (ok) { + retransmissionTimeout = val; + qDebug() << "retransmissionTimeout" << retransmissionTimeout; + } + val = settings.value("PARAMETER_REWRITE_TIMEOUT", rewriteTimeout).toInt(&ok); + if (ok) { + rewriteTimeout = val; + } + settings.endGroup(); +} + + + +/** + * Send a request to deliver the list of onboard parameters + * from the MAV. + */ +void UASParameterCommsMgr::requestParameterList() +{ + if (!mav) { + return; + } + + //TODO check: no need to cause datamodel to forget params here? +// paramDataModel->forgetAllOnboardParameters(); + + if (!transmissionListMode) { + // Clear transmission state + receivedParamsList.clear(); + transmissionListSizeKnown.clear(); + + transmissionListMode = true; + foreach (int key, missingReadPackets.keys()) { + missingReadPackets.value(key)->clear(); + } + transmissionActive = true; + + setParameterStatusMsg(tr("Requested param list.. waiting")); + listRecvTimeout = QGC::groundTimeMilliseconds() + 10000; + mav->requestParameters(); + setRetransmissionGuardEnabled(true); + } + else { + qDebug() << __FILE__ << __LINE__ << "Ignoring requestParameterList because we're receiving params list"; + } + +} + + +/* + Empty read retransmission list + Empty write retransmission list +*/ +void UASParameterCommsMgr::clearRetransmissionLists(int& missingReadCount, int& missingWriteCount ) +{ + qDebug() << __FILE__ << __LINE__ << "clearRetransmissionLists"; + + missingReadCount = 0; + QList readKeys = missingReadPackets.keys(); + foreach (int compId, readKeys) { + missingReadCount += missingReadPackets.value(compId)->count(); + missingReadPackets.value(compId)->clear(); + } + + missingWriteCount = 0; + QList writeKeys = missingWriteAckPackets.keys(); + foreach (int compId, writeKeys) { + missingWriteCount += missingWriteAckPackets.value(compId)->count(); + missingWriteAckPackets.value(compId)->clear(); + } + +} + + +void UASParameterCommsMgr::emitPendingParameterCommit(int compId, const QString& key, QVariant& value) +{ + int paramType = (int)value.type(); + switch (paramType) + { + case QVariant::Char: + { + QVariant fixedValue(QChar((unsigned char)value.toInt())); + emit commitPendingParameter(compId, key, fixedValue); + } + break; + case QVariant::Int: + { + QVariant fixedValue(value.toInt()); + emit commitPendingParameter(compId, key, fixedValue); + } + break; + case QVariant::UInt: + { + QVariant fixedValue(value.toUInt()); + emit commitPendingParameter(compId, key, fixedValue); + } + break; + case QMetaType::Float: + { + QVariant fixedValue(value.toFloat()); + emit commitPendingParameter(compId, key, fixedValue); + } + break; + default: + qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE"; + return; + } + + setParameterStatusMsg(tr("Requested write of: %1: %2").arg(key).arg(value.toDouble())); + +} + + +void UASParameterCommsMgr::resendReadWriteRequests() +{ + int compId; + QList compIds; + + // Re-request at maximum retransmissionBurstRequestSize parameters at once + // to prevent link flooding' + int requestedReadCount = 0; + compIds = missingReadPackets.keys(); + foreach (compId, compIds) { + // Request n parameters from this component (at maximum) + QList* missingReadParams = missingReadPackets.value(compId, NULL); + qDebug() << "missingReadParams:" << missingReadParams->count(); + foreach (int paramId, *missingReadParams) { + if (requestedReadCount < retransmissionBurstRequestSize) { + //qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD REQUESTS RETRANSMISSION OF PARAM #" << paramId << "FROM COMPONENT #" << compId; + emit parameterUpdateRequestedById(compId, paramId); + setParameterStatusMsg(tr("Requested retransmission of #%1").arg(paramId+1)); + requestedReadCount++; + } + else { + qDebug() << "Throttling read retransmit requests at" << requestedReadCount; + break; + } + } + } + + // Re-request at maximum retransmissionBurstRequestSize parameters at once + // to prevent write-request link flooding + int requestedWriteCount = 0; + compIds = missingWriteAckPackets.keys(); + foreach (compId, compIds) { + QMap * missingParams = missingWriteAckPackets.value(compId); + foreach (QString key, missingParams->keys()) { + if (requestedWriteCount < retransmissionBurstRequestSize) { + // Re-request write operation + QVariant value = missingParams->value(key); + emitPendingParameterCommit(compId, key, value); + requestedWriteCount++; + } + else { + qDebug() << "Throttling write retransmit requests at" << requestedWriteCount; + break; + } + } + } + + if ((0 == requestedWriteCount) && (0 == requestedReadCount) ) { + qDebug() << __FILE__ << __LINE__ << "NO re-read or rewrite requests??"; + if (!transmissionListMode) { + setRetransmissionGuardEnabled(false); + transmissionActive = false; + } + } + else { + //restart the timer now that we've sent + setRetransmissionGuardEnabled(true); + } +} + +void UASParameterCommsMgr::resetAfterListReceive() +{ + transmissionListMode = false; + transmissionListSizeKnown.clear(); + + //We shouldn't clear missingPackets because other transactions might be using them? + +} + +void UASParameterCommsMgr::retransmissionGuardTick() +{ + quint64 curTime = QGC::groundTimeMilliseconds(); + + //Workaround for an apparent Qt bug that causes retransmission guard timer to fire prematurely (350ms) + int elapsed = (int)(curTime - lastTimerReset); + if (elapsed < retransmissionTimeout) { + qDebug() << "retransmissionGuardTick elapsed:" << (curTime - lastTimerReset); + //reset the guard timer: it fired prematurely + setRetransmissionGuardEnabled(true); + return; + } + qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD ACTIVE after" << elapsed; + + + if (transmissionActive) { + + if (transmissionListMode && transmissionListSizeKnown.isEmpty() ) { + //we are still waitin for the first parameter list response + if (curTime > this->listRecvTimeout) { + //re-request parameters + setParameterStatusMsg(tr("TIMEOUT: Re-requesting param list"),ParamCommsStatusLevel_Warning); + listRecvTimeout = curTime + 10000; + mav->requestParameters(); + //reset the timer + setRetransmissionGuardEnabled(true); + } + return; + } + + // Check for timeout + // stop retransmission attempts on timeout + if (curTime > transmissionTimeout) { + setRetransmissionGuardEnabled(false); + resetAfterListReceive(); + + int missingReadCount, missingWriteCount; + clearRetransmissionLists(missingReadCount,missingWriteCount); + if ((missingReadCount > 0) || (missingWriteCount > 0)) { + setParameterStatusMsg(tr("TIMEOUT! MISSING: %1 read, %2 write.").arg(missingReadCount).arg(missingWriteCount), + ParamCommsStatusLevel_Warning); + } + + return; + } + + resendReadWriteRequests(); + } + else { + qDebug() << __FILE__ << __LINE__ << "STOPPING RETRANSMISSION GUARD GRACEFULLY"; + setRetransmissionGuardEnabled(false); + } +} + + + +/** + * Enabling the retransmission guard enables the parameter widget to track + * dropped parameters and to re-request them. This works for both individual + * parameter reads as well for whole list requests. + * + * @param enabled True if retransmission checking should be enabled, false else + */ + +void UASParameterCommsMgr::setRetransmissionGuardEnabled(bool enabled) +{ + if (enabled) { + retransmissionTimer.start(retransmissionTimeout); + lastTimerReset = QGC::groundTimeMilliseconds() ; + } else { + retransmissionTimer.stop(); + } +} + +void UASParameterCommsMgr::requestParameterUpdate(int component, const QString& parameter) +{ + if (mav) { + mav->requestParameter(component, parameter); + } +} + +void UASParameterCommsMgr::requestRcCalibrationParamsUpdate() +{ + if (!transmissionListMode) { + QString minTpl("RC%1_MIN"); + QString maxTpl("RC%1_MAX"); + QString trimTpl("RC%1_TRIM"); + QString revTpl("RC%1_REV"); + + // Do not request the RC type, as these values depend on this + // active onboard parameter + + for (unsigned int i = 1; i < (RC_CAL_CHAN_MAX+1); ++i) { + qDebug() << "Request RC " << i; + mav->requestParameter(0, minTpl.arg(i)); + QGC::SLEEP::usleep(5000); + mav->requestParameter(0, trimTpl.arg(i)); + QGC::SLEEP::usleep(5000); + mav->requestParameter(0, maxTpl.arg(i)); + QGC::SLEEP::usleep(5000); + mav->requestParameter(0, revTpl.arg(i)); + QGC::SLEEP::usleep(5000); + } + } + else { + qDebug() << __FILE__ << __LINE__ << "Ignoring requestRcCalibrationParamsUpdate because we're receiving params list"; + } +} + + +/** + * @param component the subsystem which has the parameter + * @param parameterName name of the parameter, as delivered by the system + * @param value value of the parameter + */ +void UASParameterCommsMgr::setParameter(int component, QString parameterName, QVariant value) +{ + if (parameterName.isEmpty()) { + return; + } + + double dblValue = value.toDouble(); + + if (paramDataModel->isValueLessThanParamMin(parameterName,dblValue)) { + setParameterStatusMsg(tr("REJ. %1, %2 < min").arg(parameterName).arg(dblValue), + ParamCommsStatusLevel_Error + ); + return; + } + if (paramDataModel->isValueGreaterThanParamMax(parameterName,dblValue)) { + setParameterStatusMsg(tr("REJ. %1, %2 > max").arg(parameterName).arg(dblValue), + ParamCommsStatusLevel_Error + ); + return; + } + + QVariant onboardVal; + paramDataModel->getOnboardParamValue(component,parameterName,onboardVal); + if (onboardVal == value) { + setParameterStatusMsg(tr("REJ. %1 already %2").arg(parameterName).arg(dblValue), + ParamCommsStatusLevel_Warning + ); + return; + } + + emitPendingParameterCommit(component, parameterName, value); + + // Wait for parameter to be written back + // mark it therefore as missing + if (!missingWriteAckPackets.contains(component)) { + missingWriteAckPackets.insert(component, new QMap()); + } + + // Insert it in missing write ACK list + missingWriteAckPackets.value(component)->insert(parameterName, value); + + // Set timeouts + if (transmissionActive) { + transmissionTimeout += rewriteTimeout; + } + else { + quint64 newTransmissionTimeout = QGC::groundTimeMilliseconds() + rewriteTimeout; + if (newTransmissionTimeout > transmissionTimeout) { + transmissionTimeout = newTransmissionTimeout; + } + transmissionActive = true; + } + + // Enable guard / reset timeouts + setRetransmissionGuardEnabled(true); +} + +void UASParameterCommsMgr::setParameterStatusMsg(const QString& msg, ParamCommsStatusLevel_t level) +{ + qDebug() << "parameterStatusMsg: " << msg; + parameterStatusMsg = msg; + + emit parameterStatusMsgUpdated(msg,level); +} + + +/** + * @param uas System which has the component + * @param component id of the component + * @param parameterName human friendly name of the parameter + */ +void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int paramCount, int paramId, QString paramName, QVariant value) +{ + Q_UNUSED(uas); //this object is assigned to one UAS only + + //notify the data model that we have an updated param + paramDataModel->handleParamUpdate(compId,paramName,value); + + // Missing packets list has to be instantiated for all components + if (!missingReadPackets.contains(compId)) { + missingReadPackets.insert(compId, new QList()); + } + + QList* compMissReadPackets = missingReadPackets.value(compId); + + // List mode is different from single parameter transfers + if (transmissionListMode) { + // Only accept the list size once on the first packet from + // each component + if (!transmissionListSizeKnown.contains(compId)) { + // Mark list size as known + transmissionListSizeKnown.insert(compId, true); + + qDebug() << "Mark all parameters as missing: " << paramCount; + for (int i = 1; i < paramCount; ++i) { //TODO check: param Id 0 is "all parameters" and not valid ? + if (!compMissReadPackets->contains(i)) { + compMissReadPackets->append(i); + } + } + + // There is only one transmission timeout for all components + // since components do not manage their transmission, + // the longest timeout is safe for all components. + quint64 thisTransmissionTimeout = QGC::groundTimeMilliseconds() + (paramCount*retransmissionTimeout); + if (thisTransmissionTimeout > transmissionTimeout) { + transmissionTimeout = thisTransmissionTimeout; + } + } + + } + + // Mark this parameter as received in read list + int index = compMissReadPackets->indexOf(paramId); + if (index != -1) { + compMissReadPackets->removeAt(index); + } + + bool justWritten = false; + bool writeMismatch = false; + + // Mark this parameter as received in write ACK list + QMap* compMissWritePackets = missingWriteAckPackets.value(compId); + if (compMissWritePackets && compMissWritePackets->contains(paramName)) { + justWritten = true; + if (compMissWritePackets->value(paramName) != value) { + writeMismatch = true; + } + compMissWritePackets->remove(paramName); + } + + int missReadCount = 0; + foreach (int key, missingReadPackets.keys()) { + missReadCount += missingReadPackets.value(key)->count(); + } + + int missWriteCount = 0; + foreach (int key, missingWriteAckPackets.keys()) { + missWriteCount += missingWriteAckPackets.value(key)->count(); + } + + //TODO simplify this if-else tree + if (justWritten) { + if (!writeMismatch) { + setParameterStatusMsg(tr("SUCCESS: Wrote %2 (#%1/%4): %3 [%5]").arg(paramId+1).arg(paramName).arg(value.toDouble()).arg(paramCount).arg(missWriteCount)); + if (0 == missWriteCount) { + setParameterStatusMsg(tr("SUCCESS: WROTE ALL PARAMETERS")); + } + } + else { + // Mismatch, tell user + setParameterStatusMsg(tr("FAILURE: Wrote %1: sent %2 != onboard %3").arg(paramName).arg(compMissWritePackets->value(paramName).toDouble()).arg(value.toDouble()), + ParamCommsStatusLevel_Warning); + } + } + else { + if (missReadCount == 0) { + // Transmission done + QTime time = QTime::currentTime(); + QString timeString = time.toString(); + setParameterStatusMsg(tr("All received. (updated at %1)").arg(timeString)); + } + else { + // Transmission in progress + QString val = QString("%1").arg(value.toFloat(), 5, 'f', 1, QChar(' ')); + setParameterStatusMsg(tr("OK: %1 %2 (%3/%4)").arg(paramName).arg(val).arg(paramCount-missReadCount).arg(paramCount), + ParamCommsStatusLevel_Warning); + //transmissionMissingPackets + } + } + + // Check if last parameter was received + if (missReadCount == 0 && missWriteCount == 0) { + resetAfterListReceive(); + setRetransmissionGuardEnabled(false); + //all parameters have been received, broadcast to UI + emit parameterListUpToDate(); + } + else { + //reset the timeout timer since we received one + setRetransmissionGuardEnabled(true); + + //qDebug() << "missCount:" << missCount << "missWriteCount:" << missWriteCount; + //if (missCount < 4) { + // foreach (int key, transmissionMissingPackets.keys()) { + // QList* list = transmissionMissingPackets.value(key); + + // if (list && list->count()) { + // QString yazza = QString().sprintf("Component %d missing %d: ",key,list->count()); + + // for (int i = 0; i < list->count(); i++) { + // int val = list->at(i); + // yazza.append( QString().sprintf("%d,",val) ); + // } + + // qDebug() << yazza; + // } + // else { + // //very suspicious...no actual missing items?? + // transmissionMissingPackets.remove(key); + // break; + // } + // } + //} + } +} + + +void UASParameterCommsMgr::writeParamsToPersistentStorage() +{ + if (mav) { + mav->writeParametersToStorage(); //TODO track timeout, retransmit etc? + } +} + + +void UASParameterCommsMgr::sendPendingParameters() +{ + // Iterate through all components, through all pending parameters and send them to UAS + int parametersSent = 0; + QMap*>* changedValues = paramDataModel->getAllPendingParams(); + QMap*>::iterator i; + for (i = changedValues->begin(); i != changedValues->end(); ++i) { + // Iterate through the parameters of the component + int compId = i.key(); + QMap* paramList = i.value(); + QMap::iterator j; + setParameterStatusMsg(tr("%1 pending params for component %2").arg(paramList->count()).arg(compId)); + + for (j = paramList->begin(); j != paramList->end(); ++j) { + //TODO mavlink command for "set parameter list" ? + setParameter(compId, j.key(), j.value()); + parametersSent++; + } + } + + // Change transmission status if necessary + if (parametersSent == 0) { + setParameterStatusMsg(tr("No transmission: No changed values."),ParamCommsStatusLevel_Warning); + } else { + setParameterStatusMsg(tr("Transmitting %1 parameters.").arg(parametersSent)); + // Set timeouts + if (transmissionActive) { + transmissionTimeout += parametersSent*rewriteTimeout; + } + else { + transmissionActive = true; + quint64 newTransmissionTimeout = QGC::groundTimeMilliseconds() + parametersSent*rewriteTimeout; + if (newTransmissionTimeout > transmissionTimeout) { + transmissionTimeout = newTransmissionTimeout; + } + } + // Enable guard + setRetransmissionGuardEnabled(true); + + qDebug() << "Pending parameters now:" << paramDataModel->countPendingParams(); + } +} + +UASParameterCommsMgr::~UASParameterCommsMgr() +{ + setRetransmissionGuardEnabled(false); + + QString ptrStr; + ptrStr.sprintf("%8p", this); + qDebug() << "UASParameterCommsMgr destructor: " << ptrStr ; + +} + diff --git a/src/uas/UASParameterCommsMgr.h b/src/uas/UASParameterCommsMgr.h new file mode 100644 index 0000000000000000000000000000000000000000..acdab75a86d3c4b7e1b1d25f944ad16b57622de4 --- /dev/null +++ b/src/uas/UASParameterCommsMgr.h @@ -0,0 +1,114 @@ +#ifndef UASPARAMETERCOMMSMGR_H +#define UASPARAMETERCOMMSMGR_H + +#include +#include +#include +#include +#include + +class UASInterface; +class UASParameterDataModel; + + + +class UASParameterCommsMgr : public QObject +{ + Q_OBJECT + + +public: + explicit UASParameterCommsMgr(QObject *parent = 0, UASInterface* uas = NULL); + ~UASParameterCommsMgr(); + + typedef enum ParamCommsStatusLevel { + ParamCommsStatusLevel_OK = 0, + ParamCommsStatusLevel_Warning = 2, + ParamCommsStatusLevel_Error = 4, + ParamCommsStatusLevel_Count + } ParamCommsStatusLevel_t; + + +protected: + /** @brief Activate / deactivate parameter retransmission */ + virtual void setRetransmissionGuardEnabled(bool enabled); + + virtual void setParameterStatusMsg(const QString& msg, ParamCommsStatusLevel_t level=ParamCommsStatusLevel_OK); + + /** @brief Load settings that control eg retransmission timeouts */ + void loadParamCommsSettings(); + + /** @brief clear transmissionMissingPackets and transmissionMissingWriteAckPackets */ + void clearRetransmissionLists(int& missingReadCount, int& missingWriteCount ); + + void resendReadWriteRequests(); + void resetAfterListReceive(); + + void emitPendingParameterCommit(int compId, const QString& key, QVariant& value); + +signals: + void commitPendingParameter(int component, QString parameter, QVariant value); + void parameterChanged(int component, int parameterIndex, QVariant value); + void parameterValueConfirmed(int uas, int component,int paramCount, int paramId, QString parameter, QVariant value); + + /** @brief We have received a complete list of all parameters onboard the MAV */ + void parameterListUpToDate(); + + void parameterUpdateRequested(int component, const QString& parameter); + void parameterUpdateRequestedById(int componentId, int paramId); + + /** @brief We updated the parameter status message */ + void parameterStatusMsgUpdated(QString msg, int level); + +public slots: + /** @brief Iterate through all components, through all pending parameters and send them to UAS */ + virtual void sendPendingParameters(); + + /** @brief Write the current onboard parameters from transient RAM into persistent storage, e.g. EEPROM or harddisk */ + virtual void writeParamsToPersistentStorage(); + + /** @brief Write one parameter to the MAV */ + virtual void setParameter(int component, QString parameterName, QVariant value); + + /** @brief Request list of parameters from MAV */ + virtual void requestParameterList(); + + /** @brief Check for missing parameters */ + virtual void retransmissionGuardTick(); + + /** @brief Request a single parameter update by name */ + virtual void requestParameterUpdate(int component, const QString& parameter); + + /** @brief Request an update of RC parameters */ + virtual void requestRcCalibrationParamsUpdate(); + + virtual void receivedParameterUpdate(int uas, int compId, int paramCount, int paramId, QString paramName, QVariant value); + +protected: + + UASInterface* mav; ///< The MAV we're talking to + + UASParameterDataModel* paramDataModel; + + // Communications management + QVector receivedParamsList; ///< Successfully received parameters + QMap* > missingReadPackets; ///< Missing packets + QMap* > missingWriteAckPackets; ///< Missing write ACK packets + bool transmissionListMode; ///< Currently requesting list + QMap transmissionListSizeKnown; ///< List size initialized? + bool transmissionActive; ///< Missing packets, working on list? + quint64 transmissionTimeout; ///< Timeout + QTimer retransmissionTimer; ///< Timer handling parameter retransmission + quint64 lastTimerReset; ///< Last time the guard timer was reset, to prevent premature firing + int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds + int rewriteTimeout; ///< Write request timeout, in milliseconds + int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst + quint64 listRecvTimeout; ///< How long to wait for first parameter list response before re-requesting + + // Status + QString parameterStatusMsg; + +}; + + +#endif // UASPARAMETERCOMMSMGR_H diff --git a/src/uas/UASParameterDataModel.cc b/src/uas/UASParameterDataModel.cc new file mode 100644 index 0000000000000000000000000000000000000000..66b847e88eb7c63aa2cbcc969c7d9378980da098 --- /dev/null +++ b/src/uas/UASParameterDataModel.cc @@ -0,0 +1,436 @@ +#include "UASParameterDataModel.h" + +#include + +#include +#include +#include + +#include "QGCMAVLink.h" + +UASParameterDataModel::UASParameterDataModel(QObject *parent) : + QObject(parent) +{ + onboardParameters.clear(); + pendingParameters.clear(); + +} + + + +int UASParameterDataModel::countPendingParams() +{ + int totalPending = 0; + QMap*>::iterator i; + for (i = pendingParameters.begin(); i != pendingParameters.end(); ++i) { + // Iterate through the parameters of the component + QMap* paramList = i.value(); + totalPending += paramList->count(); + } + + return totalPending; +} + + +bool UASParameterDataModel::updatePendingParamWithValue(int compId, QString& key, const QVariant& value) +{ + bool pending = true; + //ensure we have this component in our onboard and pending lists already + addComponent(compId); + + QMap* existParams = getOnboardParamsForComponent(compId); + if (existParams->contains(key)) { + QVariant existValue = existParams->value(key); + if (existValue == value) { + pending = false; + } + } + + if (pending) { + setPendingParam(compId,key,value); + } + else { + removePendingParam(compId,key); + } + + return pending; +} + + +bool UASParameterDataModel::isParamChangePending(int compId, const QString& key) +{ + QMap* pendingParms = getPendingParamsForComponent(compId); + return ((NULL != pendingParms) && pendingParms->contains(key)); +} + +void UASParameterDataModel::setPendingParam(int compId, QString& key, const QVariant &value) +{ + //ensure we have a placeholder map for this component + addComponent(compId); + QMap *pendParams = getPendingParamsForComponent(compId); + if (pendParams) { + pendParams->insert(key,value); + emit pendingParamUpdate(compId, key, value, true); + } +} + +void UASParameterDataModel::removePendingParam(int compId, QString& key) +{ + qDebug() << "removePendingParam:" << key; + + QMap *pendParams = getPendingParamsForComponent(compId); + if (pendParams) { + pendParams->remove(key); + //broadcast the existing value + QVariant existVal; + getOnboardParamValue(compId,key,existVal); + emit pendingParamUpdate(compId, key,existVal, false); + } +} + +void UASParameterDataModel::setOnboardParam(int compId, QString& key, const QVariant& value) +{ + //ensure we have a placeholder map for this component + addComponent(compId); + QMap *params = getOnboardParamsForComponent(compId); + params->insert(key,value); +} + +void UASParameterDataModel::setOnboardParamWithType(int compId, QString& key, QVariant& value) +{ + + switch ((int)value.type()) + { + case QVariant::Int: + { + QVariant fixedValue(value.toInt()); + onboardParameters.value(compId)->insert(key, fixedValue); + } + break; + case QVariant::UInt: + { + QVariant fixedValue(value.toUInt()); + onboardParameters.value(compId)->insert(key, fixedValue); + } + break; + case QMetaType::Float: + { + QVariant fixedValue(value.toFloat()); + onboardParameters.value(compId)->insert(key, fixedValue); + } + break; + case QMetaType::QChar: + { + QVariant fixedValue(QChar((unsigned char)value.toUInt())); + onboardParameters.value(compId)->insert(key, fixedValue); + } + break; + default: + qCritical() << "ABORTED PARAM UPDATE, NO VALID QVARIANT TYPE"; + return; + } +} + +void UASParameterDataModel::addComponent(int compId) +{ + if (!onboardParameters.contains(compId)) { + onboardParameters.insert(compId, new QMap()); + } + if (!pendingParameters.contains(compId)) { + pendingParameters.insert(compId, new QMap()); + } +} + + +void UASParameterDataModel::handleParamUpdate(int compId, QString& paramName, QVariant& value) +{ + //verify that the value requested by the user matches the set value + //if it doesn't match, leave the pending parameter in the pending list! + if (pendingParameters.contains(compId)) { + QMap *pendingParams = pendingParameters.value(compId); + if ((NULL != pendingParams) && pendingParams->contains(paramName)) { + QVariant reqVal = pendingParams->value(paramName); + if (reqVal == value) { + //notify everyone that this item is being removed from the pending parameters list since it's now confirmed + emit pendingParamUpdate(compId, paramName, value, false); + pendingParams->remove(paramName); + } + else { + qDebug() << "Pending commit for " << paramName << " want: " << reqVal << " got: " << value; + } + } + } + + emit parameterUpdated(compId,paramName,value); + setOnboardParam(compId,paramName,value); + +} + +bool UASParameterDataModel::getOnboardParamValue(int componentId, const QString& key, QVariant& value) const +{ + + if (onboardParameters.contains(componentId)) { + if (onboardParameters.value(componentId)->contains(key)) { + value = onboardParameters.value(componentId)->value(key); + return true; + } + } + + return false; +} + +void UASParameterDataModel::forgetAllOnboardParams() +{ + onboardParameters.clear(); +} + +void UASParameterDataModel::readUpdateParamsFromStream( QTextStream& stream) +{ + bool userWarned = false; + + while (!stream.atEnd()) { + QString line = stream.readLine(); + if (!line.startsWith("#")) { + QStringList wpParams = line.split("\t"); + int lineMavId = wpParams.at(0).toInt(); + if (wpParams.size() == 5) { + // Only load parameters for right mav + if (!userWarned && (uasId != lineMavId)) { + //TODO warn the user somehow ?? + QString msg = tr("The parameters in the stream have been saved from system %1, but the currently selected system has the ID %2.").arg(lineMavId).arg(uasId); +// MainWindow::instance()->showCriticalMessage( +// tr("Parameter loading warning"), +// tr("The parameters from the file %1 have been saved from system %2, but the currently selected system has the ID %3. If this is unintentional, please click on to revert to the parameters that are currently onboard").arg(fileName).arg(wpParams.at(0).toInt()).arg(mav->getUASID())); + userWarned = true; + return; + } + + bool changed = false; + int componentId = wpParams.at(1).toInt(); + QString key = wpParams.at(2); + QString valStr = wpParams.at(3); + double dblVal = wpParams.at(3).toDouble(); + uint paramType = wpParams.at(4).toUInt(); + + + if (!onboardParameters.contains(componentId)) { + addComponent(componentId); + changed = true; + } + else { + if (fabs((static_cast(onboardParameters.value(componentId)->value(key, dblVal).toDouble())) - (dblVal)) > + 2.0f * FLT_EPSILON) { + changed = true; + qDebug() << "Changed" << key << "VAL" << dblVal; + } + } + + + if (changed) { + switch (paramType) + { + case MAV_PARAM_TYPE_REAL32: + updatePendingParamWithValue(componentId,key,QVariant(valStr.toFloat())); + break; + case MAV_PARAM_TYPE_UINT32: + updatePendingParamWithValue(componentId,key, QVariant(valStr.toUInt())); + break; + case MAV_PARAM_TYPE_INT32: + updatePendingParamWithValue(componentId,key,QVariant(valStr.toInt())); + break; + default: + qDebug() << "FAILED LOADING PARAM" << key << "UNKNOWN DATA TYPE"; + } + } + + + } + } + } + +} + +void UASParameterDataModel::writeOnboardParamsToStream( QTextStream &stream, const QString& name) +{ + stream << "# Onboard parameters for system " << name << "\n"; + stream << "#\n"; + stream << "# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)\n"; + + // Iterate through all components, through all parameters and emit them + QMap*>::iterator i; + for (i = onboardParameters.begin(); i != onboardParameters.end(); ++i) { + // Iterate through the parameters of the component + int compid = i.key(); + QMap* comp = i.value(); + { + QMap::iterator j; + for (j = comp->begin(); j != comp->end(); ++j) + { + QString paramValue("%1"); + QString paramType("%1"); + switch ((int)j.value().type()) + { + case QVariant::Int: + paramValue = paramValue.arg(j.value().toInt()); + paramType = paramType.arg(MAV_PARAM_TYPE_INT32); + break; + case QVariant::UInt: + paramValue = paramValue.arg(j.value().toUInt()); + paramType = paramType.arg(MAV_PARAM_TYPE_UINT32); + break; + case QMetaType::Float: + // We store parameters as floats, with only 6 digits of precision guaranteed for decimal string conversion + // (see IEEE 754, 32 bit single-precision) + paramValue = paramValue.arg((double)j.value().toFloat(), 25, 'g', 6); + paramType = paramType.arg(MAV_PARAM_TYPE_REAL32); + break; + default: + qCritical() << "ABORTED PARAM WRITE TO FILE, NO VALID QVARIANT TYPE" << j.value(); + return; + } + stream << this->uasId << "\t" << compid << "\t" << j.key() << "\t" << paramValue << "\t" << paramType << "\n"; + stream.flush(); + } + } + } +} + + +void UASParameterDataModel::loadParamMetaInfoFromStream(QTextStream& stream) +{ + + // First line is header + // there might be more lines, but the first + // line is assumed to be at least header + QString header = stream.readLine(); + + // Ignore top-level comment lines + while (header.startsWith('#') || header.startsWith('/') + || header.startsWith('=') || header.startsWith('^')) + { + header = stream.readLine(); + } + + bool charRead = false; + QString separator = ""; + QList sepCandidates; + sepCandidates << '\t'; + sepCandidates << ','; + sepCandidates << ';'; + //sepCandidates << ' '; + sepCandidates << '~'; + sepCandidates << '|'; + + // Iterate until separator is found + // or full header is parsed + for (int i = 0; i < header.length(); i++) + { + if (sepCandidates.contains(header.at(i))) + { + // Separator found + if (charRead) + { + separator += header[i]; + } + } + else + { + // Char found + charRead = true; + // If the separator is not empty, this char + // has been read after a separator, so detection + // is now complete + if (separator != "") break; + } + } + + bool stripFirstSeparator = false; + bool stripLastSeparator = false; + + // Figure out if the lines start with the separator (e.g. wiki syntax) + if (header.startsWith(separator)) stripFirstSeparator = true; + + // Figure out if the lines end with the separator (e.g. wiki syntax) + if (header.endsWith(separator)) stripLastSeparator = true; + + QString out = separator; + out.replace("\t", ""); + //qDebug() << " Separator: \"" << out << "\""; + //qDebug() << "READING CSV:" << header; + + + // Read data + while (!stream.atEnd()) + { + QString line = stream.readLine(); + + //qDebug() << "LINE PRE-STRIP" << line; + + // Strip separtors if necessary + if (stripFirstSeparator) line.remove(0, separator.length()); + if (stripLastSeparator) line.remove(line.length()-separator.length(), line.length()-1); + + //qDebug() << "LINE POST-STRIP" << line; + + // Keep empty parts here - we still have to act on them + QStringList parts = line.split(separator, QString::KeepEmptyParts); + + // Each line is: + // variable name, Min, Max, Default, Multiplier, Enabled (0 = no, 1 = yes), Comment + + + // Fill in min, max and default values + if (parts.count() > 1) + { + // min + paramMin.insert(parts.at(0).trimmed(), parts.at(1).toDouble()); + } + if (parts.count() > 2) + { + // max + paramMax.insert(parts.at(0).trimmed(), parts.at(2).toDouble()); + } + if (parts.count() > 3) + { + // default + paramDefault.insert(parts.at(0).trimmed(), parts.at(3).toDouble()); + } + // IGNORING 4 and 5 for now + if (parts.count() > 6) + { + // tooltip + paramDescriptions.insert(parts.at(0).trimmed(), parts.at(6).trimmed()); + qDebug() << "PARAM META:" << parts.at(0).trimmed(); + } + } +} + + void UASParameterDataModel::setParamDescriptions(const QMap& paramInfo) +{ + if (paramInfo.isEmpty()) { + qDebug() << __FILE__ << ":" << __LINE__ << "setParamDescriptions with empty"; + } + + paramDescriptions = paramInfo; +} + +bool UASParameterDataModel::isValueGreaterThanParamMax(const QString& paramName, double dblVal) +{ + if (paramMax.contains(paramName)) { + if (dblVal > paramMax.value(paramName)) + return true; + } + + return false; +} + +bool UASParameterDataModel::isValueLessThanParamMin(const QString& paramName, double dblVal) +{ + if (paramMin.contains(paramName)) { + if (dblVal < paramMin.value(paramName)) + return true; + } + + return false; + } + diff --git a/src/uas/UASParameterDataModel.h b/src/uas/UASParameterDataModel.h new file mode 100644 index 0000000000000000000000000000000000000000..2ca97965d8885e7c0aefc4a586e38e79d373597c --- /dev/null +++ b/src/uas/UASParameterDataModel.h @@ -0,0 +1,121 @@ +#ifndef UASPARAMETERDATAMODEL_H +#define UASPARAMETERDATAMODEL_H + +#include +#include +#include + +class QTextStream; + +class UASParameterDataModel : public QObject +{ + Q_OBJECT +public: + explicit UASParameterDataModel(QObject *parent = 0); + + + //Parameter meta info + bool isParamMinKnown(const QString& param) { return paramMin.contains(param); } + virtual bool isValueLessThanParamMin(const QString& param, double dblVal); + + bool isParamMaxKnown(const QString& param) { return paramMax.contains(param); } + virtual bool isValueGreaterThanParamMax(const QString& param, double dblVal); + + bool isParamDefaultKnown(const QString& param) { return paramDefault.contains(param); } + double getParamMin(const QString& param) { return paramMin.value(param, 0.0f); } + double getParamMax(const QString& param) { return paramMax.value(param, 0.0f); } + double getParamDefault(const QString& param) { return paramDefault.value(param, 0.0f); } + virtual QString getParamDescription(const QString& param) { return paramDescriptions.value(param, ""); } + virtual void setParamDescriptions(const QMap& paramInfo); + + //TODO make this method protected? + /** @brief Ensure that the data model is aware of this component + * @param compId Id of the component + */ + virtual void addComponent(int compId); + + + + /** @brief Save the onboard parameter with a the type specified in the QVariant as fixed */ + virtual void setOnboardParamWithType(int componentId, QString& key, QVariant& value); + + /** @brief clears every parameter for every loaded component */ + virtual void forgetAllOnboardParams(); + + + /** @brief add this parameter to pending list iff it has changed from onboard value + * @return true if the parameter is now pending + */ + virtual bool updatePendingParamWithValue(int componentId, QString& key, const QVariant &value); + virtual void handleParamUpdate(int componentId, QString& key, QVariant& value); + virtual bool getOnboardParamValue(int componentId, const QString& key, QVariant& value) const; + + virtual bool isParamChangePending(int componentId,const QString& key); + + QMap* getPendingParamsForComponent(int componentId) { + return pendingParameters.value(componentId); + } + + QMap* getOnboardParamsForComponent(int componentId) { + return onboardParameters.value(componentId); + } + + QMap* >* getAllPendingParams() { + return &pendingParameters; + } + + QMap* >* getAllOnboardParams() { + return &onboardParameters; + } + + /** @brief return a count of all pending parameters */ + int countPendingParams(); + + + virtual void writeOnboardParamsToStream(QTextStream &stream, const QString& uasName); + virtual void readUpdateParamsFromStream(QTextStream &stream); + + virtual void loadParamMetaInfoFromStream(QTextStream& stream); + + void setUASID(int anId) { this->uasId = anId; } + +protected: + /** @brief set the confirmed value of a parameter in the onboard params list */ + virtual void setOnboardParam(int componentId, QString& key, const QVariant& value); + + /** @brief Write a new pending parameter value that may be eventually sent to the UAS */ + virtual void setPendingParam(int componentId, QString& key, const QVariant& value); + /** @brief remove a parameter from the pending list */ + virtual void removePendingParam(int compId, QString& key); + + +signals: + + /** @brief We've received an update of a parameter's value */ + void parameterUpdated(int compId, QString paramName, QVariant value); + + /** @brief Notifies listeners that a param was added to or removed from the pending list */ + void pendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending); + + void allPendingParamsCommitted(); ///< All pending params have been committed to the MAV + +public slots: + + +protected: + int uasId; ///< The UAS / MAV to which this data model pertains + QMap* > pendingParameters; ///< Changed values that have not yet been transmitted to the UAS, by component ID + QMap* > onboardParameters; ///< All parameters confirmed to be stored onboard the UAS, by component ID + + // Tooltip data structures + QMap paramDescriptions; ///< Tooltip values + + // Min / Default / Max data structures + QMap paramMin; ///< Minimum param values + QMap paramDefault; ///< Default param values + QMap paramMax; ///< Minimum param values + + +}; + +#endif // UASPARAMETERDATAMODEL_H diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index d6bdb29b866bca719a20fd27ab2e6ea1bc86debe..888a548e707cf80f7f696e12be379991bccefcb9 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -975,7 +975,9 @@ void UASWaypointManager::sendWaypointRequestList() wprl.target_system = uasid; wprl.target_component = MAV_COMP_ID_MISSIONPLANNER; - emit updateStatusString(QString("Requesting waypoint list...")); + QString statusMsg(tr("Requesting waypoint list...")); + qDebug() << __FILE__ << __LINE__ << statusMsg; + emit updateStatusString(statusMsg); mavlink_msg_mission_request_list_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wprl); uas->sendMessage(message); diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index d3a2a9d2a3ec2a0c749ec06a99a47d36eec66f42..8974032bfafb0f6146415ef4761d1d672ccaa818 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -950,35 +950,60 @@ void HSIDisplay::setActiveUAS(UASInterface* uas) if (uas) { - connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool))); - connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64))); - connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); - connect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64))); - connect(uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64))); - connect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float))); - connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); - connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); - - connect(uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool))); - connect(uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool))); - connect(uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool))); - connect(uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool))); - - connect(uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int))); - connect(uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int))); - connect(uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int))); - connect(uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int))); - connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float))); - - connect(uas, SIGNAL(gyroStatusChanged(bool,bool,bool)), this, SLOT(updateGyroStatus(bool,bool,bool))); - connect(uas, SIGNAL(accelStatusChanged(bool,bool,bool)), this, SLOT(updateAccelStatus(bool,bool,bool))); - connect(uas, SIGNAL(magSensorStatusChanged(bool,bool,bool)), this, SLOT(updateMagSensorStatus(bool,bool,bool))); - connect(uas, SIGNAL(baroStatusChanged(bool,bool,bool)), this, SLOT(updateBaroStatus(bool,bool,bool))); - connect(uas, SIGNAL(airspeedStatusChanged(bool,bool,bool)), this, SLOT(updateAirspeedStatus(bool,bool,bool))); - connect(uas, SIGNAL(opticalFlowStatusChanged(bool,bool,bool)), this, SLOT(updateOpticalFlowStatus(bool,bool,bool))); - connect(uas, SIGNAL(laserStatusChanged(bool,bool,bool)), this, SLOT(updateLaserStatus(bool,bool,bool))); - connect(uas, SIGNAL(groundTruthSensorStatusChanged(bool,bool,bool)), this, SLOT(updateGroundTruthSensorStatus(bool,bool,bool))); - connect(uas, SIGNAL(actuatorStatusChanged(bool,bool,bool)), this, SLOT(updateActuatorStatus(bool,bool,bool))); + connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), + this, SLOT(updateSatellite(int,int,float,float,float,bool))); + connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), + this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64))); + connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), + this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); + connect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), + this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64))); + connect(uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), + this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64))); + connect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), + this, SLOT(updateUserPositionSetpoints(int,float,float,float,float))); + connect(uas, SIGNAL(velocityChanged_NED(UASInterface*,double,double,double,quint64)), + this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); + connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), + this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); + connect(uas, SIGNAL(attitudeControlEnabled(bool)), + this, SLOT(updateAttitudeControllerEnabled(bool))); + connect(uas, SIGNAL(positionXYControlEnabled(bool)), + this, SLOT(updatePositionXYControllerEnabled(bool))); + connect(uas, SIGNAL(positionZControlEnabled(bool)), + this, SLOT(updatePositionZControllerEnabled(bool))); + connect(uas, SIGNAL(positionYawControlEnabled(bool)), + this, SLOT(updatePositionYawControllerEnabled(bool))); + + connect(uas, SIGNAL(localizationChanged(UASInterface*,int)), + this, SLOT(updateLocalization(UASInterface*,int))); + connect(uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), + this, SLOT(updateVisionLocalization(UASInterface*,int))); + connect(uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), + this, SLOT(updateGpsLocalization(UASInterface*,int))); + connect(uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), + this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int))); + connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), + this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float))); + + connect(uas, SIGNAL(gyroStatusChanged(bool,bool,bool)), + this, SLOT(updateGyroStatus(bool,bool,bool))); + connect(uas, SIGNAL(accelStatusChanged(bool,bool,bool)), + this, SLOT(updateAccelStatus(bool,bool,bool))); + connect(uas, SIGNAL(magSensorStatusChanged(bool,bool,bool)), + this, SLOT(updateMagSensorStatus(bool,bool,bool))); + connect(uas, SIGNAL(baroStatusChanged(bool,bool,bool)), + this, SLOT(updateBaroStatus(bool,bool,bool))); + connect(uas, SIGNAL(airspeedStatusChanged(bool,bool,bool)), + this, SLOT(updateAirspeedStatus(bool,bool,bool))); + connect(uas, SIGNAL(opticalFlowStatusChanged(bool,bool,bool)), + this, SLOT(updateOpticalFlowStatus(bool,bool,bool))); + connect(uas, SIGNAL(laserStatusChanged(bool,bool,bool)), + this, SLOT(updateLaserStatus(bool,bool,bool))); + connect(uas, SIGNAL(groundTruthSensorStatusChanged(bool,bool,bool)), + this, SLOT(updateGroundTruthSensorStatus(bool,bool,bool))); + connect(uas, SIGNAL(actuatorStatusChanged(bool,bool,bool)), + this, SLOT(updateActuatorStatus(bool,bool,bool))); statusClearTimer.start(3000); } else diff --git a/src/ui/ParameterInterface.cc b/src/ui/ParameterInterface.cc index e387a20938fb47abfbf1676d8858f4156b5229d3..93624d50ea6b871f87277d651bc76816092b2683 100644 --- a/src/ui/ParameterInterface.cc +++ b/src/ui/ParameterInterface.cc @@ -72,6 +72,7 @@ ParameterInterface::ParameterInterface(QWidget *parent) : ParameterInterface::~ParameterInterface() { + delete paramWidgets; delete m_ui; } @@ -89,8 +90,20 @@ void ParameterInterface::selectUAS(int index) */ void ParameterInterface::addUAS(UASInterface* uas) { + int uasId = uas->getUASID(); + qDebug() << "ParameterInterface::addUAS : " << uasId ; + + if (paramWidgets->contains(uasId) ) { + return; + } + QGCParamWidget* param = new QGCParamWidget(uas, this); - paramWidgets->insert(uas->getUASID(), param); + param->init(); + QString ptrStr; + ptrStr.sprintf("QGCParamWidget %8p (parent %8p)", param,this); + qDebug() << "Created " << ptrStr << " for UAS id: " << uasId << " count: " << paramWidgets->count(); + + paramWidgets->insert(uasId, param); m_ui->stackedWidget->addWidget(param); QGCSensorSettingsWidget* sensor = NULL; diff --git a/src/ui/PrimaryFlightDisplay.cc b/src/ui/PrimaryFlightDisplay.cc index d0070d2292c24ee800fb85bf0a06b4179646f2f7..651500ea23c15295e1448ecddc4dcbc596cbbe2f 100644 --- a/src/ui/PrimaryFlightDisplay.cc +++ b/src/ui/PrimaryFlightDisplay.cc @@ -267,15 +267,24 @@ void PrimaryFlightDisplay::forgetUAS(UASInterface* uas) { if (this->uas != NULL && this->uas == uas) { // Disconnect any previously connected active MAV - disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64))); - disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64))); - disconnect(this->uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int))); - disconnect(this->uas, SIGNAL(primarySpeedChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimarySpeed(UASInterface*,double,quint64))); - disconnect(this->uas, SIGNAL(gpsSpeedChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSSpeed(UASInterface*,double,quint64))); - disconnect(this->uas, SIGNAL(climbRateChanged(UASInterface*, double, quint64)), this, SLOT(updateClimbRate(UASInterface*, AltitudeMeasurementSource, double, quint64))); - disconnect(this->uas, SIGNAL(primaryAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimaryAltitude(UASInterface*, double, quint64))); - disconnect(this->uas, SIGNAL(gpsAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSAltitude(UASInterface*, double, quint64))); - disconnect(this->uas, SIGNAL(navigationControllerErrorsChanged(UASInterface*, double, double, double)), this, SLOT(updateNavigationControllerErrors(UASInterface*, double, double, double))); + disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), + this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64))); + disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)), + this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64))); + //disconnect(this->uas, SIGNAL(waypointSelected(int,int)), + // this, SLOT(selectWaypoint(int, int))); + disconnect(this->uas, SIGNAL(primarySpeedChanged(UASInterface*, double, quint64)), + this, SLOT(updatePrimarySpeed(UASInterface*,double,quint64))); + disconnect(this->uas, SIGNAL(gpsSpeedChanged(UASInterface*, double, quint64)), + this, SLOT(updateGPSSpeed(UASInterface*,double,quint64))); + disconnect(this->uas, SIGNAL(climbRateChanged(UASInterface*, double, quint64)), + this,SLOT(updateClimbRate(UASInterface*, double, quint64))); + disconnect(this->uas, SIGNAL(primaryAltitudeChanged(UASInterface*, double, quint64)), + this, SLOT(updatePrimaryAltitude(UASInterface*, double, quint64))); + disconnect(this->uas, SIGNAL(gpsAltitudeChanged(UASInterface*, double, quint64)), + this, SLOT(updateGPSAltitude(UASInterface*, double, quint64))); + disconnect(this->uas, SIGNAL(navigationControllerErrorsChanged(UASInterface*, double, double, double)), + this, SLOT(updateNavigationControllerErrors(UASInterface*, double, double, double))); //disconnect(this->uas, SIGNAL(batteryChanged(UASInterface*, double, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, double, int))); //disconnect(this->uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString))); @@ -314,10 +323,12 @@ void PrimaryFlightDisplay::setActiveUAS(UASInterface* uas) //connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64))); //connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); - connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int))); + //connect(uas, SIGNAL(waypointSelected(int,int)), this, + // SLOT(selectWaypoint(int, int))); connect(uas, SIGNAL(primarySpeedChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimarySpeed(UASInterface*,double,quint64))); connect(uas, SIGNAL(gpsSpeedChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSSpeed(UASInterface*,double,quint64))); - connect(uas, SIGNAL(climbRateChanged(UASInterface*, double, quint64)), this, SLOT(updateClimbRate(UASInterface*, AltitudeMeasurementSource, double, quint64))); + connect(uas, SIGNAL(climbRateChanged(UASInterface*, double, quint64)), this, + SLOT(updateClimbRate(UASInterface*, double, quint64))); connect(uas, SIGNAL(primaryAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimaryAltitude(UASInterface*, double, quint64))); connect(uas, SIGNAL(gpsAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSAltitude(UASInterface*, double, quint64))); connect(uas, SIGNAL(navigationControllerErrorsChanged(UASInterface*, double, double, double)), this, SLOT(updateNavigationControllerErrors(UASInterface*, double, double, double))); diff --git a/src/ui/QGCConfigView.cc b/src/ui/QGCConfigView.cc index fb8f519b73bd3be644e0827c7ed7c1da95596406..16fc3ecf947380f2ae92499f7733c0817b62ac27 100644 --- a/src/ui/QGCConfigView.cc +++ b/src/ui/QGCConfigView.cc @@ -8,7 +8,7 @@ QGCConfigView::QGCConfigView(QWidget *parent) : QWidget(parent), ui(new Ui::QGCConfigView), - currUAS(NULL) + mav(NULL) { ui->setupUi(this); @@ -26,7 +26,7 @@ QGCConfigView::~QGCConfigView() void QGCConfigView::activeUASChanged(UASInterface* uas) { - if (currUAS == uas) + if (mav == uas) return; //remove all child widgets since they could contain stale data @@ -41,11 +41,13 @@ void QGCConfigView::activeUASChanged(UASInterface* uas) } } - if (NULL != uas) { + mav = uas; + if (NULL != mav) { ui->gridLayout->removeWidget(ui->waitingLabel); ui->waitingLabel->setVisible(false); - switch (uas->getAutopilotType()) { + int autopilotType = mav->getAutopilotType(); + switch (autopilotType) { case MAV_AUTOPILOT_PX4: ui->gridLayout->addWidget(new QGCPX4VehicleConfig()); break; diff --git a/src/ui/QGCConfigView.h b/src/ui/QGCConfigView.h index 182d50c3b714a2c76f1ad523b61ed612eb2539cd..0c1bda9a5757e5c6d04949cd4ee9695df2a1ae4c 100644 --- a/src/ui/QGCConfigView.h +++ b/src/ui/QGCConfigView.h @@ -21,7 +21,7 @@ public slots: private: Ui::QGCConfigView *ui; - UASInterface* currUAS; + UASInterface* mav; }; diff --git a/src/ui/QGCPX4VehicleConfig.cc b/src/ui/QGCPX4VehicleConfig.cc index 3ea93d914b270768f522fc1469afd970e56f0f53..e28569335bbe26f23be31d767acb388a65235954 100644 --- a/src/ui/QGCPX4VehicleConfig.cc +++ b/src/ui/QGCPX4VehicleConfig.cc @@ -13,9 +13,12 @@ #include #include "QGCPX4VehicleConfig.h" -#include "UASManager.h" + #include "QGC.h" +#include "QGCPendingParamWidget.h" #include "QGCToolWidget.h" +#include "UASManager.h" +#include "UASParameterCommsMgr.h" #include "ui_QGCPX4VehicleConfig.h" @@ -80,7 +83,9 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int))); //connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions())); - + //TODO connect buttons here to save/clear actions? + ui->pendingCommitsWidget->init(); + ui->pendingCommitsWidget->update(); //TODO the following methods are not yet implemented @@ -299,7 +304,6 @@ void QGCPX4VehicleConfig::loadQgcConfig(bool primary) } // Generate widgets for the Advanced tab. - left = true; foreach (QString file,vehicledir.entryList(QDir::Files | QDir::NoDotAndDotDot)) { if (file.toLower().endsWith(".qgw")) { @@ -793,9 +797,12 @@ void QGCPX4VehicleConfig::loadConfig() xml.readNext(); } - mav->getParamManager()->setParamInfo(paramTooltips); + if (!paramTooltips.isEmpty()) { + mav->getParamManager()->setParamDescriptions(paramTooltips); + } doneLoadingConfig = true; - mav->requestParameters(); //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished. + //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished. + mav->getParamCommsMgr()->requestParameterList(); } void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) @@ -824,31 +831,28 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) // Disconnect old system disconnect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(remoteControlChannelRawChanged(int,float))); + //TODO use paramCommsMgr instead disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant))); - disconnect(ui->refreshButton,SIGNAL(clicked()),mav,SLOT(requestParameters())); + disconnect(ui->refreshButton,SIGNAL(clicked()), + paramCommsMgr,SLOT(requestParameterList())); // Delete all children from all fixed tabs. - foreach(QWidget* child, ui->generalLeftContents->findChildren()) - { + foreach(QWidget* child, ui->generalLeftContents->findChildren()) { child->deleteLater(); } - foreach(QWidget* child, ui->generalRightContents->findChildren()) - { + foreach(QWidget* child, ui->generalRightContents->findChildren()) { child->deleteLater(); } - foreach(QWidget* child, ui->advanceColumnContents->findChildren()) - { + foreach(QWidget* child, ui->advanceColumnContents->findChildren()) { child->deleteLater(); } - foreach(QWidget* child, ui->sensorContents->findChildren()) - { + foreach(QWidget* child, ui->sensorContents->findChildren()) { child->deleteLater(); } // And then delete any custom tabs - foreach(QWidget* child, additionalTabs) - { + foreach(QWidget* child, additionalTabs) { child->deleteLater(); } additionalTabs.clear(); @@ -864,6 +868,7 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) // Connect new system mav = active; + paramCommsMgr = mav->getParamCommsMgr(); // Reset current state resetCalibrationRC(); @@ -873,26 +878,24 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) chanCount = 0; // Connect new system - connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this, + connect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(remoteControlChannelRawChanged(int,float))); - connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, + connect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant))); - connect(ui->refreshButton, SIGNAL(clicked()), active, SLOT(requestParameters())); + connect(ui->refreshButton, SIGNAL(clicked()), + paramCommsMgr,SLOT(requestParameterList())); - if (systemTypeToParamMap.contains(mav->getSystemTypeName())) - { + if (systemTypeToParamMap.contains(mav->getSystemTypeName())) { paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()]; } - else - { + else { //Indication that we have no meta data for this system type. qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName(); paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()]; } - if (!paramTooltips.isEmpty()) - { - mav->getParamManager()->setParamInfo(paramTooltips); + if (!paramTooltips.isEmpty()) { + mav->getParamManager()->setParamDescriptions(paramTooltips); } qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName(); @@ -910,8 +913,7 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) ui->writeButton->setEnabled(true); ui->loadFileButton->setEnabled(true); ui->saveFileButton->setEnabled(true); - if (mav->getAutopilotTypeName() == "ARDUPILOTMEGA") - { + if (mav->getAutopilotTypeName() == "ARDUPILOTMEGA") { ui->readButton->hide(); ui->writeButton->hide(); } @@ -941,6 +943,7 @@ void QGCPX4VehicleConfig::writeCalibrationRC() // Do not write the RC type, as these values depend on this // active onboard parameter + //TODO consolidate RC param sending in the UAS comms mgr for (unsigned int i = 0; i < chanCount; ++i) { //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i]; @@ -975,26 +978,8 @@ void QGCPX4VehicleConfig::writeCalibrationRC() void QGCPX4VehicleConfig::requestCalibrationRC() { - if (!mav) return; - - QString minTpl("RC%1_MIN"); - QString maxTpl("RC%1_MAX"); - QString trimTpl("RC%1_TRIM"); - QString revTpl("RC%1_REV"); - - // Do not request the RC type, as these values depend on this - // active onboard parameter - - for (unsigned int i = 0; i < chanMax; ++i) - { - mav->requestParameter(0, minTpl.arg(i+1)); - QGC::SLEEP::usleep(5000); - mav->requestParameter(0, trimTpl.arg(i+1)); - QGC::SLEEP::usleep(5000); - mav->requestParameter(0, maxTpl.arg(i+1)); - QGC::SLEEP::usleep(5000); - mav->requestParameter(0, revTpl.arg(i+1)); - QGC::SLEEP::usleep(5000); + if (paramCommsMgr) { + paramCommsMgr->requestRcCalibrationParamsUpdate(); } } @@ -1249,8 +1234,6 @@ void QGCPX4VehicleConfig::handleRcParameterChange(QString parameterName, QVarian void QGCPX4VehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { - Q_UNUSED(uas); - Q_UNUSED(component); if (!doneLoadingConfig) { //We do not want to attempt to generate any UI elements until loading of the config file is complete. //We should re-request params later if needed, that is not implemented yet. diff --git a/src/ui/QGCPX4VehicleConfig.h b/src/ui/QGCPX4VehicleConfig.h index b11d2e60e2b9c3b62f014fed62c5888ab61c20d0..a242fcf9d3d4b9c210b9dcb83edef26a7225f717 100644 --- a/src/ui/QGCPX4VehicleConfig.h +++ b/src/ui/QGCPX4VehicleConfig.h @@ -10,6 +10,8 @@ #include "QGCToolWidget.h" #include "UASInterface.h" +class UASParameterCommsMgr; + namespace Ui { class QGCPX4VehicleConfig; } @@ -159,6 +161,7 @@ protected slots: protected: bool doneLoadingConfig; UASInterface* mav; ///< The current MAV + UASParameterCommsMgr* paramCommsMgr; ///< param comms mgr for the mav static const unsigned int chanMax = 8; ///< Maximum number of channels unsigned int chanCount; ///< Actual channels int rcType; ///< Type of the remote control @@ -184,6 +187,7 @@ protected: QTimer updateTimer; ///< Controls update intervals enum RC_MODE rc_mode; ///< Mode of the remote control, according to usual convention QList toolWidgets; ///< Configurable widgets + QMap toolWidgetsByName; ///< bool calibrationEnabled; ///< calibration mode on / off QMap paramToWidgetMap; ///< Holds the current active MAV's parameter widgets. diff --git a/src/ui/QGCPX4VehicleConfig.ui b/src/ui/QGCPX4VehicleConfig.ui index 8607a55643c540d831a7b0290ace9a4f673e7e58..da0ddfd9b14f9b30ad3c3eb374727e2d1a4551db 100644 --- a/src/ui/QGCPX4VehicleConfig.ui +++ b/src/ui/QGCPX4VehicleConfig.ui @@ -138,7 +138,7 @@ Config - 0 + 3 @@ -1035,8 +1035,8 @@ p, li { white-space: pre-wrap; } 0 0 - 16 - 16 + 597 + 569 @@ -1168,7 +1168,17 @@ p, li { white-space: pre-wrap; } 0 - + + + + 0 + 30 + + + + true + + @@ -1259,6 +1269,12 @@ p, li { white-space: pre-wrap; }
ui/designer/QGCRadioChannelDisplay.h
1 + + QGCPendingParamWidget + QWidget +
/ui/QGCPendingParamWidget.h
+ 1 +
diff --git a/src/ui/QGCParamWidget.cc b/src/ui/QGCParamWidget.cc index 94e1697b52a7502b2d6db2abb84dd6dc412fc8f3..f2fc58073ec42f90a32b32dd621e70f43181399a 100644 --- a/src/ui/QGCParamWidget.cc +++ b/src/ui/QGCParamWidget.cc @@ -27,21 +27,23 @@ This file is part of the QGROUNDCONTROL project */ #include #include -#include -#include -#include +#include +#include #include +#include +#include + #include -#include -#include #include -#include +#include +#include +#include -#include "QGCParamWidget.h" -#include "UASInterface.h" #include "MainWindow.h" -#include #include "QGC.h" +#include "QGCParamWidget.h" +#include "UASInterface.h" +#include "UASParameterCommsMgr.h" /** * @param uas MAV to set the parameters on @@ -49,21 +51,50 @@ This file is part of the QGROUNDCONTROL project */ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : QGCUASParamManager(uas, parent), - components(new QMap()) + componentItems(new QMap()), + updatingParamNameLock("") +{ + +} + +void QGCParamWidget::init() +{ + layoutWidget(); + connectSignalsAndSlots(); + + // Ensure we're receiving the list of params + requestAllParamsUpdate(); +} + +void QGCParamWidget::connectSignalsAndSlots() { - // Load settings - loadSettings(); - // Load default values and tooltips - QString hey(uas->getAutopilotTypeName()); - QString hey2(uas->getSystemTypeName()); - loadParameterInfoCSV(hey, hey2); + // Listen for edits to the tree UI + connect(tree, SIGNAL(itemChanged(QTreeWidgetItem*,int)), + this, SLOT(parameterItemChanged(QTreeWidgetItem*,int))); + // Listen to updated param signals from the data model + connect(paramDataModel, SIGNAL(parameterUpdated(int, QString , QVariant )), + this, SLOT(handleParameterUpdate(int,QString,QVariant))); + + connect(paramDataModel, SIGNAL(pendingParamUpdate(int , const QString&, QVariant , bool )), + this, SLOT(handlePendingParamUpdate(int , const QString& , QVariant, bool ))); + + // Listen for param list reload finished + connect(paramCommsMgr, SIGNAL(parameterListUpToDate()), + this, SLOT(handleParameterListUpToDate())); + + // Listen to communications status messages so we can display them + connect(paramCommsMgr, SIGNAL(parameterStatusMsgUpdated(QString,int)), + this, SLOT(handleParamStatusMsgUpdate(QString , int ))); +} + +void QGCParamWidget::layoutWidget() +{ // Create tree widget tree = new QTreeWidget(this); statusLabel = new QLabel(); statusLabel->setAutoFillBackground(true); - tree->setColumnWidth(70, 30); // Set tree widget as widget onto this component QGridLayout* horizontalLayout; @@ -82,18 +113,18 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : statusLabel->setText(tr("Click refresh to download parameters")); horizontalLayout->addWidget(statusLabel, 1, 0, 1, 3); - // BUTTONS QPushButton* refreshButton = new QPushButton(tr("Get")); refreshButton->setToolTip(tr("Load parameters currently in non-permanent memory of aircraft.")); refreshButton->setWhatsThis(tr("Load parameters currently in non-permanent memory of aircraft.")); - connect(refreshButton, SIGNAL(clicked()), this, SLOT(requestParameterList())); + connect(refreshButton, SIGNAL(clicked()), this, SLOT(requestAllParamsUpdate())); horizontalLayout->addWidget(refreshButton, 2, 0); QPushButton* setButton = new QPushButton(tr("Set")); setButton->setToolTip(tr("Set current parameters in non-permanent onboard memory")); setButton->setWhatsThis(tr("Set current parameters in non-permanent onboard memory")); - connect(setButton, SIGNAL(clicked()), this, SLOT(setParameters())); + connect(setButton, SIGNAL(clicked()), + this, SLOT(sendPendingParameters())); horizontalLayout->addWidget(setButton, 2, 1); QPushButton* writeButton = new QPushButton(tr("Write (ROM)")); @@ -105,13 +136,13 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : QPushButton* loadFileButton = new QPushButton(tr("Load File")); loadFileButton->setToolTip(tr("Load parameters from a file on this computer in the view. To write them to the aircraft, use transmit after loading them.")); loadFileButton->setWhatsThis(tr("Load parameters from a file on this computer in the view. To write them to the aircraft, use transmit after loading them.")); - connect(loadFileButton, SIGNAL(clicked()), this, SLOT(loadParameters())); + connect(loadFileButton, SIGNAL(clicked()), this, SLOT(loadParametersFromFile())); horizontalLayout->addWidget(loadFileButton, 3, 0); QPushButton* saveFileButton = new QPushButton(tr("Save File")); saveFileButton->setToolTip(tr("Save parameters in this view to a file on this computer.")); saveFileButton->setWhatsThis(tr("Save parameters in this view to a file on this computer.")); - connect(saveFileButton, SIGNAL(clicked()), this, SLOT(saveParameters())); + connect(saveFileButton, SIGNAL(clicked()), this, SLOT(saveParametersToFile())); horizontalLayout->addWidget(saveFileButton, 3, 1); QPushButton* readButton = new QPushButton(tr("Read (ROM)")); @@ -135,611 +166,297 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : headerItems.append("Value"); tree->setHeaderLabels(headerItems); tree->setColumnCount(2); + tree->setColumnWidth(0,200); + tree->setColumnWidth(1,120); tree->setExpandsOnDoubleClick(true); - // Connect signals/slots - connect(this, SIGNAL(parameterChanged(int,QString,QVariant)), mav, SLOT(setParameter(int,QString,QVariant))); - connect(tree, SIGNAL(itemChanged(QTreeWidgetItem*,int)), this, SLOT(parameterItemChanged(QTreeWidgetItem*,int))); - - // New parameters from UAS - connect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(addParameter(int,int,int,int,QString,QVariant))); - - // Connect retransmission guard - connect(this, SIGNAL(requestParameter(int,QString)), uas, SLOT(requestParameter(int,QString))); - connect(this, SIGNAL(requestParameter(int,int)), uas, SLOT(requestParameter(int,int))); - connect(&retransmissionTimer, SIGNAL(timeout()), this, SLOT(retransmissionGuardTick())); - - // Get parameters - if (uas) requestParameterList(); + tree->setVisible(true); } -void QGCParamWidget::loadSettings() -{ - QSettings settings; - settings.beginGroup("QGC_MAVLINK_PROTOCOL"); - bool ok; - int temp = settings.value("PARAMETER_RETRANSMISSION_TIMEOUT", retransmissionTimeout).toInt(&ok); - if (ok) retransmissionTimeout = temp; - temp = settings.value("PARAMETER_REWRITE_TIMEOUT", rewriteTimeout).toInt(&ok); - if (ok) rewriteTimeout = temp; - settings.endGroup(); -} -void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QString& airframe) +void QGCParamWidget::addComponentItem(int compId, QString compName) { - Q_UNUSED(airframe); - - qDebug() << "ATTEMPTING TO LOAD CSV"; - QDir appDir = QApplication::applicationDirPath(); - appDir.cd("files"); - QString fileName = QString("%1/%2/parameter_tooltips/tooltips.txt").arg(appDir.canonicalPath()).arg(autopilot.toLower()); - QFile paramMetaFile(fileName); + QString compLine = QString("%1 (#%2)").arg(compName).arg(compId); - qDebug() << "AUTOPILOT:" << autopilot; - qDebug() << "FILENAME: " << fileName; + QString ptrStr = QString().sprintf("%8p", this); + qDebug() << "QGCParamWidget" << ptrStr << "addComponentItem:" << compLine; - // Load CSV data - if (!paramMetaFile.open(QIODevice::ReadOnly | QIODevice::Text)) - { - //qDebug() << "COULD NOT OPEN PARAM META INFO FILE:" << fileName; - return; + if (componentItems->contains(compId)) { + // Update existing component item + componentItems->value(compId)->setData(0, Qt::DisplayRole, compLine); + //components->value(component)->setData(1, Qt::DisplayRole, QString::number(component)); + componentItems->value(compId)->setFirstColumnSpanned(true); + } else { + // Add new component item + QStringList list(compLine); + QTreeWidgetItem* compItem = new QTreeWidgetItem(list); + compItem->setFirstColumnSpanned(true); + componentItems->insert(compId, compItem); + // Create parameter grouping for this component and update maps + paramGroups.insert(compId, new QMap()); + tree->addTopLevelItem(compItem); + tree->update(); } - // Extract header + //TODO it seems unlikely that the UI would know about a component before the data model... + paramDataModel->addComponent(compId); - // Read in values - // Find all keys - QTextStream in(¶mMetaFile); +} - // First line is header - // there might be more lines, but the first - // line is assumed to be at least header - QString header = in.readLine(); +void QGCParamWidget::handlePendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending) +{ + // qDebug() << "handlePendingParamUpdate:" << paramName << "with updatingParamNameLock:" << updatingParamNameLock; - // Ignore top-level comment lines - while (header.startsWith('#') || header.startsWith('/') - || header.startsWith('=') || header.startsWith('^')) - { - header = in.readLine(); + if (updatingParamNameLock == paramName) { + //qDebug() << "ignoring bounce from " << paramName; + return; } - - bool charRead = false; - QString separator = ""; - QList sepCandidates; - sepCandidates << '\t'; - sepCandidates << ','; - sepCandidates << ';'; - //sepCandidates << ' '; - sepCandidates << '~'; - sepCandidates << '|'; - - // Iterate until separator is found - // or full header is parsed - for (int i = 0; i < header.length(); i++) - { - if (sepCandidates.contains(header.at(i))) - { - // Separator found - if (charRead) - { - separator += header[i]; - } - } - else - { - // Char found - charRead = true; - // If the separator is not empty, this char - // has been read after a separator, so detection - // is now complete - if (separator != "") break; - } + else { + updatingParamNameLock = paramName; } - bool stripFirstSeparator = false; - bool stripLastSeparator = false; - - // Figure out if the lines start with the separator (e.g. wiki syntax) - if (header.startsWith(separator)) stripFirstSeparator = true; - - // Figure out if the lines end with the separator (e.g. wiki syntax) - if (header.endsWith(separator)) stripLastSeparator = true; - - QString out = separator; - out.replace("\t", ""); - //qDebug() << " Separator: \"" << out << "\""; - //qDebug() << "READING CSV:" << header; - - - // Read data - while (!in.atEnd()) - { - QString line = in.readLine(); + QTreeWidgetItem* paramItem = updateParameterDisplay(compId,paramName,value); + if (isPending) { + paramItem->setBackground(0, QBrush(QColor(QGC::colorOrange))); + paramItem->setBackground(1, QBrush(QColor(QGC::colorOrange))); + } + else { + paramItem->setBackground(0, Qt::NoBrush); + paramItem->setBackground(1, Qt::NoBrush); + } - //qDebug() << "LINE PRE-STRIP" << line; + updatingParamNameLock.clear(); - // Strip separtors if necessary - if (stripFirstSeparator) line.remove(0, separator.length()); - if (stripLastSeparator) line.remove(line.length()-separator.length(), line.length()-1); +} - //qDebug() << "LINE POST-STRIP" << line; +void QGCParamWidget::handleParameterUpdate(int compId, const QString& paramName, QVariant value) +{ +// qDebug() << "handlePendingParamUpdate:" << paramName << "with updatingParamNameLock:" << updatingParamNameLock; + if (paramName == updatingParamNameLock) { + qDebug() << "handlePendingParamUpdate ignoring bounce from " << paramName; + return; + } + updatingParamNameLock = paramName; + updateParameterDisplay(compId, paramName, value); + updatingParamNameLock.clear(); +} - // Keep empty parts here - we still have to act on them - QStringList parts = line.split(separator, QString::KeepEmptyParts); - // Each line is: - // variable name, Min, Max, Default, Multiplier, Enabled (0 = no, 1 = yes), Comment +void QGCParamWidget::handleParameterListUpToDate() +{ + //turn off updates while we refresh the entire list + tree->setUpdatesEnabled(false); + //rewrite the component item tree after receiving the full list + QMap*>::iterator i; + QMap*>* onboardParams = paramDataModel->getAllOnboardParams(); - // Fill in min, max and default values - if (parts.count() > 1) - { - // min - paramMin.insert(parts.at(0).trimmed(), parts.at(1).toDouble()); - } - if (parts.count() > 2) - { - // max - paramMax.insert(parts.at(0).trimmed(), parts.at(2).toDouble()); - } - if (parts.count() > 3) - { - // default - paramDefault.insert(parts.at(0).trimmed(), parts.at(3).toDouble()); - } - // IGNORING 4 and 5 for now - if (parts.count() > 6) - { - // tooltip - paramToolTips.insert(parts.at(0).trimmed(), parts.at(6).trimmed()); - qDebug() << "PARAM META:" << parts.at(0).trimmed(); + for (i = onboardParams->begin(); i != onboardParams->end(); ++i) { + int compId = i.key(); + QMap* paramPairs = onboardParams->value(compId); + QMap::iterator j; + for (j = paramPairs->begin(); j != paramPairs->end(); j++) { + updatingParamNameLock = j.key(); + updateParameterDisplay(compId, j.key(),j.value()); + updatingParamNameLock.clear(); } } -} -/** - * @return The MAV of this widget. Unless the MAV object has been destroyed, this - * pointer is never zero. - */ -UASInterface* QGCParamWidget::getUAS() -{ - return mav; + // Expand visual tree + tree->expandItem(tree->topLevelItem(0)); + tree->setUpdatesEnabled(true); + tree->update(); + } -/** - * - * @param uas System which has the component - * @param component id of the component - * @param componentName human friendly name of the component - */ -void QGCParamWidget::addComponent(int uas, int component, QString componentName) +QTreeWidgetItem* QGCParamWidget::findChildWidgetItemForParam(QTreeWidgetItem* parentItem, const QString& paramName) { - Q_UNUSED(uas); - if (components->contains(component)) { - // Update existing - components->value(component)->setData(0, Qt::DisplayRole, QString("%1 (#%2)").arg(componentName).arg(component)); - //components->value(component)->setData(1, Qt::DisplayRole, QString::number(component)); - components->value(component)->setFirstColumnSpanned(true); - } else { - // Add new - QStringList list(QString("%1 (#%2)").arg(componentName).arg(component)); - QTreeWidgetItem* comp = new QTreeWidgetItem(list); - comp->setFirstColumnSpanned(true); - components->insert(component, comp); - // Create grouping and update maps - paramGroups.insert(component, new QMap()); - tree->addTopLevelItem(comp); - tree->update(); - // Create map in parameters - if (!parameters.contains(component)) { - parameters.insert(component, new QMap()); - } - // Create map in changed parameters - if (!changedValues.contains(component)) { - changedValues.insert(component, new QMap()); + QTreeWidgetItem* childItem = NULL; + + for (int i = 0; i < parentItem->childCount(); i++) { + QTreeWidgetItem* child = parentItem->child(i); + QString key = child->data(0, Qt::DisplayRole).toString(); + if (key == paramName) { + childItem = child; + break; } } + + return childItem; } -/** - * @param uas System which has the component - * @param component id of the component - * @param parameterName human friendly name of the parameter - */ -void QGCParamWidget::addParameter(int uas, int component, int paramCount, int paramId, QString parameterName, QVariant value) +QTreeWidgetItem* QGCParamWidget::getParentWidgetItemForParam(int compId, const QString& paramName) { - addParameter(uas, component, parameterName, value); - - // Missing packets list has to be instantiated for all components - if (!transmissionMissingPackets.contains(component)) { - transmissionMissingPackets.insert(component, new QList()); - } - - // List mode is different from single parameter transfers - if (transmissionListMode) { - // Only accept the list size once on the first packet from - // each component - if (!transmissionListSizeKnown.contains(component)) - { - // Mark list size as known - transmissionListSizeKnown.insert(component, true); - - // Mark all parameters as missing - for (int i = 0; i < paramCount; ++i) - { - if (!transmissionMissingPackets.value(component)->contains(i)) - { - transmissionMissingPackets.value(component)->append(i); - } - } + QTreeWidgetItem* parentItem = componentItems->value(compId); - // There is only one transmission timeout for all components - // since components do not manage their transmission, - // the longest timeout is safe for all components. - quint64 thisTransmissionTimeout = QGC::groundTimeMilliseconds() + ((paramCount)*retransmissionTimeout); - if (thisTransmissionTimeout > transmissionTimeout) - { - transmissionTimeout = thisTransmissionTimeout; - } - } + QString splitToken = "_"; + // Check if auto-grouping can work + if (paramName.contains(splitToken)) { + QString parentStr = paramName.section(splitToken, 0, 0, QString::SectionSkipEmpty); + QMap* compParamGroups = paramGroups.value(compId); + if (!compParamGroups->contains(parentStr)) { + // Insert group item + QStringList glist; + glist.append(parentStr); + QTreeWidgetItem* groupItem = new QTreeWidgetItem(glist); - // Start retransmission guard - // or reset timer - setRetransmissionGuardEnabled(true); - } + compParamGroups->insert(parentStr, groupItem); - // Mark this parameter as received in read list - int index = transmissionMissingPackets.value(component)->indexOf(paramId); - // If the MAV sent the parameter without request, it wont be in missing list - if (index != -1) transmissionMissingPackets.value(component)->removeAt(index); - - bool justWritten = false; - bool writeMismatch = false; - //bool lastWritten = false; - // Mark this parameter as received in write ACK list - QMap* map = transmissionMissingWriteAckPackets.value(component); - if (map && map->contains(parameterName)) - { - justWritten = true; - QVariant newval = map->value(parameterName); - if (map->value(parameterName) != value) - { - writeMismatch = true; + // insert new group alphabetized + QList groupKeys = compParamGroups->uniqueKeys(); + int insertIdx = groupKeys.indexOf(parentStr); + componentItems->value(compId)->insertChild(insertIdx,groupItem); } - map->remove(parameterName); - } - - int missCount = 0; - foreach (int key, transmissionMissingPackets.keys()) - { - missCount += transmissionMissingPackets.value(key)->count(); - } - - int missWriteCount = 0; - foreach (int key, transmissionMissingWriteAckPackets.keys()) - { - missWriteCount += transmissionMissingWriteAckPackets.value(key)->count(); - } - if (justWritten && !writeMismatch && missWriteCount == 0) - { - // Just wrote one and count went to 0 - this was the last missing write parameter - statusLabel->setText(tr("SUCCESS: WROTE ALL PARAMETERS")); - QPalette pal = statusLabel->palette(); - pal.setColor(backgroundRole(), QGC::colorGreen); - statusLabel->setPalette(pal); - } else if (justWritten && !writeMismatch) - { - statusLabel->setText(tr("SUCCESS: Wrote %2 (#%1/%4): %3").arg(paramId+1).arg(parameterName).arg(value.toDouble()).arg(paramCount)); - QPalette pal = statusLabel->palette(); - pal.setColor(backgroundRole(), QGC::colorGreen); - statusLabel->setPalette(pal); - } else if (justWritten && writeMismatch) - { - // Mismatch, tell user - QPalette pal = statusLabel->palette(); - pal.setColor(backgroundRole(), QGC::colorRed); - statusLabel->setPalette(pal); - statusLabel->setText(tr("FAILURE: Wrote %1: sent %2 != onboard %3").arg(parameterName).arg(map->value(parameterName).toDouble()).arg(value.toDouble())); + //parent item for this parameter item will be a group widget item + parentItem = compParamGroups->value(parentStr); } - else - { - if (missCount > 0) - { - QPalette pal = statusLabel->palette(); - pal.setColor(backgroundRole(), QGC::colorOrange); - statusLabel->setPalette(pal); - } - else - { - QPalette pal = statusLabel->palette(); - pal.setColor(backgroundRole(), QGC::colorGreen); - statusLabel->setPalette(pal); - } - QString val = QString("%1").arg(value.toFloat(), 5, 'f', 1, QChar(' ')); - //statusLabel->setText(tr("OK: %1 %2 #%3/%4, %5 miss").arg(parameterName).arg(val).arg(paramId+1).arg(paramCount).arg(missCount)); - if (missCount == 0) - { - // Transmission done - QTime time = QTime::currentTime(); - QString timeString = time.toString(); - statusLabel->setText(tr("All received. (updated at %1)").arg(timeString)); - } - else - { - // Transmission in progress - statusLabel->setText(tr("OK: %1 %2 (%3/%4)").arg(parameterName).arg(val).arg(paramCount-missCount).arg(paramCount)); - } + else { + //parent item for this parameter will be the top level (component) widget item + parentItem = componentItems->value(compId); } - // Check if last parameter was received - if (missCount == 0 && missWriteCount == 0) - { - this->transmissionActive = false; - this->transmissionListMode = false; - transmissionListSizeKnown.clear(); - foreach (int key, transmissionMissingPackets.keys()) - { - transmissionMissingPackets.value(key)->clear(); - } - - // Expand visual tree - tree->expandItem(tree->topLevelItem(0)); - } + return parentItem; } -/** - * @param uas System which has the component - * @param component id of the component - * @param parameterName human friendly name of the parameter - */ -void QGCParamWidget::addParameter(int uas, int component, QString parameterName, QVariant value) +QTreeWidgetItem* QGCParamWidget::updateParameterDisplay(int compId, QString parameterName, QVariant value) { - //qDebug() << "PARAM WIDGET GOT PARAM:" << value; - Q_UNUSED(uas); - // Reference to item in tree - QTreeWidgetItem* parameterItem = NULL; - - // Get component - if (!components->contains(component)) - { - // QString componentName; - // switch (component) - // { - // case MAV_COMP_ID_CAMERA: - // componentName = tr("Camera (#%1)").arg(component); - // break; - // case MAV_COMP_ID_IMU: - // componentName = tr("IMU (#%1)").arg(component); - // break; - // default: - // componentName = tr("Component #").arg(component); - // break; - // } - QString componentName = tr("Component #%1").arg(component); - addComponent(uas, component, componentName); - } - - // Replace value in map +// qDebug() << "QGCParamWidget::updateParameterDisplay" << parameterName; - // FIXME - if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName); - parameters.value(component)->insert(parameterName, value); - - - QString splitToken = "_"; - // Check if auto-grouping can work - if (parameterName.contains(splitToken)) - { - QString parent = parameterName.section(splitToken, 0, 0, QString::SectionSkipEmpty); - QMap* compParamGroups = paramGroups.value(component); - if (!compParamGroups->contains(parent)) - { - // Insert group item - QStringList glist; - glist.append(parent); - QTreeWidgetItem* item = new QTreeWidgetItem(glist); - compParamGroups->insert(parent, item); - components->value(component)->addChild(item); - } + // Reference to item in tree + QTreeWidgetItem* paramItem = NULL; - // Append child to group - bool found = false; - QTreeWidgetItem* parentItem = compParamGroups->value(parent); - for (int i = 0; i < parentItem->childCount(); i++) { - QTreeWidgetItem* child = parentItem->child(i); - QString key = child->data(0, Qt::DisplayRole).toString(); - if (key == parameterName) - { - //qDebug() << "UPDATED CHILD"; - parameterItem = child; - if (value.type() == QVariant::Char) - { - parameterItem->setData(1, Qt::DisplayRole, value.toUInt()); - } - else - { - parameterItem->setData(1, Qt::DisplayRole, value); - } - found = true; - } - } + // Add component item if necessary + if (!componentItems->contains(compId)) { + QString componentName = tr("Component #%1").arg(compId); + addComponentItem(compId, componentName); + } - if (!found) - { + //default parent item for this parameter widget item will be the top level component item + QTreeWidgetItem* parentItem = getParentWidgetItemForParam(compId,parameterName); + if (parentItem) { + paramItem = findChildWidgetItemForParam(parentItem,parameterName); + if (!paramItem) { // Insert parameter into map QStringList plist; plist.append(parameterName); // CREATE PARAMETER ITEM - parameterItem = new QTreeWidgetItem(plist); + paramItem = new QTreeWidgetItem(plist); // CONFIGURE PARAMETER ITEM - if (value.type() == QVariant::Char) - { - parameterItem->setData(1, Qt::DisplayRole, value.toUInt()); + if (value.type() == QVariant::Char) { + paramItem->setData(1, Qt::DisplayRole, value.toUInt()); } - else - { - parameterItem->setData(1, Qt::DisplayRole, value); + else { + paramItem->setData(1, Qt::DisplayRole, value); } + paramItem->setFlags(paramItem->flags() | Qt::ItemIsEditable); + + //TODO insert alphabetically + parentItem->addChild(paramItem); + + //only add the tooltip when the parameter item is first added + QString paramDesc = paramDataModel->getParamDescription(parameterName); + if (!paramDesc.isEmpty()) { + QString tooltipFormat; + if (paramDataModel->isParamDefaultKnown(parameterName)) { + tooltipFormat = tr("Default: %1, %2"); + double paramDefValue = paramDataModel->getParamDefault(parameterName); + tooltipFormat = tooltipFormat.arg(paramDefValue).arg(paramDesc); + } + else { + tooltipFormat = paramDesc; + } + paramItem->setToolTip(0, tooltipFormat); + paramItem->setToolTip(1, tooltipFormat); + } + } - compParamGroups->value(parent)->addChild(parameterItem); - parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable); + //update the parameterItem's data + if (value.type() == QVariant::Char) { + paramItem->setData(1, Qt::DisplayRole, value.toUInt()); } - } - else - { - bool found = false; - QTreeWidgetItem* parent = components->value(component); - for (int i = 0; i < parent->childCount(); i++) - { - QTreeWidgetItem* child = parent->child(i); - QString key = child->data(0, Qt::DisplayRole).toString(); - if (key == parameterName) - { - //qDebug() << "UPDATED CHILD"; - parameterItem = child; - parameterItem->setData(1, Qt::DisplayRole, value); - found = true; - } + else { + paramItem->setData(1, Qt::DisplayRole, value); } + } - if (!found) - { - // Insert parameter into map - QStringList plist; - plist.append(parameterName); - // CREATE PARAMETER ITEM - parameterItem = new QTreeWidgetItem(plist); - // CONFIGURE PARAMETER ITEM - parameterItem->setData(1, Qt::DisplayRole, value); + if (paramItem) { + // Reset background color + paramItem->setBackground(0, Qt::NoBrush); + paramItem->setBackground(1, Qt::NoBrush); - components->value(component)->addChild(parameterItem); - parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable); + paramItem->setTextColor(0, QGC::colorDarkWhite); + paramItem->setTextColor(1, QGC::colorDarkWhite); + + if (paramItem == tree->currentItem()) { + //need to unset current item to clear highlighting (green by default) + tree->setCurrentItem(NULL); //clear the selected line } - //tree->expandAll(); - } - // Reset background color - parameterItem->setBackground(0, Qt::NoBrush); - parameterItem->setBackground(1, Qt::NoBrush); - // Add tooltip - QString tooltipFormat; - if (paramDefault.contains(parameterName)) - { - tooltipFormat = tr("Default: %1, %2"); - tooltipFormat = tooltipFormat.arg(paramDefault.value(parameterName, 0.0f)).arg(paramToolTips.value(parameterName, "")); - } - else - { - tooltipFormat = paramToolTips.value(parameterName, ""); + } - parameterItem->setToolTip(0, tooltipFormat); - parameterItem->setToolTip(1, tooltipFormat); + return paramItem; - //tree->update(); - if (changedValues.contains(component)) changedValues.value(component)->remove(parameterName); } -/** - * Send a request to deliver the list of onboard parameters - * to the MAV. - */ -void QGCParamWidget::requestParameterList() + + +void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* paramItem, int column) { - if (!mav) return; - // FIXME This call does not belong here - // Once the comm handling is moved to a new - // Param manager class the settings can be directly - // loaded from MAVLink protocol - loadSettings(); - // End of FIXME - // Clear view and request param list - clear(); - parameters.clear(); - received.clear(); - // Clear transmission state - transmissionListMode = true; - transmissionListSizeKnown.clear(); - foreach (int key, transmissionMissingPackets.keys()) - { - transmissionMissingPackets.value(key)->clear(); - } - transmissionActive = true; + if (paramItem && column > 0) { - // Set status text - statusLabel->setText(tr("Requested param list.. waiting")); + QString key = paramItem->data(0, Qt::DisplayRole).toString(); + //qDebug() << "parameterItemChanged:" << key << "with updatingParamNameLock:" << updatingParamNameLock; - mav->requestParameters(); -} + if (key == updatingParamNameLock) { + //qDebug() << "parameterItemChanged ignoring parameterItemChanged" << key; + return; + } + else { + updatingParamNameLock = key; + } -void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column) -{ - if (current && column > 0) { - QTreeWidgetItem* parent = current->parent(); + QTreeWidgetItem* parent = paramItem->parent(); while (parent->parent() != NULL) { parent = parent->parent(); } // Parent is now top-level component - int key = components->key(parent); - if (!changedValues.contains(key)) { - changedValues.insert(key, new QMap()); - } - QMap* map = changedValues.value(key, NULL); - if (map) { - QString str = current->data(0, Qt::DisplayRole).toString(); - QVariant value = current->data(1, Qt::DisplayRole); + int componentId = componentItems->key(parent); + QVariant value = paramItem->data(1, Qt::DisplayRole); + + + bool pending = paramDataModel->updatePendingParamWithValue(componentId,key,value); + + // If the value will result in an update + if (pending) { // Set parameter on changed list to be transmitted to MAV - QPalette pal = statusLabel->palette(); - pal.setColor(backgroundRole(), QGC::colorOrange); - statusLabel->setPalette(pal); - statusLabel->setText(tr("Transmit pend. %1:%2: %3").arg(key).arg(str).arg(value.toFloat(), 5, 'f', 1, QChar(' '))); - //qDebug() << "PARAM CHANGED: COMP:" << key << "KEY:" << str << "VALUE:" << value; - // Changed values list - if (map->contains(str)) map->remove(str); - map->insert(str, value); - - // Check if the value was numerically changed - if (!parameters.value(key)->contains(str) || parameters.value(key)->value(str, value.toDouble()-1) != value) { - current->setBackground(0, QBrush(QColor(QGC::colorOrange))); - current->setBackground(1, QBrush(QColor(QGC::colorOrange))); - } + statusLabel->setText(tr("Pending: %1:%2: %3").arg(componentId).arg(key).arg(value.toFloat(), 5, 'f', 1, QChar(' '))); - switch ((int)parameters.value(key)->value(str).type()) - { - case QVariant::Int: - { - QVariant fixedValue(value.toInt()); - parameters.value(key)->insert(str, fixedValue); - } - break; - case QVariant::UInt: - { - QVariant fixedValue(value.toUInt()); - parameters.value(key)->insert(str, fixedValue); - } - break; - case QMetaType::Float: - { - QVariant fixedValue(value.toFloat()); - parameters.value(key)->insert(str, fixedValue); - } - break; - case QMetaType::QChar: - { - QVariant fixedValue(QChar((unsigned char)value.toUInt())); - parameters.value(key)->insert(str, fixedValue); - } - break; - default: - qCritical() << "ABORTED PARAM UPDATE, NO VALID QVARIANT TYPE"; - return; - } + paramItem->setBackground(0, QBrush(QColor(QGC::colorOrange))); + paramItem->setBackground(1, QBrush(QColor(QGC::colorOrange))); } + else { + QMap* pendingParams = paramDataModel->getPendingParamsForComponent(componentId); + int pendingCount = pendingParams->count(); + statusLabel->setText(tr("Pending items: %1").arg(pendingCount)); + paramItem->setBackground(0, Qt::NoBrush); + paramItem->setBackground(1, Qt::NoBrush); + } + + + if (paramItem == tree->currentItem()) { + //need to unset current item to clear highlighting (green by default) + tree->setCurrentItem(NULL); //clear the selected line + } + + updatingParamNameLock.clear(); } } -void QGCParamWidget::saveParameters() + + +void QGCParamWidget::saveParametersToFile() { if (!mav) return; QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "./parameters.txt", tr("Parameter File (*.txt)")); @@ -748,53 +465,13 @@ void QGCParamWidget::saveParameters() return; } - QTextStream in(&file); - - in << "# Onboard parameters for system " << mav->getUASName() << "\n"; - in << "#\n"; - in << "# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)\n"; - - // Iterate through all components, through all parameters and emit them - QMap*>::iterator i; - for (i = parameters.begin(); i != parameters.end(); ++i) { - // Iterate through the parameters of the component - int compid = i.key(); - QMap* comp = i.value(); - { - QMap::iterator j; - for (j = comp->begin(); j != comp->end(); ++j) - { - QString paramValue("%1"); - QString paramType("%1"); - switch ((int)j.value().type()) - { - case QVariant::Int: - paramValue = paramValue.arg(j.value().toInt()); - paramType = paramType.arg(MAV_PARAM_TYPE_INT32); - break; - case QVariant::UInt: - paramValue = paramValue.arg(j.value().toUInt()); - paramType = paramType.arg(MAV_PARAM_TYPE_UINT32); - break; - case QMetaType::Float: - // We store parameters as floats, with only 6 digits of precision guaranteed for decimal string conversion - // (see IEEE 754, 32 bit single-precision) - paramValue = paramValue.arg((double)j.value().toFloat(), 25, 'g', 6); - paramType = paramType.arg(MAV_PARAM_TYPE_REAL32); - break; - default: - qCritical() << "ABORTED PARAM WRITE TO FILE, NO VALID QVARIANT TYPE" << j.value(); - return; - } - in << mav->getUASID() << "\t" << compid << "\t" << j.key() << "\t" << paramValue << "\t" << paramType << "\n"; - in.flush(); - } - } - } + QTextStream outstream(&file); + paramDataModel->writeOnboardParamsToStream(outstream,mav->getUASName()); file.close(); } -void QGCParamWidget::loadParameters() + +void QGCParamWidget::loadParametersFromFile() { if (!mav) return; QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Parameter file (*.txt)")); @@ -802,338 +479,29 @@ void QGCParamWidget::loadParameters() if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) return; - bool userWarned = false; - QTextStream in(&file); - while (!in.atEnd()) { - QString line = in.readLine(); - if (!line.startsWith("#")) { - QStringList wpParams = line.split("\t"); - if (wpParams.size() == 5) { - // Only load parameters for right mav - if (!userWarned && (mav->getUASID() != wpParams.at(0).toInt())) { - MainWindow::instance()->showCriticalMessage(tr("Parameter loading warning"), tr("The parameters from the file %1 have been saved from system %2, but the currently selected system has the ID %3. If this is unintentional, please click on to revert to the parameters that are currently onboard").arg(fileName).arg(wpParams.at(0).toInt()).arg(mav->getUASID())); - userWarned = true; - } - - bool changed = false; - int component = wpParams.at(1).toInt(); - QString parameterName = wpParams.at(2); - if (!parameters.contains(component) || - fabs((static_cast(parameters.value(component)->value(parameterName, wpParams.at(3).toDouble()).toDouble())) - (wpParams.at(3).toDouble())) > 2.0f * FLT_EPSILON) { - changed = true; - qDebug() << "Changed" << parameterName << "VAL" << wpParams.at(3).toDouble(); - } - - // Set parameter value - - // Create changed values data structure if necessary - if (changed && !changedValues.contains(wpParams.at(1).toInt())) { - changedValues.insert(wpParams.at(1).toInt(), new QMap()); - } - - // Add to changed values - if (changed && changedValues.value(wpParams.at(1).toInt())->contains(wpParams.at(2))) { - changedValues.value(wpParams.at(1).toInt())->remove(wpParams.at(2)); - } - - switch (wpParams.at(4).toUInt()) - { - case (int)MAV_PARAM_TYPE_REAL32: - addParameter(wpParams.at(0).toInt(), wpParams.at(1).toInt(), wpParams.at(2), wpParams.at(3).toFloat()); - if (changed) { - changedValues.value(wpParams.at(1).toInt())->insert(wpParams.at(2), wpParams.at(3).toFloat()); - setParameter(wpParams.at(1).toInt(), wpParams.at(2), wpParams.at(3).toFloat()); - qDebug() << "FLOAT PARAM CHANGED"; - } - break; - case (int)MAV_PARAM_TYPE_UINT32: - addParameter(wpParams.at(0).toInt(), wpParams.at(1).toInt(), wpParams.at(2), wpParams.at(3).toUInt()); - if (changed) { - changedValues.value(wpParams.at(1).toInt())->insert(wpParams.at(2), wpParams.at(3).toUInt()); - setParameter(wpParams.at(1).toInt(), wpParams.at(2), QVariant(wpParams.at(3).toUInt())); - } - break; - case (int)MAV_PARAM_TYPE_INT32: - addParameter(wpParams.at(0).toInt(), wpParams.at(1).toInt(), wpParams.at(2), wpParams.at(3).toInt()); - if (changed) { - changedValues.value(wpParams.at(1).toInt())->insert(wpParams.at(2), wpParams.at(3).toInt()); - setParameter(wpParams.at(1).toInt(), wpParams.at(2), QVariant(wpParams.at(3).toInt())); - } - break; - default: - qDebug() << "FAILED LOADING PARAM" << wpParams.at(2) << "NO KNOWN DATA TYPE"; - } - - //qDebug() << "MARKING COMP" << wpParams.at(1).toInt() << "PARAM" << wpParams.at(2) << "VALUE" << (float)wpParams.at(3).toDouble() << "AS CHANGED"; - - // Mark in UI - - - } - } - } + paramDataModel->readUpdateParamsFromStream(in); file.close(); - -} - -/** - * Enabling the retransmission guard enables the parameter widget to track - * dropped parameters and to re-request them. This works for both individual - * parameter reads as well for whole list requests. - * - * @param enabled True if retransmission checking should be enabled, false else - */ -void QGCParamWidget::setRetransmissionGuardEnabled(bool enabled) -{ - if (enabled) { - retransmissionTimer.start(retransmissionTimeout); - } else { - retransmissionTimer.stop(); - } } -void QGCParamWidget::retransmissionGuardTick() +void QGCParamWidget::setParameterStatusMsg(const QString& msg) { - if (transmissionActive) { - //qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD ACTIVE, CHECKING FOR DROPS.."; - - // Check for timeout - // stop retransmission attempts on timeout - if (QGC::groundTimeMilliseconds() > transmissionTimeout) { - setRetransmissionGuardEnabled(false); - transmissionActive = false; - - // Empty read retransmission list - // Empty write retransmission list - int missingReadCount = 0; - QList readKeys = transmissionMissingPackets.keys(); - foreach (int component, readKeys) { - missingReadCount += transmissionMissingPackets.value(component)->count(); - transmissionMissingPackets.value(component)->clear(); - } - - // Empty write retransmission list - int missingWriteCount = 0; - QList writeKeys = transmissionMissingWriteAckPackets.keys(); - foreach (int component, writeKeys) { - missingWriteCount += transmissionMissingWriteAckPackets.value(component)->count(); - transmissionMissingWriteAckPackets.value(component)->clear(); - } - statusLabel->setText(tr("TIMEOUT! MISSING: %1 read, %2 write.").arg(missingReadCount).arg(missingWriteCount)); - } - - // Re-request at maximum retransmissionBurstRequestSize parameters at once - // to prevent link flooding - QMap*>::iterator i; - for (i = parameters.begin(); i != parameters.end(); ++i) { - // Iterate through the parameters of the component - int component = i.key(); - // Request n parameters from this component (at maximum) - QList * paramList = transmissionMissingPackets.value(component, NULL); - if (paramList) { - int count = 0; - foreach (int id, *paramList) { - if (count < retransmissionBurstRequestSize) { - //qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD REQUESTS RETRANSMISSION OF PARAM #" << id << "FROM COMPONENT #" << component; - emit requestParameter(component, id); - statusLabel->setText(tr("Requested retransmission of #%1").arg(id+1)); - count++; - } else { - break; - } - } - } - } - - // Re-request at maximum retransmissionBurstRequestSize parameters at once - // to prevent write-request link flooding - // Empty write retransmission list - QList writeKeys = transmissionMissingWriteAckPackets.keys(); - foreach (int component, writeKeys) { - int count = 0; - QMap * missingParams = transmissionMissingWriteAckPackets.value(component); - foreach (QString key, missingParams->keys()) { - if (count < retransmissionBurstRequestSize) { - // Re-request write operation - QVariant value = missingParams->value(key); - switch ((int)parameters.value(component)->value(key).type()) - { - case QVariant::Int: - { - QVariant fixedValue(value.toInt()); - emit parameterChanged(component, key, fixedValue); - } - break; - case QVariant::UInt: - { - QVariant fixedValue(value.toUInt()); - emit parameterChanged(component, key, fixedValue); - } - break; - case QMetaType::Float: - { - QVariant fixedValue(value.toFloat()); - emit parameterChanged(component, key, fixedValue); - } - break; - default: - //qCritical() << "ABORTED PARAM RETRANSMISSION, NO VALID QVARIANT TYPE"; - return; - } - statusLabel->setText(tr("Requested rewrite of: %1: %2").arg(key).arg(missingParams->value(key).toDouble())); - count++; - } else { - break; - } - } - } - } else { - //qDebug() << __FILE__ << __LINE__ << "STOPPING RETRANSMISSION GUARD GRACEFULLY"; - setRetransmissionGuardEnabled(false); - } -} - - -/** - * The .. signal is emitted - */ -void QGCParamWidget::requestParameterUpdate(int component, const QString& parameter) -{ - if (mav) mav->requestParameter(component, parameter); + statusLabel->setText(msg); } - -/** - * @param component the subsystem which has the parameter - * @param parameterName name of the parameter, as delivered by the system - * @param value value of the parameter - */ -void QGCParamWidget::setParameter(int component, QString parameterName, QVariant value) +void QGCParamWidget::requestAllParamsUpdate() { - if (paramMin.contains(parameterName) && value.toDouble() < paramMin.value(parameterName)) - { - statusLabel->setText(tr("REJ. %1 < min").arg(value.toDouble())); - return; - } - if (paramMax.contains(parameterName) && value.toDouble() > paramMax.value(parameterName)) - { - statusLabel->setText(tr("REJ. %1 > max").arg(value.toDouble())); - return; - } - if (parameters.value(component)->value(parameterName) == value) - { - statusLabel->setText(tr("REJ. %1 > max").arg(value.toDouble())); - return; - } - - switch ((int)parameters.value(component)->value(parameterName).type()) - { - case QVariant::Char: - { - QVariant fixedValue(QChar((unsigned char)value.toInt())); - emit parameterChanged(component, parameterName, fixedValue); - //qDebug() << "PARAM WIDGET SENT:" << fixedValue; - } - break; - case QVariant::Int: - { - QVariant fixedValue(value.toInt()); - emit parameterChanged(component, parameterName, fixedValue); - //qDebug() << "PARAM WIDGET SENT:" << fixedValue; - } - break; - case QVariant::UInt: - { - QVariant fixedValue(value.toUInt()); - emit parameterChanged(component, parameterName, fixedValue); - //qDebug() << "PARAM WIDGET SENT:" << fixedValue; - } - break; - case QMetaType::Float: - { - QVariant fixedValue(value.toFloat()); - emit parameterChanged(component, parameterName, fixedValue); - //qDebug() << "PARAM WIDGET SENT:" << fixedValue; - } - break; - default: - qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE"; + if (!mav) { return; } - // Wait for parameter to be written back - // mark it therefore as missing - if (!transmissionMissingWriteAckPackets.contains(component)) - { - transmissionMissingWriteAckPackets.insert(component, new QMap()); - } - - // Insert it in missing write ACK list - transmissionMissingWriteAckPackets.value(component)->insert(parameterName, value); - - // Set timeouts - if (transmissionActive) - { - transmissionTimeout += rewriteTimeout; - } - else - { - quint64 newTransmissionTimeout = QGC::groundTimeMilliseconds() + rewriteTimeout; - if (newTransmissionTimeout > transmissionTimeout) - { - transmissionTimeout = newTransmissionTimeout; - } - transmissionActive = true; - } + // Clear view and request param list + clear(); - // Enable guard / reset timeouts - setRetransmissionGuardEnabled(true); + requestParameterList(); } -/** - * Set all parameter in the parameter tree on the MAV - */ -void QGCParamWidget::setParameters() -{ - // Iterate through all components, through all parameters and emit them - int parametersSent = 0; - QMap*>::iterator i; - for (i = changedValues.begin(); i != changedValues.end(); ++i) { - // Iterate through the parameters of the component - int compid = i.key(); - QMap* comp = i.value(); - { - QMap::iterator j; - for (j = comp->begin(); j != comp->end(); ++j) { - setParameter(compid, j.key(), j.value()); - parametersSent++; - } - } - } - // Change transmission status if necessary - if (parametersSent == 0) { - statusLabel->setText(tr("No transmission: No changed values.")); - } else { - statusLabel->setText(tr("Transmitting %1 parameters.").arg(parametersSent)); - // Set timeouts - if (transmissionActive) - { - transmissionTimeout += parametersSent*rewriteTimeout; - } - else - { - transmissionActive = true; - quint64 newTransmissionTimeout = QGC::groundTimeMilliseconds() + parametersSent*rewriteTimeout; - if (newTransmissionTimeout > transmissionTimeout) { - transmissionTimeout = newTransmissionTimeout; - } - } - // Enable guard - setRetransmissionGuardEnabled(true); - } -} /** * Write the current onboard parameters from RAM into @@ -1141,39 +509,23 @@ void QGCParamWidget::setParameters() */ void QGCParamWidget::writeParameters() { - int changedParamCount = 0; - - QMap*>::iterator i; - for (i = changedValues.begin(); i != changedValues.end(); ++i) - { - // Iterate through the parameters of the component - QMap* comp = i.value(); - { - QMap::iterator j; - for (j = comp->begin(); j != comp->end(); ++j) - { - changedParamCount++; - } - } - } + int changedParamCount = paramDataModel->countPendingParams(); - if (changedParamCount > 0) - { + if (changedParamCount > 0) { QMessageBox msgBox; msgBox.setText(tr("There are locally changed parameters. Please transmit them first () or update them with the onboard values () before storing onboard from RAM to ROM.")); msgBox.exec(); } - else - { - if (!mav) return; - mav->writeParametersToStorage(); + else { + paramCommsMgr->writeParamsToPersistentStorage(); } } + void QGCParamWidget::readParameters() { if (!mav) return; - mav->readParametersFromStorage(); + mav->readParametersFromStorage(); //TODO use data model / mgr instead? } /** @@ -1182,5 +534,22 @@ void QGCParamWidget::readParameters() void QGCParamWidget::clear() { tree->clear(); - components->clear(); + componentItems->clear(); +} + +void QGCParamWidget::handleParamStatusMsgUpdate(QString msg, int level) +{ + QColor bgColor = QGC::colorGreen; + if ((int)UASParameterCommsMgr::ParamCommsStatusLevel_Warning == level) { + bgColor = QGC::colorOrange; + } + else if ((int)UASParameterCommsMgr::ParamCommsStatusLevel_Error == level) { + bgColor = QGC::colorRed; + } + + QPalette pal = statusLabel->palette(); + pal.setColor(backgroundRole(), bgColor); + statusLabel->setPalette(pal); + statusLabel->setText(msg); + } diff --git a/src/ui/QGCParamWidget.h b/src/ui/QGCParamWidget.h index f62227d015ddc7079443ea4e3c5fe31182c52a2e..f23a627d339ac20cd5dc1d4310f736365e4ce2b3 100644 --- a/src/ui/QGCParamWidget.h +++ b/src/ui/QGCParamWidget.h @@ -48,40 +48,39 @@ class QGCParamWidget : public QGCUASParamManager Q_OBJECT public: QGCParamWidget(UASInterface* uas, QWidget *parent = 0); - /** @brief Get the UAS of this widget */ - UASInterface* getUAS(); - - bool isParamMinKnown(const QString& param) { return paramMin.contains(param); } - bool isParamMaxKnown(const QString& param) { return paramMax.contains(param); } - bool isParamDefaultKnown(const QString& param) { return paramDefault.contains(param); } - double getParamMin(const QString& param) { return paramMin.value(param, 0.0f); } - double getParamMax(const QString& param) { return paramMax.value(param, 0.0f); } - double getParamDefault(const QString& param) { return paramDefault.value(param, 0.0f); } - QString getParamInfo(const QString& param) { return paramToolTips.value(param, ""); } - void setParamInfo(const QMap& param) { paramToolTips = param; } + virtual void init(); ///< Two-stage construction: initialize the object + +protected: + virtual void setParameterStatusMsg(const QString& msg); + virtual void layoutWidget();///< Layout the appearance of this widget + virtual void connectSignalsAndSlots();///< Connect signals/slots as needed + virtual QTreeWidgetItem* getParentWidgetItemForParam(int compId, const QString& paramName); + virtual QTreeWidgetItem* findChildWidgetItemForParam(QTreeWidgetItem* parentItem, const QString& paramName); + signals: - /** @brief A parameter was changed in the widget, NOT onboard */ - //void parameterChanged(int component, QString parametername, float value); // defined in QGCUASParamManager already - /** @brief Request a single parameter */ - void requestParameter(int component, int parameter); - /** @brief Request a single parameter by name */ - void requestParameter(int component, const QString& parameter); + + public slots: - /** @brief Add a component to the list */ - void addComponent(int uas, int component, QString componentName); - /** @brief Add a parameter to the list with retransmission / safety checks */ - void addParameter(int uas, int component, int paramCount, int paramId, QString parameterName, QVariant value); - /** @brief Add a parameter to the list */ - void addParameter(int uas, int component, QString parameterName, QVariant value); + /** @brief Add a component to the list + * @param compId Component id of the component + * @param compName Human friendly name of the component + */ + void addComponentItem(int compId, QString compName); + + + virtual void handleParameterUpdate(int component,const QString& parameterName, QVariant value); + virtual void handlePendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending); + + virtual void handleParameterListUpToDate(); + + virtual void handleParamStatusMsgUpdate(QString msg, int level); + + /** @brief Ensure that view of parameter matches data in the model */ + QTreeWidgetItem* updateParameterDisplay(int component, QString parameterName, QVariant value); /** @brief Request list of parameters from MAV */ - void requestParameterList(); - /** @brief Request one single parameter */ - void requestParameterUpdate(int component, const QString& parameter); - /** @brief Set one parameter, changes value in RAM of MAV */ - void setParameter(int component, QString parameterName, QVariant value); - /** @brief Set all parameters, changes the value in RAM of MAV */ - void setParameters(); + void requestAllParamsUpdate(); + /** @brief Write the current parameters to permanent storage (EEPROM/HDD) */ void writeParameters(); /** @brief Read the parameters from permanent storage to RAM */ @@ -92,32 +91,19 @@ public slots: void parameterItemChanged(QTreeWidgetItem* prev, int column); /** @brief Store parameters to a file */ - void saveParameters(); + void saveParametersToFile(); /** @brief Load parameters from a file */ - void loadParameters(); + void loadParametersFromFile(); + - /** @brief Check for missing parameters */ - void retransmissionGuardTick(); protected: QTreeWidget* tree; ///< The parameter tree - QLabel* statusLabel; ///< Parameter transmission label - QMap* components; ///< The list of components - QMap* > paramGroups; ///< Parameter groups - - // Tooltip data structures - QMap paramToolTips; ///< Tooltip values - // Min / Default / Max data structures - QMap paramMin; ///< Minimum param values - QMap paramDefault; ///< Default param values - QMap paramMax; ///< Minimum param values - - /** @brief Activate / deactivate parameter retransmission */ - void setRetransmissionGuardEnabled(bool enabled); - /** @brief Load settings */ - void loadSettings(); - /** @brief Load meta information from CSV */ - void loadParameterInfoCSV(const QString& autopilot, const QString& airframe); + QLabel* statusLabel; ///< User-facing parameter status label + QMap* componentItems; ///< The tree of component items, stored by component ID + QMap* > paramGroups; ///< Parameter groups to organize component items + QString updatingParamNameLock; ///< Name of param currently being updated-- used for reducing echo on param change + }; #endif // QGCPARAMWIDGET_H diff --git a/src/ui/QGCPendingParamWidget.cc b/src/ui/QGCPendingParamWidget.cc new file mode 100644 index 0000000000000000000000000000000000000000..57ee57d5dba204f2967bceff05fa828ecce3209a --- /dev/null +++ b/src/ui/QGCPendingParamWidget.cc @@ -0,0 +1,62 @@ +#include "QGCPendingParamWidget.h" + +#include "UASManager.h" +#include "UASParameterCommsMgr.h" + + +QGCPendingParamWidget::QGCPendingParamWidget(QObject *parent) : + QGCParamWidget(UASManager::instance()->getActiveUAS(),(QWidget*)parent) +{ +} + + +void QGCPendingParamWidget::init() +{ + //we override a lot of the super's init methods + layoutWidget(); + connectSignalsAndSlots(); + + //don't request update params here...assume that everything we need is in the data model +} + +void QGCPendingParamWidget::connectSignalsAndSlots() +{ + // Listing for pending list update + connect(paramDataModel, SIGNAL(pendingParamUpdate(int , const QString&, QVariant , bool )), + this, SLOT(handlePendingParamUpdate(int , const QString& , QVariant, bool ))); + + // Listen to communications status messages so we can display them + connect(paramCommsMgr, SIGNAL(parameterStatusMsgUpdated(QString,int)), + this, SLOT(handleParamStatusMsgUpdate(QString , int ))); +} + +void QGCPendingParamWidget::handlePendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending) +{ + // qDebug() << "handlePendingParamUpdate:" << paramName << "with updatingParamNameLock:" << updatingParamNameLock; + + if (updatingParamNameLock == paramName) { + //qDebug() << "ignoring bounce from " << paramName; + return; + } + else { + updatingParamNameLock = paramName; + } + + QTreeWidgetItem* paramItem = updateParameterDisplay(compId,paramName,value); + + if (isPending) { + QTreeWidgetItem* paramItem = updateParameterDisplay(compId,paramName,value); + paramItem->setFlags(paramItem->flags() & ~Qt::ItemIsEditable); //disallow editing + paramItem->setBackground(0, QBrush(QColor(QGC::colorOrange))); + paramItem->setBackground(1, QBrush(QColor(QGC::colorOrange))); + tree->expandAll(); + } + else { + //we don't display non-pending items + paramItem->parent()->removeChild(paramItem); + } + + updatingParamNameLock.clear(); + +} + diff --git a/src/ui/QGCPendingParamWidget.h b/src/ui/QGCPendingParamWidget.h new file mode 100644 index 0000000000000000000000000000000000000000..4c6e7370c45419d3748f2747766848de0688f572 --- /dev/null +++ b/src/ui/QGCPendingParamWidget.h @@ -0,0 +1,27 @@ +#ifndef QGCPENDINGPARAMWIDGET_H +#define QGCPENDINGPARAMWIDGET_H + + +#include "QGCParamWidget.h" + +class QGCPendingParamWidget : public QGCParamWidget +{ + Q_OBJECT + +public: + explicit QGCPendingParamWidget(QObject* parent); + virtual void init(); ///< Two-stage construction: initialize the object + +protected: + virtual void connectSignalsAndSlots(); + + + +signals: + +public slots: + virtual void handlePendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending); + +}; + +#endif // QGCPENDINGPARAMWIDGET_H diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc index d94076dbd48b464a9384f6e40741c781a87be03e..2aa2ead2e6725bc5b138851337a6d4fee0996554 100644 --- a/src/ui/QGCVehicleConfig.cc +++ b/src/ui/QGCVehicleConfig.cc @@ -13,9 +13,11 @@ #include #include "QGCVehicleConfig.h" -#include "UASManager.h" + #include "QGC.h" #include "QGCToolWidget.h" +#include "UASManager.h" +#include "UASParameterCommsMgr.h" #include "ui_QGCVehicleConfig.h" QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : @@ -786,9 +788,10 @@ void QGCVehicleConfig::loadConfig() xml.readNext(); } - mav->getParamManager()->setParamInfo(paramTooltips); + mav->getParamManager()->setParamDescriptions(paramTooltips); doneLoadingConfig = true; - mav->requestParameters(); //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished. + //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished. + mav->getParamCommsMgr()->requestParameterList(); } void QGCVehicleConfig::setActiveUAS(UASInterface* active) @@ -888,7 +891,7 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) if (!paramTooltips.isEmpty()) { - mav->getParamManager()->setParamInfo(paramTooltips); + mav->getParamManager()->setParamDescriptions(paramTooltips); } qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName(); @@ -937,6 +940,7 @@ void QGCVehicleConfig::writeCalibrationRC() // Do not write the RC type, as these values depend on this // active onboard parameter + //TODO consolidate RC param sending in the UAS comms mgr for (unsigned int i = 0; i < chanCount; ++i) { //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i]; @@ -971,26 +975,8 @@ void QGCVehicleConfig::writeCalibrationRC() void QGCVehicleConfig::requestCalibrationRC() { - if (!mav) return; - - QString minTpl("RC%1_MIN"); - QString maxTpl("RC%1_MAX"); - QString trimTpl("RC%1_TRIM"); - QString revTpl("RC%1_REV"); - - // Do not request the RC type, as these values depend on this - // active onboard parameter - - for (unsigned int i = 0; i < chanMax; ++i) - { - mav->requestParameter(0, minTpl.arg(i+1)); - QGC::SLEEP::usleep(5000); - mav->requestParameter(0, trimTpl.arg(i+1)); - QGC::SLEEP::usleep(5000); - mav->requestParameter(0, maxTpl.arg(i+1)); - QGC::SLEEP::usleep(5000); - mav->requestParameter(0, revTpl.arg(i+1)); - QGC::SLEEP::usleep(5000); + if (mav) { + mav->getParamCommsMgr()->requestRcCalibrationParamsUpdate(); } } diff --git a/src/ui/designer/QGCComboBox.cc b/src/ui/designer/QGCComboBox.cc index 21d86f67954059323952d6038c11c023e9f5130b..01ca3881b888730de03ab424bcfd9dce6f3a8269 100644 --- a/src/ui/designer/QGCComboBox.cc +++ b/src/ui/designer/QGCComboBox.cc @@ -48,7 +48,7 @@ QGCComboBox::QGCComboBox(QWidget *parent) : connect(ui->editRemoveItemButton,SIGNAL(clicked()),this,SLOT(delButtonClicked())); // Sending actions - connect(ui->writeButton, SIGNAL(clicked()), this, SLOT(sendParameter())); + connect(ui->writeButton, SIGNAL(clicked()), this, SLOT(setParamPending())); connect(ui->editSelectComponentComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectComponent(int))); connect(ui->editSelectParamComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectParameter(int))); //connect(ui->valueSlider, SIGNAL(valueChanged(int)), this, SLOT(setSliderValue(int))); @@ -108,15 +108,14 @@ void QGCComboBox::setActiveUAS(UASInterface* activeUas) // Update current param value //requestParameter(); // Set param info - QString text = uas->getParamManager()->getParamInfo(parameterName); - if (text != "") - { + + QString text = uas->getParamDataModel()->getParamDescription(parameterName); + if (!text.isEmpty()) { ui->infoLabel->setToolTip(text); ui->infoLabel->show(); } // Force-uncheck and hide label if no description is available - if (ui->editInfoCheckBox->isChecked()) - { + if (ui->editInfoCheckBox->isChecked()) { showInfo((text.length() > 0)); } } @@ -147,27 +146,21 @@ void QGCComboBox::selectParameter(int paramIndex) parameterName = ui->editSelectParamComboBox->itemText(paramIndex); // Update min and max values if available - if (uas) - { - if (uas->getParamManager()) - { - // Current value - //uas->getParamManager()->requestParameterUpdate(component, parameterName); - + if (uas) { + UASParameterDataModel* dataModel = uas->getParamDataModel(); + if (dataModel) { // Minimum - if (uas->getParamManager()->isParamMinKnown(parameterName)) - { - parameterMin = uas->getParamManager()->getParamMin(parameterName); + if (dataModel->isParamMinKnown(parameterName)) { + parameterMin = dataModel->getParamMin(parameterName); } // Maximum - if (uas->getParamManager()->isParamMaxKnown(parameterName)) - { - parameterMax = uas->getParamManager()->getParamMax(parameterName); + if (dataModel->isParamMaxKnown(parameterName)) { + parameterMax = dataModel->getParamMax(parameterName); } // Description - QString text = uas->getParamManager()->getParamInfo(parameterName); + QString text = dataModel->getParamDescription(parameterName); //ui->infoLabel->setText(text); showInfo(!(text.length() > 0)); } @@ -240,24 +233,13 @@ void QGCComboBox::endEditMode() emit editingFinished(); } -void QGCComboBox::sendParameter() +void QGCComboBox::setParamPending() { - if (uas) - { - // Set value, param manager handles retransmission - if (uas->getParamManager()) - { - qDebug() << "Sending param:" << parameterName << "to component" << component << "with a value of" << parameterValue; - uas->getParamManager()->setParameter(component, parameterName, parameterValue); - } - else - { - qDebug() << "UAS HAS NO PARAM MANAGER, DOING NOTHING"; - } + if (uas) { + uas->getParamManager()->setPendingParam(component, parameterName, parameterValue); } - else - { - qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING"; + else { + qWarning() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING"; } } diff --git a/src/ui/designer/QGCComboBox.h b/src/ui/designer/QGCComboBox.h index 4c5491580e5c7da5af777354a7a4e03bb675bdb8..ecc71126b5b3bdc976e22abe40979582da5546a7 100644 --- a/src/ui/designer/QGCComboBox.h +++ b/src/ui/designer/QGCComboBox.h @@ -23,8 +23,8 @@ public: public slots: void startEditMode(); void endEditMode(); - /** @brief Send the parameter to the MAV */ - void sendParameter(); + /** @brief Queue parameter for sending to the MAV (add to pending list)*/ + void setParamPending(); /** @brief Update the UI with the new parameter value */ void setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, const QVariant value); void writeSettings(QSettings& settings); diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc index edba2c78cd7bc08e99571a541e711cfeafcf8e5a..54b3bd723ee827c814505ab81ad82a4ae89284f0 100644 --- a/src/ui/designer/QGCParamSlider.cc +++ b/src/ui/designer/QGCParamSlider.cc @@ -47,20 +47,31 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) : connect(ui->editDoneButton, SIGNAL(clicked()), this, SLOT(endEditMode())); // Sending actions - connect(ui->writeButton, SIGNAL(clicked()), this, SLOT(sendParameter())); - connect(ui->editSelectComponentComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectComponent(int))); - connect(ui->editSelectParamComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectParameter(int))); - connect(ui->valueSlider, SIGNAL(valueChanged(int)), this, SLOT(setSliderValue(int))); - connect(ui->doubleValueSpinBox, SIGNAL(valueChanged(double)), this, SLOT(setParamValue(double))); - connect(ui->intValueSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setParamValue(int))); - connect(ui->editNameLabel, SIGNAL(textChanged(QString)), ui->nameLabel, SLOT(setText(QString))); + connect(ui->writeButton, SIGNAL(clicked()), + this, SLOT(setParamPending())); + connect(ui->editSelectComponentComboBox, SIGNAL(currentIndexChanged(int)), + this, SLOT(selectComponent(int))); + connect(ui->editSelectParamComboBox, SIGNAL(currentIndexChanged(int)), + this, SLOT(selectParameter(int))); + connect(ui->valueSlider, SIGNAL(valueChanged(int)), + this, SLOT(setSliderValue(int))); + connect(ui->doubleValueSpinBox, SIGNAL(valueChanged(double)), + this, SLOT(setParamValue(double))); + connect(ui->intValueSpinBox, SIGNAL(valueChanged(int)), + this, SLOT(setParamValue(int))); + connect(ui->editNameLabel, SIGNAL(textChanged(QString)), + ui->nameLabel, SLOT(setText(QString))); connect(ui->readButton, SIGNAL(clicked()), this, SLOT(requestParameter())); - connect(ui->editRefreshParamsButton, SIGNAL(clicked()), this, SLOT(refreshParamList())); - connect(ui->editInfoCheckBox, SIGNAL(clicked(bool)), this, SLOT(showInfo(bool))); + connect(ui->editRefreshParamsButton, SIGNAL(clicked()), + this, SLOT(refreshParamList())); + connect(ui->editInfoCheckBox, SIGNAL(clicked(bool)), + this, SLOT(showInfo(bool))); // connect to self - connect(ui->infoLabel, SIGNAL(released()), this, SLOT(showTooltip())); + connect(ui->infoLabel, SIGNAL(released()), + this, SLOT(showTooltip())); // Set the current UAS if present - connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); + connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), + this, SLOT(setActiveUAS(UASInterface*))); } QGCParamSlider::~QGCParamSlider() @@ -83,8 +94,7 @@ void QGCParamSlider::refreshParamList() { ui->editSelectParamComboBox->setEnabled(true); ui->editSelectComponentComboBox->setEnabled(true); - if (uas) - { + if (uas) { uas->getParamManager()->requestParameterList(); ui->editStatusLabel->setText(tr("Parameter list updating..")); } @@ -92,38 +102,38 @@ void QGCParamSlider::refreshParamList() void QGCParamSlider::setActiveUAS(UASInterface* activeUas) { - if (activeUas) - { - if (uas) - { - disconnect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(setParameterValue(int,int,int,int,QString,QVariant))); - } - // Connect buttons and signals - connect(activeUas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(setParameterValue(int,int,int,int,QString,QVariant)), Qt::UniqueConnection); + if (uas != activeUas) { + if (uas) { + disconnect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), + this, SLOT(setParameterValue(int,int,int,int,QString,QVariant))); + } + if (activeUas) { + connect(activeUas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), + this, SLOT(setParameterValue(int,int,int,int,QString,QVariant)), Qt::UniqueConnection); + } uas = activeUas; - // Update current param value - //requestParameter(); - // Set param info - QString text = uas->getParamManager()->getParamInfo(parameterName); - if (text != "") - { + } + + if (uas && !parameterName.isEmpty()) { + QString text = uas->getParamDataModel()->getParamDescription(parameterName); + if (!text.isEmpty()) { ui->infoLabel->setToolTip(text); ui->infoLabel->show(); } // Force-uncheck and hide label if no description is available - if (ui->editInfoCheckBox->isChecked()) - { + if (ui->editInfoCheckBox->isChecked()) { showInfo((text.length() > 0)); } } + + } void QGCParamSlider::requestParameter() { - if (!parameterName.isEmpty() && uas) - { - uas->getParamManager()->requestParameterUpdate(this->component, this->parameterName); + if (uas && !parameterName.isEmpty()) { + uas->getParamManager()->requestParameterUpdate(component, parameterName); } } @@ -174,34 +184,25 @@ void QGCParamSlider::selectParameter(int paramIndex) { // Set name parameterName = ui->editSelectParamComboBox->itemText(paramIndex); + if (parameterName.isEmpty()) { + return; + } // Update min and max values if available - if (uas) - { - if (uas->getParamManager()) - { - // Current value - //uas->getParamManager()->requestParameterUpdate(component, parameterName); - + if (uas) { + UASParameterDataModel* dataModel = uas->getParamDataModel(); + if (dataModel) { // Minimum - if (uas->getParamManager()->isParamMinKnown(parameterName)) - { - parameterMin = uas->getParamManager()->getParamMin(parameterName); + if (dataModel->isParamMinKnown(parameterName)) { + parameterMin = dataModel->getParamMin(parameterName); ui->editMinSpinBox->setValue(parameterMin); } // Maximum - if (uas->getParamManager()->isParamMaxKnown(parameterName)) - { - parameterMax = uas->getParamManager()->getParamMax(parameterName); + if (dataModel->isParamMaxKnown(parameterName)) { + parameterMax = dataModel->getParamMax(parameterName); ui->editMaxSpinBox->setValue(parameterMax); } - - // Description - //QString text = uas->getParamManager()->getParamInfo(parameterName); - //ui->infoLabel->setText(text); - - //showInfo(!(text.length() > 0)); } } } @@ -257,7 +258,7 @@ void QGCParamSlider::endEditMode() ui->writeButton->show(); ui->readButton->show(); ui->valueSlider->show(); - switch (parameterValue.type()) + switch ((int)parameterValue.type()) { case QVariant::Char: case QVariant::Int: @@ -276,23 +277,13 @@ void QGCParamSlider::endEditMode() emit editingFinished(); } -void QGCParamSlider::sendParameter() +void QGCParamSlider::setParamPending() { - if (uas) - { - // Set value, param manager handles retransmission - if (uas->getParamManager()) - { - uas->getParamManager()->setParameter(component, parameterName, parameterValue); - } - else - { - qDebug() << "UAS HAS NO PARAM MANAGER, DOING NOTHING"; - } + if (uas) { + uas->getParamManager()->setPendingParam(component, parameterName, parameterValue); } - else - { - qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING"; + else { + qWarning() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING"; } } @@ -301,7 +292,7 @@ void QGCParamSlider::setSliderValue(int sliderValue) if (!valueModLock && !valueModLockParam) { valueModLock = true; - switch (parameterValue.type()) + switch ((int)parameterValue.type()) { case QVariant::Char: parameterValue = QVariant(QChar((unsigned char)scaledIntToFloat(sliderValue))); @@ -337,55 +328,48 @@ void QGCParamSlider::setSliderValue(int sliderValue) * @brief parameterName Key/name of the parameter * @brief value Value of the parameter */ -void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, QVariant value) +void QGCParamSlider::setParameterValue(int uasId, int compId, int paramCount, int paramIndex, QString paramName, QVariant value) { Q_UNUSED(paramCount); - if (ui->nameLabel->text() == "Name") - { - ui->nameLabel->setText(parameterName); + if (uasId != this->uas->getUASID()) { + return; + } + + if (ui->nameLabel->text() == "Name") { + ui->nameLabel->setText(paramName); } // Check if this component and parameter are part of the list bool found = false; - for (int i = 0; i< ui->editSelectComponentComboBox->count(); ++i) - { - if (component == ui->editSelectComponentComboBox->itemData(i).toInt()) - { + for (int i = 0; i< ui->editSelectComponentComboBox->count(); ++i) { + if (compId == ui->editSelectComponentComboBox->itemData(i).toInt()) { found = true; } } - if (!found) - { - ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(component), component); + if (!found) { + ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(compId), compId); } // Parameter checking found = false; - for (int i = 0; i < ui->editSelectParamComboBox->count(); ++i) - { - if (parameterName == ui->editSelectParamComboBox->itemText(i)) - { + for (int i = 0; i < ui->editSelectParamComboBox->count(); ++i) { + if (paramName == ui->editSelectParamComboBox->itemText(i)) { found = true; } } - if (!found) - { - ui->editSelectParamComboBox->addItem(parameterName, paramIndex); + if (!found) { + ui->editSelectParamComboBox->addItem(paramName, paramIndex); } - if (visibleParam != "") - { - if (parameterName == visibleParam) - { - if (visibleVal == value.toInt()) - { - this->uas->requestParameter(this->component,this->parameterName); + if (visibleParam != "") { + if (paramName == visibleParam) { + if (visibleVal == value.toInt()) { + uas->getParamManager()->requestParameterUpdate(compId,paramName); visibleEnabled = true; this->show(); } - else - { + else { //Disable the component here. ui->valueSlider->setEnabled(false); ui->intValueSpinBox->setEnabled(false); @@ -396,16 +380,14 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i } } Q_UNUSED(uas); - if (component == this->component && parameterName == this->parameterName) - { - if (!visibleEnabled) - { + if (compId == this->component && paramName == this->parameterName) { + if (!visibleEnabled) { return; } parameterValue = value; ui->valueSlider->setEnabled(true); valueModLockParam = true; - switch (value.type()) + switch ((int)value.type()) { case QVariant::Char: ui->intValueSpinBox->show(); @@ -468,8 +450,7 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i parameterMin = ui->editMinSpinBox->value(); } - if (paramIndex == paramCount - 1) - { + if (paramIndex == paramCount - 1) { ui->editStatusLabel->setText(tr("Complete parameter list received.")); } } diff --git a/src/ui/designer/QGCParamSlider.h b/src/ui/designer/QGCParamSlider.h index 7160cd937ef5e48f7930ab3cb99e448936d68429..3ef78fdf714d26e50b1f2a6e9cbd683b1c876a0c 100644 --- a/src/ui/designer/QGCParamSlider.h +++ b/src/ui/designer/QGCParamSlider.h @@ -23,8 +23,8 @@ public: public slots: void startEditMode(); void endEditMode(); - /** @brief Send the parameter to the MAV */ - void sendParameter(); + /** @brief Queue parameter for sending to the MAV (add to pending list)*/ + void setParamPending(); /** @brief Set the slider value as parameter value */ void setSliderValue(int sliderValue); /** @brief Update the UI with the new parameter value */ diff --git a/src/ui/uas/UASListWidget.cc b/src/ui/uas/UASListWidget.cc index d1cdde02eb62aa7582dc7ad5b1e1c7a74f02d375..2b000d376936e733a5a95a8e00774f1f09d0e33a 100644 --- a/src/ui/uas/UASListWidget.cc +++ b/src/ui/uas/UASListWidget.cc @@ -149,7 +149,7 @@ void UASListWidget::addUAS(UASInterface* uas) QList* x = uas->getLinks(); if (x->size()) { - LinkInterface* li = x->at(0); + LinkInterface* li = x->first(); // Find an existing QGroupBox for this LinkInterface or create a // new one.