Commit c27191b0 authored by Don Gagne's avatar Don Gagne

Merge pull request #1085 from DonLakeFlyer/QLoggingCategory

Better QLoggingCategory support, fixed parameter list request
parents fa69b34c 3ca1c633
...@@ -231,4 +231,7 @@ ...@@ -231,4 +231,7 @@
<qresource prefix="/unittest"> <qresource prefix="/unittest">
<file alias="MockLink.param">src/qgcunittest/MockLink.param</file> <file alias="MockLink.param">src/qgcunittest/MockLink.param</file>
</qresource> </qresource>
<qresource prefix="/QLoggingCategory">
<file alias="qtlogging.ini">files/QLoggingCategory/qtlogging.ini</file>
</qresource>
</RCC> </RCC>
...@@ -92,6 +92,36 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) : ...@@ -92,6 +92,36 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) :
Q_ASSERT(_app == NULL); Q_ASSERT(_app == NULL);
_app = this; _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 // Set application information
if (_runningUnitTests) { if (_runningUnitTests) {
// We don't want unit tests to use the same QSettings space as the normal app. So we tweak the app // We don't want unit tests to use the same QSettings space as the normal app. So we tweak the app
......
...@@ -133,7 +133,6 @@ public slots: ...@@ -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 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 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 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 requestParameter(int component, const QString& parameter) { Q_UNUSED(component); Q_UNUSED(parameter); Q_ASSERT(false); };
virtual void writeParametersToStorage() { Q_ASSERT(false); }; virtual void writeParametersToStorage() { Q_ASSERT(false); };
virtual void readParametersFromStorage() { Q_ASSERT(false); }; virtual void readParametersFromStorage() { Q_ASSERT(false); };
......
...@@ -79,7 +79,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -79,7 +79,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas->addLink(link); uas->addLink(link);
// First thing we do with a new UAS is get the parameters // 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 // Now add UAS to "official" list, which makes the whole application aware of it
UASManager::instance()->addUAS(uas); UASManager::instance()->addUAS(uas);
......
...@@ -217,6 +217,8 @@ void QGCUASParamManager::requestRcCalibrationParamsUpdate() { ...@@ -217,6 +217,8 @@ void QGCUASParamManager::requestRcCalibrationParamsUpdate() {
void QGCUASParamManager::_parameterListUpToDate(void) void QGCUASParamManager::_parameterListUpToDate(void)
{ {
qDebug() << "Emitting parameters ready, count:" << paramDataModel.countOnboardParams();
_parametersReady = true; _parametersReady = true;
emit parameterListUpToDate(); emit parameterListUpToDate();
} }
...@@ -1968,16 +1968,6 @@ int UAS::getCommunicationStatus() const ...@@ -1968,16 +1968,6 @@ int UAS::getCommunicationStatus() const
return commStatus; 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() void UAS::writeParametersToStorage()
{ {
mavlink_message_t msg; mavlink_message_t msg;
......
...@@ -830,9 +830,6 @@ public slots: ...@@ -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 */ /** @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); void setModeArm(uint8_t newBaseMode, uint32_t newCustomMode);
/** @brief Request all parameters */
void requestParameters();
/** @brief Request a single parameter by name */ /** @brief Request a single parameter by name */
void requestParameter(int component, const QString& parameter); void requestParameter(int component, const QString& parameter);
/** @brief Request a single parameter by index */ /** @brief Request a single parameter by index */
......
...@@ -315,8 +315,6 @@ public slots: ...@@ -315,8 +315,6 @@ public slots:
virtual void setLocalOriginAtCurrentGPSPosition() = 0; virtual void setLocalOriginAtCurrentGPSPosition() = 0;
/** @brief Set world frame origin / home position at this GPS position */ /** @brief Set world frame origin / home position at this GPS position */
virtual void setHomePosition(double lat, double lon, double alt) = 0; 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 */ /** @brief Request one specific onboard parameter */
virtual void requestParameter(int component, const QString& parameter) = 0; virtual void requestParameter(int component, const QString& parameter) = 0;
/** @brief Write parameter to permanent storage */ /** @brief Write parameter to permanent storage */
......
...@@ -5,11 +5,13 @@ ...@@ -5,11 +5,13 @@
#include "QGCUASParamManagerInterface.h" #include "QGCUASParamManagerInterface.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "MAVLinkProtocol.h"
#include "MainWindow.h"
#define RC_CAL_CHAN_MAX 8 #define RC_CAL_CHAN_MAX 8
Q_LOGGING_CATEGORY(UASParameterCommsMgrLog, "UASParameterCommsMgrLog")
UASParameterCommsMgr::UASParameterCommsMgr(QObject *parent) : UASParameterCommsMgr::UASParameterCommsMgr(QObject *parent) :
QObject(parent), QObject(parent),
lastReceiveTime(0), lastReceiveTime(0),
...@@ -67,7 +69,15 @@ void UASParameterCommsMgr::loadParamCommsSettings() ...@@ -67,7 +69,15 @@ void UASParameterCommsMgr::loadParamCommsSettings()
settings.endGroup(); 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 * Send a request to deliver the list of onboard parameters
...@@ -78,16 +88,20 @@ void UASParameterCommsMgr::requestParameterList() ...@@ -78,16 +88,20 @@ void UASParameterCommsMgr::requestParameterList()
if (!mav) { if (!mav) {
return; return;
} }
if (!transmissionListMode) { if (!transmissionListMode) {
qCDebug(UASParameterCommsMgrLog) << "Requesting full parameter list";
transmissionListMode = true;//TODO eliminate? transmissionListMode = true;//TODO eliminate?
//we use (compId 0, paramId 0) as indicating all params for the system //we use (compId 0, paramId 0) as indicating all params for the system
markReadParamWaiting(0,0); markReadParamWaiting(0,0);
mav->requestParameters();
_sendParamRequestListMsg();
updateSilenceTimer(); updateSilenceTimer();
} }
else { 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, ...@@ -119,7 +133,7 @@ void UASParameterCommsMgr::markWriteParamWaiting(int compId, QString paramName,
*/ */
void UASParameterCommsMgr::clearRetransmissionLists(int& missingReadCount, int& missingWriteCount ) void UASParameterCommsMgr::clearRetransmissionLists(int& missingReadCount, int& missingWriteCount )
{ {
qDebug() << __FILE__ << __LINE__ << "clearRetransmissionLists"; qCDebug(UASParameterCommsMgrLog) << "Clearing re-transmission lists";
missingReadCount = 0; missingReadCount = 0;
QList<int> compIds = readsWaiting.keys(); QList<int> compIds = readsWaiting.keys();
...@@ -192,7 +206,7 @@ void UASParameterCommsMgr::resendReadWriteRequests() ...@@ -192,7 +206,7 @@ void UASParameterCommsMgr::resendReadWriteRequests()
qDebug() << "compId " << compId << "readsWaiting:" << missingReadParams->count(); qDebug() << "compId " << compId << "readsWaiting:" << missingReadParams->count();
foreach (int paramId, *missingReadParams) { foreach (int paramId, *missingReadParams) {
if (0 == paramId && 0 == compId) { if (0 == paramId && 0 == compId) {
mav->requestParameters(); _sendParamRequestListMsg();
//don't request any other params individually for this component //don't request any other params individually for this component
break; break;
} }
...@@ -203,7 +217,7 @@ void UASParameterCommsMgr::resendReadWriteRequests() ...@@ -203,7 +217,7 @@ void UASParameterCommsMgr::resendReadWriteRequests()
requestedReadCount++; requestedReadCount++;
} }
else { else {
qDebug() << "Throttling read retransmit requests at" << requestedReadCount; qCDebug(UASParameterCommsMgrLog) << "Throttling read retransmit requests at" << requestedReadCount;
break; break;
} }
} }
...@@ -223,7 +237,7 @@ void UASParameterCommsMgr::resendReadWriteRequests() ...@@ -223,7 +237,7 @@ void UASParameterCommsMgr::resendReadWriteRequests()
requestedWriteCount++; requestedWriteCount++;
} }
else { else {
qDebug() << "Throttling write retransmit requests at" << requestedWriteCount; qCDebug(UASParameterCommsMgrLog) << "Throttling write retransmit requests at" << requestedWriteCount;
break; break;
} }
} }
...@@ -243,7 +257,7 @@ void UASParameterCommsMgr::silenceTimerExpired() ...@@ -243,7 +257,7 @@ void UASParameterCommsMgr::silenceTimerExpired()
{ {
quint64 curTime = QGC::groundTimeMilliseconds(); quint64 curTime = QGC::groundTimeMilliseconds();
int elapsed = (int)(curTime - lastSilenceTimerReset); int elapsed = (int)(curTime - lastSilenceTimerReset);
qDebug() << "silenceTimerExpired elapsed:" << elapsed; qCDebug(UASParameterCommsMgrLog) << "silenceTimerExpired elapsed:" << elapsed;
if (elapsed < silenceTimeout) { if (elapsed < silenceTimeout) {
//reset the guard timer: it fired prematurely //reset the guard timer: it fired prematurely
...@@ -253,7 +267,7 @@ void UASParameterCommsMgr::silenceTimerExpired() ...@@ -253,7 +267,7 @@ void UASParameterCommsMgr::silenceTimerExpired()
int totalElapsed = (int)(curTime - lastReceiveTime); int totalElapsed = (int)(curTime - lastReceiveTime);
if (totalElapsed > maxSilenceTimeout) { if (totalElapsed > maxSilenceTimeout) {
qDebug() << "maxSilenceTimeout exceeded: " << totalElapsed; qCDebug(UASParameterCommsMgrLog) << "maxSilenceTimeout exceeded: " << totalElapsed;
int missingReads, missingWrites; int missingReads, missingWrites;
clearRetransmissionLists(missingReads,missingWrites); clearRetransmissionLists(missingReads,missingWrites);
emit _stopSilenceTimer(); // Stop timer on our thread; emit _stopSilenceTimer(); // Stop timer on our thread;
...@@ -299,7 +313,7 @@ void UASParameterCommsMgr::requestRcCalibrationParamsUpdate() ...@@ -299,7 +313,7 @@ void UASParameterCommsMgr::requestRcCalibrationParamsUpdate()
} }
} }
else { 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() ...@@ -377,6 +391,7 @@ void UASParameterCommsMgr::updateSilenceTimer()
} }
else { else {
//all parameters have been received, broadcast to UI //all parameters have been received, broadcast to UI
qCDebug(UASParameterCommsMgrLog) << "emitting parameterListUpToDate";
emit parameterListUpToDate(); emit parameterListUpToDate();
resetAfterListReceive(); resetAfterListReceive();
emit _stopSilenceTimer(); // Stop timer on our thread; emit _stopSilenceTimer(); // Stop timer on our thread;
...@@ -396,6 +411,8 @@ void UASParameterCommsMgr::setParameterStatusMsg(const QString& msg, ParamCommsS ...@@ -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) 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 Q_UNUSED(uas); //this object is assigned to one UAS only
lastReceiveTime = QGC::groundTimeMilliseconds(); lastReceiveTime = QGC::groundTimeMilliseconds();
// qDebug() << "compId" << compId << "receivedParameterUpdate:" << paramName; // qDebug() << "compId" << compId << "receivedParameterUpdate:" << paramName;
...@@ -423,7 +440,7 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para ...@@ -423,7 +440,7 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
//remove our placeholder read request for all params //remove our placeholder read request for all params
readsWaiting.value(0)->remove(0); 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 for (int i = 1; i < paramCount; ++i) { //param Id 0 is "all parameters" and not valid
compMissingReads->insert(i); compMissingReads->insert(i);
} }
...@@ -533,7 +550,7 @@ void UASParameterCommsMgr::sendPendingParameters(bool copyToPersistent, bool for ...@@ -533,7 +550,7 @@ void UASParameterCommsMgr::sendPendingParameters(bool copyToPersistent, bool for
} }
else { else {
setParameterStatusMsg(tr("Transmitting %1 parameters.").arg(parametersSent)); 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() ...@@ -546,7 +563,7 @@ UASParameterCommsMgr::~UASParameterCommsMgr()
QString ptrStr; QString ptrStr;
ptrStr.sprintf("%8p", this); ptrStr.sprintf("%8p", this);
qDebug() << "UASParameterCommsMgr destructor: " << ptrStr ; qCDebug(UASParameterCommsMgrLog) << "UASParameterCommsMgr destructor: " << ptrStr ;
} }
......
...@@ -6,11 +6,12 @@ ...@@ -6,11 +6,12 @@
#include <QTimer> #include <QTimer>
#include <QVariant> #include <QVariant>
#include <QVector> #include <QVector>
#include <QLoggingCategory>
class UASInterface; class UASInterface;
class UASParameterDataModel; class UASParameterDataModel;
Q_DECLARE_LOGGING_CATEGORY(UASParameterCommsMgrLog)
class UASParameterCommsMgr : public QObject class UASParameterCommsMgr : public QObject
{ {
...@@ -122,6 +123,9 @@ private slots: ...@@ -122,6 +123,9 @@ private slots:
/// @brief We signal this to ourselves in order to get timer started/stopped on our own thread. /// @brief We signal this to ourselves in order to get timer started/stopped on our own thread.
void _startSilenceTimerOnThisThread(void); void _startSilenceTimerOnThisThread(void);
void _stopSilenceTimerOnThisThread(void); void _stopSilenceTimerOnThisThread(void);
private:
void _sendParamRequestListMsg(void);
}; };
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment