Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
c27191b0
Commit
c27191b0
authored
Dec 08, 2014
by
Don Gagne
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #1085 from DonLakeFlyer/QLoggingCategory
Better QLoggingCategory support, fixed parameter list request
parents
fa69b34c
3ca1c633
Changes
11
Hide whitespace changes
Inline
Side-by-side
Showing
11 changed files
with
73 additions
and
33 deletions
+73
-33
qtlogging.ini
files/QLoggingCategory/qtlogging.ini
+0
-0
qgroundcontrol.qrc
qgroundcontrol.qrc
+3
-0
QGCApplication.cc
src/QGCApplication.cc
+30
-0
MockUAS.h
src/qgcunittest/MockUAS.h
+0
-1
QGCMAVLinkUASFactory.cc
src/uas/QGCMAVLinkUASFactory.cc
+1
-1
QGCUASParamManager.cc
src/uas/QGCUASParamManager.cc
+2
-0
UAS.cc
src/uas/UAS.cc
+0
-10
UAS.h
src/uas/UAS.h
+0
-3
UASInterface.h
src/uas/UASInterface.h
+0
-2
UASParameterCommsMgr.cc
src/uas/UASParameterCommsMgr.cc
+32
-15
UASParameterCommsMgr.h
src/uas/UASParameterCommsMgr.h
+5
-1
No files found.
qtlogging.ini
→
files/QLoggingCategory/
qtlogging.ini
View file @
c27191b0
File moved
qgroundcontrol.qrc
View file @
c27191b0
...
...
@@ -231,4 +231,7 @@
<qresource prefix="/unittest">
<file alias="MockLink.param">src/qgcunittest/MockLink.param</file>
</qresource>
<qresource prefix="/QLoggingCategory">
<file alias="qtlogging.ini">files/QLoggingCategory/qtlogging.ini</file>
</qresource>
</RCC>
src/QGCApplication.cc
View file @
c27191b0
...
...
@@ -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
...
...
src/qgcunittest/MockUAS.h
View file @
c27191b0
...
...
@@ -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
);
};
...
...
src/uas/QGCMAVLinkUASFactory.cc
View file @
c27191b0
...
...
@@ -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
);
...
...
src/uas/QGCUASParamManager.cc
View file @
c27191b0
...
...
@@ -217,6 +217,8 @@ void QGCUASParamManager::requestRcCalibrationParamsUpdate() {
void
QGCUASParamManager
::
_parameterListUpToDate
(
void
)
{
qDebug
()
<<
"Emitting parameters ready, count:"
<<
paramDataModel
.
countOnboardParams
();
_parametersReady
=
true
;
emit
parameterListUpToDate
();
}
src/uas/UAS.cc
View file @
c27191b0
...
...
@@ -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
;
...
...
src/uas/UAS.h
View file @
c27191b0
...
...
@@ -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 */
...
...
src/uas/UASInterface.h
View file @
c27191b0
...
...
@@ -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 */
...
...
src/uas/UASParameterCommsMgr.cc
View file @
c27191b0
...
...
@@ -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
{
q
Debug
()
<<
__FILE__
<<
__LINE__
<<
"Ignoring requestParameterList because we're receiving params list"
;
q
CDebug
(
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
)
{
q
Debug
()
<<
__FILE__
<<
__LINE__
<<
"clearRetransmissionL
ists"
;
q
CDebug
(
UASParameterCommsMgrLog
)
<<
"Clearing re-transmission l
ists"
;
missingReadCount
=
0
;
QList
<
int
>
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
{
q
Debug
(
)
<<
"Throttling read retransmit requests at"
<<
requestedReadCount
;
q
CDebug
(
UASParameterCommsMgrLog
)
<<
"Throttling read retransmit requests at"
<<
requestedReadCount
;
break
;
}
}
...
...
@@ -223,7 +237,7 @@ void UASParameterCommsMgr::resendReadWriteRequests()
requestedWriteCount
++
;
}
else
{
q
Debug
(
)
<<
"Throttling write retransmit requests at"
<<
requestedWriteCount
;
q
CDebug
(
UASParameterCommsMgrLog
)
<<
"Throttling write retransmit requests at"
<<
requestedWriteCount
;
break
;
}
}
...
...
@@ -243,7 +257,7 @@ void UASParameterCommsMgr::silenceTimerExpired()
{
quint64
curTime
=
QGC
::
groundTimeMilliseconds
();
int
elapsed
=
(
int
)(
curTime
-
lastSilenceTimerReset
);
q
Debug
(
)
<<
"silenceTimerExpired elapsed:"
<<
elapsed
;
q
CDebug
(
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
)
{
q
Debug
(
)
<<
"maxSilenceTimeout exceeded: "
<<
totalElapsed
;
q
CDebug
(
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
{
q
Debug
()
<<
__FILE__
<<
__LINE__
<<
"Ignoring requestRcCalibrationParamsUpdate because we're receiving params list"
;
q
CDebug
(
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
);
q
Debug
()
<<
"
Mark all parameters as missing: "
<<
paramCount
;
q
CDebug
(
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
));
q
Debug
(
)
<<
"Pending parameters now:"
<<
paramDataModel
->
countPendingParams
();
q
CDebug
(
UASParameterCommsMgrLog
)
<<
"Pending parameters now:"
<<
paramDataModel
->
countPendingParams
();
}
...
...
@@ -546,7 +563,7 @@ UASParameterCommsMgr::~UASParameterCommsMgr()
QString
ptrStr
;
ptrStr
.
sprintf
(
"%8p"
,
this
);
q
Debug
(
)
<<
"UASParameterCommsMgr destructor: "
<<
ptrStr
;
q
CDebug
(
UASParameterCommsMgrLog
)
<<
"UASParameterCommsMgr destructor: "
<<
ptrStr
;
}
...
...
src/uas/UASParameterCommsMgr.h
View file @
c27191b0
...
...
@@ -6,11 +6,12 @@
#include <QTimer>
#include <QVariant>
#include <QVector>
#include <QLoggingCategory>
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
);
};
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment