From b11fd1d6b4350c5e74594d6b634784405f4e65c8 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 8 Dec 2014 14:22:28 -0800 Subject: [PATCH 1/4] Default qtlogging.ini file is copied if it doesn't exist --- files/QLoggingCategory/qtlogging.ini | 2 ++ qgroundcontrol.qrc | 3 +++ qtlogging.ini | 2 -- src/QGCApplication.cc | 30 ++++++++++++++++++++++++++++++ 4 files changed, 35 insertions(+), 2 deletions(-) create mode 100644 files/QLoggingCategory/qtlogging.ini delete mode 100644 qtlogging.ini diff --git a/files/QLoggingCategory/qtlogging.ini b/files/QLoggingCategory/qtlogging.ini new file mode 100644 index 0000000..c67fdd4 --- /dev/null +++ b/files/QLoggingCategory/qtlogging.ini @@ -0,0 +1,2 @@ +[Rules] +*Log=false diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index dd04adb..d1ba57b 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -231,4 +231,7 @@ src/qgcunittest/MockLink.param + + files/QLoggingCategory/qtlogging.ini + diff --git a/qtlogging.ini b/qtlogging.ini deleted file mode 100644 index c67fdd4..0000000 --- a/qtlogging.ini +++ /dev/null @@ -1,2 +0,0 @@ -[Rules] -*Log=false diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 469bcee..57bb92b 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -92,6 +92,36 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) : Q_ASSERT(_app == NULL); _app = this; + +#ifdef QT_DEBUG + // First thing we want to do is set up the qtlogging.ini file. If it doesn't already exist we copy + // it to the correct location. This way default debug builds will have logging turned off. + + bool loggingDirectoryOk = false; + QDir iniFileLocation(QStandardPaths::writableLocation(QStandardPaths::GenericConfigLocation)); + if (!iniFileLocation.cd("QtProjects")) { + if (!iniFileLocation.mkdir("QtProjects")) { + qDebug() << "Unable to create qtlogging.ini directory" << iniFileLocation.filePath("QtProjects"); + } else { + if (!iniFileLocation.cd("QtProjects")) { + qDebug() << "Unable to access qtlogging.ini directory" << iniFileLocation.filePath("QtProjects");; + } + loggingDirectoryOk = true; + } + } else { + loggingDirectoryOk = true; + } + + if (loggingDirectoryOk) { + qDebug () << iniFileLocation; + if (!iniFileLocation.exists("qtlogging.ini")) { + if (!QFile::copy(":QLoggingCategory/qtlogging.ini", iniFileLocation.filePath("qtlogging.ini"))) { + qDebug() << "Unable to copy qtlogging.ini to" << iniFileLocation; + } + } + } +#endif + // Set application information if (_runningUnitTests) { // We don't want unit tests to use the same QSettings space as the normal app. So we tweak the app From 5a60edb1c627ac5a13019b0d0edae7c218164ac0 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 8 Dec 2014 14:22:52 -0800 Subject: [PATCH 2/4] Use correct parameter list request api --- src/uas/QGCMAVLinkUASFactory.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/uas/QGCMAVLinkUASFactory.cc b/src/uas/QGCMAVLinkUASFactory.cc index 39df612..07bfcf2 100644 --- a/src/uas/QGCMAVLinkUASFactory.cc +++ b/src/uas/QGCMAVLinkUASFactory.cc @@ -79,7 +79,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte uas->addLink(link); // First thing we do with a new UAS is get the parameters - uas->requestParameters(); + uas->getParamManager()->requestParameterList(); // Now add UAS to "official" list, which makes the whole application aware of it UASManager::instance()->addUAS(uas); From 39eb564f6159f80fd9feb9b9a061a2688dcb5634 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 8 Dec 2014 14:25:28 -0800 Subject: [PATCH 3/4] Removed UAS::requestParameters method This removes confusion as to whether you call UAS::requestParameters (incorrect) or QGCUASParamManager::requestParameterList (correct) from client code. --- src/qgcunittest/MockUAS.h | 1 - src/uas/QGCUASParamManager.cc | 2 ++ src/uas/UAS.cc | 10 ---------- src/uas/UAS.h | 3 --- src/uas/UASInterface.h | 2 -- 5 files changed, 2 insertions(+), 16 deletions(-) diff --git a/src/qgcunittest/MockUAS.h b/src/qgcunittest/MockUAS.h index b6bda69..e9a48d9 100644 --- a/src/qgcunittest/MockUAS.h +++ b/src/qgcunittest/MockUAS.h @@ -133,7 +133,6 @@ public slots: virtual void setTargetPosition(float x, float y, float z, float yaw) { Q_UNUSED(x); Q_UNUSED(y); Q_UNUSED(z); Q_UNUSED(yaw); Q_ASSERT(false); }; virtual void setLocalOriginAtCurrentGPSPosition() { Q_ASSERT(false); }; virtual void setHomePosition(double lat, double lon, double alt) { Q_UNUSED(lat); Q_UNUSED(lon); Q_UNUSED(alt); Q_ASSERT(false); }; - virtual void requestParameters() { Q_ASSERT(false); }; virtual void requestParameter(int component, const QString& parameter) { Q_UNUSED(component); Q_UNUSED(parameter); Q_ASSERT(false); }; virtual void writeParametersToStorage() { Q_ASSERT(false); }; virtual void readParametersFromStorage() { Q_ASSERT(false); }; diff --git a/src/uas/QGCUASParamManager.cc b/src/uas/QGCUASParamManager.cc index 7212d9c..f1de5ab 100644 --- a/src/uas/QGCUASParamManager.cc +++ b/src/uas/QGCUASParamManager.cc @@ -217,6 +217,8 @@ void QGCUASParamManager::requestRcCalibrationParamsUpdate() { void QGCUASParamManager::_parameterListUpToDate(void) { + qDebug() << "Emitting parameters ready, count:" << paramDataModel.countOnboardParams(); + _parametersReady = true; emit parameterListUpToDate(); } diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 1e7f16d..29a618e 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1968,16 +1968,6 @@ int UAS::getCommunicationStatus() const return commStatus; } -void UAS::requestParameters() -{ - mavlink_message_t msg; - mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL); - sendMessage(msg); - - QDateTime time = QDateTime::currentDateTime(); - qDebug() << __FILE__ << ":" << __LINE__ << time.toString() << "LOADING PARAM LIST"; -} - void UAS::writeParametersToStorage() { mavlink_message_t msg; diff --git a/src/uas/UAS.h b/src/uas/UAS.h index a359de3..ed203a8 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -830,9 +830,6 @@ public slots: /** @brief Set current mode of operation, e.g. auto or manual, does not check the arming status, for anything else than arming/disarming operations use setMode instead */ void setModeArm(uint8_t newBaseMode, uint32_t newCustomMode); - /** @brief Request all parameters */ - void requestParameters(); - /** @brief Request a single parameter by name */ void requestParameter(int component, const QString& parameter); /** @brief Request a single parameter by index */ diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 2d7beb7..6a6b566 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -315,8 +315,6 @@ public slots: virtual void setLocalOriginAtCurrentGPSPosition() = 0; /** @brief Set world frame origin / home position at this GPS position */ virtual void setHomePosition(double lat, double lon, double alt) = 0; - /** @brief Request all onboard parameters of all components */ - virtual void requestParameters() = 0; /** @brief Request one specific onboard parameter */ virtual void requestParameter(int component, const QString& parameter) = 0; /** @brief Write parameter to permanent storage */ From 3ca1c633b4041863c30c9e9de3a363fd8fda8b53 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 8 Dec 2014 14:26:20 -0800 Subject: [PATCH 4/4] Sends it's own param_request_list message instead of calling us Also added/converted some logging to debug the problem caused by the two parameter request apis. --- src/uas/UASParameterCommsMgr.cc | 47 ++++++++++++++++++++++++++++------------- src/uas/UASParameterCommsMgr.h | 6 +++++- 2 files changed, 37 insertions(+), 16 deletions(-) diff --git a/src/uas/UASParameterCommsMgr.cc b/src/uas/UASParameterCommsMgr.cc index 137c238..ea5aff9 100644 --- a/src/uas/UASParameterCommsMgr.cc +++ b/src/uas/UASParameterCommsMgr.cc @@ -5,11 +5,13 @@ #include "QGCUASParamManagerInterface.h" #include "UASInterface.h" - - +#include "MAVLinkProtocol.h" +#include "MainWindow.h" #define RC_CAL_CHAN_MAX 8 +Q_LOGGING_CATEGORY(UASParameterCommsMgrLog, "UASParameterCommsMgrLog") + UASParameterCommsMgr::UASParameterCommsMgr(QObject *parent) : QObject(parent), lastReceiveTime(0), @@ -67,7 +69,15 @@ void UASParameterCommsMgr::loadParamCommsSettings() settings.endGroup(); } - +void UASParameterCommsMgr::_sendParamRequestListMsg(void) +{ + MAVLinkProtocol* mavlink = MainWindow::instance()->getMAVLink(); + Q_ASSERT(mavlink); + + mavlink_message_t msg; + mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, mav->getUASID(), MAV_COMP_ID_ALL); + mav->sendMessage(msg); +} /** * Send a request to deliver the list of onboard parameters @@ -78,16 +88,20 @@ void UASParameterCommsMgr::requestParameterList() if (!mav) { return; } + if (!transmissionListMode) { + qCDebug(UASParameterCommsMgrLog) << "Requesting full parameter list"; transmissionListMode = true;//TODO eliminate? //we use (compId 0, paramId 0) as indicating all params for the system markReadParamWaiting(0,0); - mav->requestParameters(); + + _sendParamRequestListMsg(); + updateSilenceTimer(); } else { - qDebug() << __FILE__ << __LINE__ << "Ignoring requestParameterList because we're receiving params list"; + qCDebug(UASParameterCommsMgrLog) << "Ignoring requestParameterList because we're receiving params list"; } } @@ -119,7 +133,7 @@ void UASParameterCommsMgr::markWriteParamWaiting(int compId, QString paramName, */ void UASParameterCommsMgr::clearRetransmissionLists(int& missingReadCount, int& missingWriteCount ) { - qDebug() << __FILE__ << __LINE__ << "clearRetransmissionLists"; + qCDebug(UASParameterCommsMgrLog) << "Clearing re-transmission lists"; missingReadCount = 0; QList compIds = readsWaiting.keys(); @@ -192,7 +206,7 @@ void UASParameterCommsMgr::resendReadWriteRequests() qDebug() << "compId " << compId << "readsWaiting:" << missingReadParams->count(); foreach (int paramId, *missingReadParams) { if (0 == paramId && 0 == compId) { - mav->requestParameters(); + _sendParamRequestListMsg(); //don't request any other params individually for this component break; } @@ -203,7 +217,7 @@ void UASParameterCommsMgr::resendReadWriteRequests() requestedReadCount++; } else { - qDebug() << "Throttling read retransmit requests at" << requestedReadCount; + qCDebug(UASParameterCommsMgrLog) << "Throttling read retransmit requests at" << requestedReadCount; break; } } @@ -223,7 +237,7 @@ void UASParameterCommsMgr::resendReadWriteRequests() requestedWriteCount++; } else { - qDebug() << "Throttling write retransmit requests at" << requestedWriteCount; + qCDebug(UASParameterCommsMgrLog) << "Throttling write retransmit requests at" << requestedWriteCount; break; } } @@ -243,7 +257,7 @@ void UASParameterCommsMgr::silenceTimerExpired() { quint64 curTime = QGC::groundTimeMilliseconds(); int elapsed = (int)(curTime - lastSilenceTimerReset); - qDebug() << "silenceTimerExpired elapsed:" << elapsed; + qCDebug(UASParameterCommsMgrLog) << "silenceTimerExpired elapsed:" << elapsed; if (elapsed < silenceTimeout) { //reset the guard timer: it fired prematurely @@ -253,7 +267,7 @@ void UASParameterCommsMgr::silenceTimerExpired() int totalElapsed = (int)(curTime - lastReceiveTime); if (totalElapsed > maxSilenceTimeout) { - qDebug() << "maxSilenceTimeout exceeded: " << totalElapsed; + qCDebug(UASParameterCommsMgrLog) << "maxSilenceTimeout exceeded: " << totalElapsed; int missingReads, missingWrites; clearRetransmissionLists(missingReads,missingWrites); emit _stopSilenceTimer(); // Stop timer on our thread; @@ -299,7 +313,7 @@ void UASParameterCommsMgr::requestRcCalibrationParamsUpdate() } } else { - qDebug() << __FILE__ << __LINE__ << "Ignoring requestRcCalibrationParamsUpdate because we're receiving params list"; + qCDebug(UASParameterCommsMgrLog) << "Ignoring requestRcCalibrationParamsUpdate because we're receiving params list"; } } @@ -377,6 +391,7 @@ void UASParameterCommsMgr::updateSilenceTimer() } else { //all parameters have been received, broadcast to UI + qCDebug(UASParameterCommsMgrLog) << "emitting parameterListUpToDate"; emit parameterListUpToDate(); resetAfterListReceive(); emit _stopSilenceTimer(); // Stop timer on our thread; @@ -396,6 +411,8 @@ void UASParameterCommsMgr::setParameterStatusMsg(const QString& msg, ParamCommsS void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int paramCount, int paramId, QString paramName, QVariant value) { + qCDebug(UASParameterCommsMgrLog) << QString("Received parameter update for: name(%1) count(%2) index(%3)").arg(paramName).arg(paramCount).arg(paramId); + Q_UNUSED(uas); //this object is assigned to one UAS only lastReceiveTime = QGC::groundTimeMilliseconds(); // qDebug() << "compId" << compId << "receivedParameterUpdate:" << paramName; @@ -423,7 +440,7 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para //remove our placeholder read request for all params readsWaiting.value(0)->remove(0); - qDebug() << "Mark all parameters as missing: " << paramCount; + qCDebug(UASParameterCommsMgrLog) << "receivedParameterUpdate: Mark all parameters as missing: " << paramCount; for (int i = 1; i < paramCount; ++i) { //param Id 0 is "all parameters" and not valid compMissingReads->insert(i); } @@ -533,7 +550,7 @@ void UASParameterCommsMgr::sendPendingParameters(bool copyToPersistent, bool for } else { setParameterStatusMsg(tr("Transmitting %1 parameters.").arg(parametersSent)); - qDebug() << "Pending parameters now:" << paramDataModel->countPendingParams(); + qCDebug(UASParameterCommsMgrLog) << "Pending parameters now:" << paramDataModel->countPendingParams(); } @@ -546,7 +563,7 @@ UASParameterCommsMgr::~UASParameterCommsMgr() QString ptrStr; ptrStr.sprintf("%8p", this); - qDebug() << "UASParameterCommsMgr destructor: " << ptrStr ; + qCDebug(UASParameterCommsMgrLog) << "UASParameterCommsMgr destructor: " << ptrStr ; } diff --git a/src/uas/UASParameterCommsMgr.h b/src/uas/UASParameterCommsMgr.h index 20a24bb..bb68ebe 100644 --- a/src/uas/UASParameterCommsMgr.h +++ b/src/uas/UASParameterCommsMgr.h @@ -6,11 +6,12 @@ #include #include #include +#include class UASInterface; class UASParameterDataModel; - +Q_DECLARE_LOGGING_CATEGORY(UASParameterCommsMgrLog) class UASParameterCommsMgr : public QObject { @@ -122,6 +123,9 @@ private slots: /// @brief We signal this to ourselves in order to get timer started/stopped on our own thread. void _startSilenceTimerOnThisThread(void); void _stopSilenceTimerOnThisThread(void); + +private: + void _sendParamRequestListMsg(void); };