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
d10e89f4
Commit
d10e89f4
authored
Aug 14, 2020
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Support multi-system display/selection
parent
92e15136
Changes
3
Show whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
115 additions
and
89 deletions
+115
-89
MAVLinkInspectorController.cc
src/AnalyzeView/MAVLinkInspectorController.cc
+50
-43
MAVLinkInspectorController.h
src/AnalyzeView/MAVLinkInspectorController.h
+34
-33
MAVLinkInspectorPage.qml
src/AnalyzeView/MAVLinkInspectorPage.qml
+31
-13
No files found.
src/AnalyzeView/MAVLinkInspectorController.cc
View file @
d10e89f4
...
...
@@ -179,6 +179,7 @@ QGCMAVLinkMessage::QGCMAVLinkMessage(QObject *parent, mavlink_message_t* message
QGCMAVLinkMessageField
*
f
=
new
QGCMAVLinkMessageField
(
this
,
msgInfo
->
fields
[
i
].
name
,
type
);
_fields
.
append
(
f
);
}
update
(
message
);
}
//-----------------------------------------------------------------------------
...
...
@@ -222,10 +223,7 @@ void
QGCMAVLinkMessage
::
update
(
mavlink_message_t
*
message
)
{
_count
++
;
//-- If we are not consuming this message, no need to parse it
if
(
!
_selected
&&
!
_fieldSelected
)
{
return
;
}
_message
=
*
message
;
const
mavlink_message_info_t
*
msgInfo
=
mavlink_get_message_info
(
message
);
if
(
!
msgInfo
)
{
...
...
@@ -454,7 +452,7 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
}
//-----------------------------------------------------------------------------
QGCMAVLink
Vehicle
::
QGCMAVLinkVehicle
(
QObject
*
parent
,
quint8
id
)
QGCMAVLink
System
::
QGCMAVLinkSystem
(
QObject
*
parent
,
quint8
id
)
:
QObject
(
parent
)
,
_id
(
id
)
{
...
...
@@ -462,14 +460,14 @@ QGCMAVLinkVehicle::QGCMAVLinkVehicle(QObject* parent, quint8 id)
}
//-----------------------------------------------------------------------------
QGCMAVLink
Vehicle
::~
QGCMAVLinkVehicle
()
QGCMAVLink
System
::~
QGCMAVLinkSystem
()
{
_messages
.
clearAndDeleteContents
();
}
//-----------------------------------------------------------------------------
QGCMAVLinkMessage
*
QGCMAVLink
Vehicle
::
findMessage
(
uint32_t
id
,
uint8_t
cid
)
QGCMAVLink
System
::
findMessage
(
uint32_t
id
,
uint8_t
cid
)
{
for
(
int
i
=
0
;
i
<
_messages
.
count
();
i
++
)
{
QGCMAVLinkMessage
*
m
=
qobject_cast
<
QGCMAVLinkMessage
*>
(
_messages
.
get
(
i
));
...
...
@@ -484,7 +482,7 @@ QGCMAVLinkVehicle::findMessage(uint32_t id, uint8_t cid)
//-----------------------------------------------------------------------------
int
QGCMAVLink
Vehicle
::
findMessage
(
QGCMAVLinkMessage
*
message
)
QGCMAVLink
System
::
findMessage
(
QGCMAVLinkMessage
*
message
)
{
for
(
int
i
=
0
;
i
<
_messages
.
count
();
i
++
)
{
QGCMAVLinkMessage
*
m
=
qobject_cast
<
QGCMAVLinkMessage
*>
(
_messages
.
get
(
i
));
...
...
@@ -497,7 +495,7 @@ QGCMAVLinkVehicle::findMessage(QGCMAVLinkMessage* message)
//-----------------------------------------------------------------------------
void
QGCMAVLink
Vehicle
::
_resetSelection
()
QGCMAVLink
System
::
_resetSelection
()
{
for
(
int
i
=
0
;
i
<
_messages
.
count
();
i
++
)
{
QGCMAVLinkMessage
*
m
=
qobject_cast
<
QGCMAVLinkMessage
*>
(
_messages
.
get
(
i
));
...
...
@@ -510,7 +508,7 @@ QGCMAVLinkVehicle::_resetSelection()
//-----------------------------------------------------------------------------
void
QGCMAVLink
Vehicle
::
setSelected
(
int
sel
)
QGCMAVLink
System
::
setSelected
(
int
sel
)
{
if
(
sel
<
_messages
.
count
())
{
_selected
=
sel
;
...
...
@@ -537,7 +535,7 @@ messages_sort(QObject* a, QObject* b)
//-----------------------------------------------------------------------------
void
QGCMAVLink
Vehicle
::
append
(
QGCMAVLinkMessage
*
message
)
QGCMAVLink
System
::
append
(
QGCMAVLinkMessage
*
message
)
{
//-- Save selected message
QGCMAVLinkMessage
*
selectedMsg
=
nullptr
;
...
...
@@ -572,15 +570,15 @@ QGCMAVLinkVehicle::append(QGCMAVLinkMessage* message)
//-----------------------------------------------------------------------------
void
QGCMAVLink
Vehicle
::
_checkCompID
(
QGCMAVLinkMessage
*
message
)
QGCMAVLink
System
::
_checkCompID
(
QGCMAVLinkMessage
*
message
)
{
if
(
_compIDsStr
.
isEmpty
())
{
_compIDsStr
<<
tr
(
"All"
);
_compIDsStr
<<
tr
(
"
Comp
All"
);
}
if
(
!
_compIDs
.
contains
(
static_cast
<
int
>
(
message
->
cid
())))
{
int
cid
=
static_cast
<
int
>
(
message
->
cid
());
_compIDs
.
append
(
cid
);
_compIDsStr
<<
QString
::
number
(
cid
);
_compIDsStr
<<
tr
(
"Comp %1"
).
arg
(
cid
);
emit
compIDsChanged
();
}
}
...
...
@@ -748,7 +746,7 @@ MAVLinkInspectorController::MAVLinkInspectorController()
MAVLinkInspectorController
::~
MAVLinkInspectorController
()
{
_charts
.
clearAndDeleteContents
();
_
vehicle
s
.
clearAndDeleteContents
();
_
system
s
.
clearAndDeleteContents
();
}
//----------------------------------------------------------------------------------------
...
...
@@ -780,24 +778,24 @@ void
MAVLinkInspectorController
::
_setActiveVehicle
(
Vehicle
*
vehicle
)
{
if
(
vehicle
)
{
QGCMAVLink
Vehicle
*
v
=
_findVehicle
(
static_cast
<
uint8_t
>
(
vehicle
->
id
()));
QGCMAVLink
System
*
v
=
_findVehicle
(
static_cast
<
uint8_t
>
(
vehicle
->
id
()));
if
(
v
)
{
_active
Vehicle
=
v
;
_active
System
=
v
;
}
else
{
_active
Vehicle
=
nullptr
;
_active
System
=
nullptr
;
}
}
else
{
_active
Vehicle
=
nullptr
;
_active
System
=
nullptr
;
}
emit
active
Vehicles
Changed
();
emit
active
System
Changed
();
}
//-----------------------------------------------------------------------------
QGCMAVLink
Vehicle
*
QGCMAVLink
System
*
MAVLinkInspectorController
::
_findVehicle
(
uint8_t
id
)
{
for
(
int
i
=
0
;
i
<
_
vehicle
s
.
count
();
i
++
)
{
QGCMAVLink
Vehicle
*
v
=
qobject_cast
<
QGCMAVLinkVehicle
*>
(
_vehicle
s
.
get
(
i
));
for
(
int
i
=
0
;
i
<
_
system
s
.
count
();
i
++
)
{
QGCMAVLink
System
*
v
=
qobject_cast
<
QGCMAVLinkSystem
*>
(
_system
s
.
get
(
i
));
if
(
v
)
{
if
(
v
->
id
()
==
id
)
{
return
v
;
...
...
@@ -811,8 +809,8 @@ MAVLinkInspectorController::_findVehicle(uint8_t id)
void
MAVLinkInspectorController
::
_refreshFrequency
()
{
for
(
int
i
=
0
;
i
<
_
vehicle
s
.
count
();
i
++
)
{
QGCMAVLink
Vehicle
*
v
=
qobject_cast
<
QGCMAVLinkVehicle
*>
(
_vehicle
s
.
get
(
i
));
for
(
int
i
=
0
;
i
<
_
system
s
.
count
();
i
++
)
{
QGCMAVLink
System
*
v
=
qobject_cast
<
QGCMAVLinkSystem
*>
(
_system
s
.
get
(
i
));
if
(
v
)
{
for
(
int
i
=
0
;
i
<
v
->
messages
()
->
count
();
i
++
)
{
QGCMAVLinkMessage
*
m
=
qobject_cast
<
QGCMAVLinkMessage
*>
(
v
->
messages
()
->
get
(
i
));
...
...
@@ -828,29 +826,29 @@ MAVLinkInspectorController::_refreshFrequency()
void
MAVLinkInspectorController
::
_vehicleAdded
(
Vehicle
*
vehicle
)
{
QGCMAVLink
Vehicle
*
v
=
_findVehicle
(
static_cast
<
uint8_t
>
(
vehicle
->
id
()));
QGCMAVLink
System
*
v
=
_findVehicle
(
static_cast
<
uint8_t
>
(
vehicle
->
id
()));
if
(
v
)
{
v
->
messages
()
->
clearAndDeleteContents
();
emit
v
->
messagesChanged
();
}
else
{
v
=
new
QGCMAVLink
Vehicle
(
this
,
static_cast
<
uint8_t
>
(
vehicle
->
id
()));
_
vehicle
s
.
append
(
v
);
_
vehicleNames
.
append
(
tr
(
"Vehicle
%1"
).
arg
(
vehicle
->
id
()));
v
=
new
QGCMAVLink
System
(
this
,
static_cast
<
uint8_t
>
(
vehicle
->
id
()));
_
system
s
.
append
(
v
);
_
systemNames
.
append
(
tr
(
"System
%1"
).
arg
(
vehicle
->
id
()));
}
emit
vehicle
sChanged
();
emit
system
sChanged
();
}
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController
::
_vehicleRemoved
(
Vehicle
*
vehicle
)
{
QGCMAVLink
Vehicle
*
v
=
_findVehicle
(
static_cast
<
uint8_t
>
(
vehicle
->
id
()));
QGCMAVLink
System
*
v
=
_findVehicle
(
static_cast
<
uint8_t
>
(
vehicle
->
id
()));
if
(
v
)
{
v
->
deleteLater
();
_
vehicle
s
.
removeOne
(
v
);
QString
vs
=
tr
(
"
Vehicle
%1"
).
arg
(
vehicle
->
id
());
_
vehicle
Names
.
removeOne
(
vs
);
emit
vehicle
sChanged
();
_
system
s
.
removeOne
(
v
);
QString
vs
=
tr
(
"
System
%1"
).
arg
(
vehicle
->
id
());
_
system
Names
.
removeOne
(
vs
);
emit
system
sChanged
();
}
}
...
...
@@ -859,15 +857,15 @@ void
MAVLinkInspectorController
::
_receiveMessage
(
LinkInterface
*
,
mavlink_message_t
message
)
{
QGCMAVLinkMessage
*
m
=
nullptr
;
QGCMAVLink
Vehicle
*
v
=
_findVehicle
(
message
.
sysid
);
QGCMAVLink
System
*
v
=
_findVehicle
(
message
.
sysid
);
if
(
!
v
)
{
v
=
new
QGCMAVLink
Vehicle
(
this
,
message
.
sysid
);
_
vehicle
s
.
append
(
v
);
_
vehicleNames
.
append
(
tr
(
"Vehicle
%1"
).
arg
(
message
.
sysid
));
emit
vehicle
sChanged
();
if
(
!
_active
Vehicle
)
{
_active
Vehicle
=
v
;
emit
active
Vehicles
Changed
();
v
=
new
QGCMAVLink
System
(
this
,
message
.
sysid
);
_
system
s
.
append
(
v
);
_
systemNames
.
append
(
tr
(
"System
%1"
).
arg
(
message
.
sysid
));
emit
system
sChanged
();
if
(
!
_active
System
)
{
_active
System
=
v
;
emit
active
System
Changed
();
}
}
else
{
m
=
v
->
findMessage
(
message
.
msgid
,
message
.
compid
);
...
...
@@ -924,3 +922,12 @@ MAVLinkInspectorController::Range_st::Range_st(QObject* parent, const QString& l
{
}
void
MAVLinkInspectorController
::
setActiveSystem
(
int
systemId
)
{
QGCMAVLinkSystem
*
v
=
_findVehicle
(
systemId
);
if
(
v
!=
_activeSystem
)
{
_activeSystem
=
v
;
emit
activeSystemChanged
();
}
}
src/AnalyzeView/MAVLinkInspectorController.h
View file @
d10e89f4
...
...
@@ -27,7 +27,7 @@ Q_DECLARE_LOGGING_CATEGORY(MAVLinkInspectorLog)
QT_CHARTS_USE_NAMESPACE
class
QGCMAVLinkMessage
;
class
QGCMAVLink
Vehicle
;
class
QGCMAVLink
System
;
class
MAVLinkChartController
;
class
MAVLinkInspectorController
;
...
...
@@ -137,7 +137,7 @@ private:
//-----------------------------------------------------------------------------
/// Vehicle MAVLink message belongs to
class
QGCMAVLink
Vehicle
:
public
QObject
{
class
QGCMAVLink
System
:
public
QObject
{
Q_OBJECT
public:
Q_PROPERTY
(
quint8
id
READ
id
CONSTANT
)
...
...
@@ -147,8 +147,8 @@ public:
Q_PROPERTY
(
int
selected
READ
selected
WRITE
setSelected
NOTIFY
selectedChanged
)
QGCMAVLink
Vehicle
(
QObject
*
parent
,
quint8
id
);
~
QGCMAVLink
Vehicle
();
QGCMAVLink
System
(
QObject
*
parent
,
quint8
id
);
~
QGCMAVLink
System
();
quint8
id
()
{
return
_id
;
}
QmlObjectListModel
*
messages
()
{
return
&
_messages
;
}
...
...
@@ -248,20 +248,21 @@ public:
MAVLinkInspectorController
();
~
MAVLinkInspectorController
();
Q_PROPERTY
(
QStringList
vehicleNames
READ
vehicleNames
NOTIFY
vehicle
sChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
vehicles
READ
vehicles
NOTIFY
vehicle
sChanged
)
Q_PROPERTY
(
QStringList
systemNames
READ
systemNames
NOTIFY
system
sChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
systems
READ
systems
NOTIFY
system
sChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
charts
READ
charts
NOTIFY
chartsChanged
)
Q_PROPERTY
(
QGCMAVLink
Vehicle
*
activeVehicle
READ
activeVehicle
NOTIFY
activeVehicles
Changed
)
Q_PROPERTY
(
QGCMAVLink
System
*
activeSystem
READ
activeSystem
NOTIFY
activeSystem
Changed
)
Q_PROPERTY
(
QStringList
timeScales
READ
timeScales
NOTIFY
timeScalesChanged
)
Q_PROPERTY
(
QStringList
rangeList
READ
rangeList
NOTIFY
rangeListChanged
)
Q_INVOKABLE
MAVLinkChartController
*
createChart
();
Q_INVOKABLE
void
deleteChart
(
MAVLinkChartController
*
chart
);
Q_INVOKABLE
void
setActiveSystem
(
int
systemId
);
QmlObjectListModel
*
vehicles
()
{
return
&
_vehicle
s
;
}
QmlObjectListModel
*
systems
()
{
return
&
_system
s
;
}
QmlObjectListModel
*
charts
()
{
return
&
_charts
;
}
QGCMAVLink
Vehicle
*
activeVehicle
()
{
return
_activeVehicle
;
}
QStringList
vehicleNames
()
{
return
_vehicle
Names
;
}
QGCMAVLink
System
*
activeSystem
()
{
return
_activeSystem
;
}
QStringList
systemNames
()
{
return
_system
Names
;
}
QStringList
timeScales
();
QStringList
rangeList
();
...
...
@@ -283,9 +284,9 @@ public:
const
QList
<
Range_st
*>&
rangeSt
()
{
return
_rangeSt
;
}
signals:
void
vehiclesChanged
();
void
systemsChanged
();
void
chartsChanged
();
void
active
VehiclesChanged
();
void
active
SystemChanged
();
void
timeScalesChanged
();
void
rangeListChanged
();
...
...
@@ -297,7 +298,7 @@ private slots:
void
_refreshFrequency
();
private:
QGCMAVLink
Vehicle
*
_findVehicle
(
uint8_t
id
);
QGCMAVLink
System
*
_findVehicle
(
uint8_t
id
);
private:
...
...
@@ -305,10 +306,10 @@ private:
int
_selectedComponentID
=
0
;
///< Currently selected component
QStringList
_timeScales
;
QStringList
_rangeList
;
QGCMAVLink
Vehicle
*
_activeVehicle
=
nullptr
;
QGCMAVLink
System
*
_activeSystem
=
nullptr
;
QTimer
_updateFrequencyTimer
;
QStringList
_
vehicle
Names
;
QmlObjectListModel
_
vehicles
;
///< List of QGCMAVLinkVehicle
QStringList
_
system
Names
;
QmlObjectListModel
_
systems
;
///< List of QGCMAVLinkSystem
QmlObjectListModel
_charts
;
///< List of MAVLinkCharts
QList
<
TimeScale_st
*>
_timeScaleSt
;
QList
<
Range_st
*>
_rangeSt
;
...
...
src/AnalyzeView/MAVLinkInspectorPage.qml
View file @
d10e89f4
...
...
@@ -24,8 +24,8 @@ AnalyzePage {
headerComponent
:
headerComponent
pageComponent
:
pageComponent
property
var
cur
Vehicle
:
controller
?
controller
.
activeVehicle
:
null
property
var
curMessage
:
cur
Vehicle
&&
curVehicle
.
messages
.
count
?
curVehicle
.
messages
.
get
(
curVehicle
.
selected
)
:
null
property
var
cur
System
:
controller
?
controller
.
activeSystem
:
null
property
var
curMessage
:
cur
System
&&
curSystem
.
messages
.
count
?
curSystem
.
messages
.
get
(
curSystem
.
selected
)
:
null
property
int
curCompID
:
0
property
real
maxButtonWidth
:
0
...
...
@@ -45,21 +45,39 @@ AnalyzePage {
}
RowLayout
{
Layout.alignment
:
Qt
.
AlignRight
visible
:
curVehicle
?
curVehicle
.
compIDsStr
.
length
>
2
:
false
QGCLabel
{
text
:
qsTr
(
"
Component ID:
"
)
visible
:
curSystem
?
controller
.
systemNames
.
length
>
1
||
curSystem
.
compIDsStr
.
length
>
2
:
false
QGCComboBox
{
id
:
systemCombo
model
:
controller
.
systemNames
sizeToContents
:
true
visible
:
controller
.
systemNames
.
length
>
1
onActivated
:
controller
.
setActiveSystem
(
controller
.
systems
.
get
(
index
).
id
);
Connections
{
target
:
controller
onActiveSystemChanged
:
{
for
(
var
systemIndex
=
0
;
systemIndex
<
controller
.
systems
.
count
;
systemIndex
++
)
{
if
(
controller
.
systems
.
get
(
systemIndex
)
==
curSystem
)
{
systemCombo
.
currentIndex
=
systemIndex
curCompID
=
0
cidCombo
.
currentIndex
=
0
break
}
}
}
}
}
QGCComboBox
{
id
:
cidCombo
model
:
cur
Vehicle
?
curVehicle
.
compIDsStr
:
[]
Layout.minimumWidth
:
ScreenTools
.
defaultFontPixelWidth
*
10
currentIndex
:
0
model
:
cur
System
?
curSystem
.
compIDsStr
:
[]
sizeToContents
:
true
visible
:
curSystem
?
curSystem
.
compIDsStr
.
length
>
2
:
false
onActivated
:
{
if
(
cur
Vehicle
&&
curVehicle
.
compIDsStr
.
length
>
1
)
{
if
(
cur
System
&&
curSystem
.
compIDsStr
.
length
>
1
)
{
if
(
index
<
1
)
curCompID
=
0
else
curCompID
=
cur
Vehicle
.
compIDs
[
index
-
1
]
curCompID
=
cur
System
.
compIDs
[
index
-
1
]
}
}
}
...
...
@@ -87,15 +105,15 @@ AnalyzePage {
anchors.right
:
parent
.
right
spacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.25
Repeater
{
model
:
cur
Vehicle
?
curVehicle
.
messages
:
[]
model
:
cur
System
?
curSystem
.
messages
:
[]
delegate
:
MAVLinkMessageButton
{
text
:
object
.
name
+
(
object
.
fieldSelected
?
"
*
"
:
""
)
compID
:
object
.
cid
checked
:
cur
Vehicle
?
(
curVehicle
.
selected
===
index
)
:
false
checked
:
cur
System
?
(
curSystem
.
selected
===
index
)
:
false
messageHz
:
object
.
messageHz
visible
:
curCompID
===
0
||
curCompID
===
compID
onClicked
:
{
cur
Vehicle
.
selected
=
index
cur
System
.
selected
=
index
}
Layout.fillWidth
:
true
}
...
...
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