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
00cf60ca
Commit
00cf60ca
authored
Dec 28, 2019
by
Gus Grubba
Committed by
Lorenz Meier
Jan 03, 2020
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
UI tweaks and adding time scale.
parent
8b0fe775
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
87 additions
and
39 deletions
+87
-39
MAVLinkInspectorController.cc
src/AnalyzeView/MAVLinkInspectorController.cc
+31
-1
MAVLinkInspectorController.h
src/AnalyzeView/MAVLinkInspectorController.h
+17
-13
MAVLinkInspectorPage.qml
src/AnalyzeView/MAVLinkInspectorPage.qml
+39
-25
No files found.
src/AnalyzeView/MAVLinkInspectorController.cc
View file @
00cf60ca
...
...
@@ -28,6 +28,13 @@ QGCMAVLinkMessageField::QGCMAVLinkMessageField(QGCMAVLinkMessage *parent, QStrin
qCDebug
(
MAVLinkInspectorLog
)
<<
"Field:"
<<
name
<<
type
;
}
//-----------------------------------------------------------------------------
QString
QGCMAVLinkMessageField
::
label
()
{
return
QString
(
_msg
->
name
()
+
": "
+
_name
);
}
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessageField
::
setSelectable
(
bool
sel
)
...
...
@@ -486,6 +493,12 @@ MAVLinkInspectorController::MAVLinkInspectorController()
connect
(
manager
,
&
MultiVehicleManager
::
activeVehicleChanged
,
this
,
&
MAVLinkInspectorController
::
_setActiveVehicle
);
_rangeXMax
=
QDateTime
::
fromMSecsSinceEpoch
(
0
);
_rangeXMin
=
QDateTime
::
fromMSecsSinceEpoch
(
std
::
numeric_limits
<
qint64
>::
max
());
_timeScales
<<
tr
(
"5 Sec"
);
_timeScales
<<
tr
(
"10 Sec"
);
_timeScales
<<
tr
(
"30 Sec"
);
_timeScales
<<
tr
(
"1 Min"
);
_timeScales
<<
tr
(
"2 Min"
);
_timeScales
<<
tr
(
"5 Min"
);
}
//-----------------------------------------------------------------------------
...
...
@@ -649,13 +662,30 @@ MAVLinkInspectorController::updateSeries(int index, QAbstractSeries* series)
}
}
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController
::
setTimeScale
(
quint32
t
)
{
_timeScale
=
t
;
emit
timeScaleChanged
();
updateXRange
();
}
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController
::
updateXRange
()
{
int
ts
=
5
*
1000
;
switch
(
_timeScale
)
{
case
1
:
ts
=
10
*
1000
;
break
;
case
2
:
ts
=
30
*
1000
;
break
;
case
3
:
ts
=
60
*
1000
;
break
;
case
4
:
ts
=
2
*
60
*
1000
;
break
;
case
5
:
ts
=
5
*
60
*
1000
;
break
;
}
qint64
t
=
static_cast
<
qint64
>
(
QGC
::
groundTimeMilliseconds
());
_rangeXMax
=
QDateTime
::
fromMSecsSinceEpoch
(
t
);
_rangeXMin
=
QDateTime
::
fromMSecsSinceEpoch
(
t
-
(
60
*
1000
)
);
_rangeXMin
=
QDateTime
::
fromMSecsSinceEpoch
(
t
-
ts
);
emit
rangeMinXChanged
();
emit
rangeMaxXChanged
();
}
src/AnalyzeView/MAVLinkInspectorController.h
View file @
00cf60ca
...
...
@@ -29,6 +29,7 @@ class MAVLinkInspectorController;
class
QGCMAVLinkMessageField
:
public
QObject
{
Q_OBJECT
Q_PROPERTY
(
QString
name
READ
name
CONSTANT
)
Q_PROPERTY
(
QString
label
READ
label
CONSTANT
)
Q_PROPERTY
(
QString
type
READ
type
CONSTANT
)
Q_PROPERTY
(
QString
value
READ
value
NOTIFY
valueChanged
)
Q_PROPERTY
(
qreal
rangeMin
READ
rangeMin
NOTIFY
rangeMinChanged
)
...
...
@@ -40,6 +41,7 @@ public:
QGCMAVLinkMessageField
(
QGCMAVLinkMessage
*
parent
,
QString
name
,
QString
type
);
QString
name
()
{
return
_name
;
}
QString
label
();
QString
type
()
{
return
_type
;
}
QString
value
()
{
return
_value
;
}
qreal
rangeMin
()
{
return
_rangeMin
;
}
...
...
@@ -173,6 +175,7 @@ public:
Q_PROPERTY
(
QDateTime
rangeXMin
READ
rangeXMin
NOTIFY
rangeMinXChanged
)
Q_PROPERTY
(
QDateTime
rangeXMax
READ
rangeXMax
NOTIFY
rangeMaxXChanged
)
Q_PROPERTY
(
QStringList
timeScales
READ
timeScales
CONSTANT
)
Q_PROPERTY
(
quint32
timeScale
READ
timeScale
WRITE
setTimeScale
NOTIFY
timeScaleChanged
)
Q_INVOKABLE
void
updateSeries
(
int
index
,
QAbstractSeries
*
series
);
...
...
@@ -180,12 +183,13 @@ public:
QmlObjectListModel
*
vehicles
()
{
return
&
_vehicles
;
}
QGCMAVLinkVehicle
*
activeVehicle
()
{
return
_activeVehicle
;
}
QStringList
vehicleNames
()
{
return
_vehicleNames
;
}
quint32
timeScale
()
{
return
_timeScale
;
}
QVariantList
chartFields
()
{
return
_chartFields
;
}
QDateTime
rangeXMin
()
{
return
_rangeXMin
;
}
QDateTime
rangeXMax
()
{
return
_rangeXMax
;
}
quint32
timeScale
()
{
return
_timeScale
;
}
QStringList
timeScales
()
{
return
_timeScales
;
}
QVariantList
chartFields
()
{
return
_chartFields
;
}
QDateTime
rangeXMin
()
{
return
_rangeXMin
;
}
QDateTime
rangeXMax
()
{
return
_rangeXMax
;
}
void
setTimeScale
(
quint32
t
)
{
_timeScale
=
t
;
emit
timeScaleChanged
();
}
void
setTimeScale
(
quint32
t
)
;
int
chartFieldCount
()
{
return
_chartFields
.
count
();
}
void
addChartField
(
QGCMAVLinkMessageField
*
field
);
void
delChartField
(
QGCMAVLinkMessageField
*
field
);
...
...
@@ -212,15 +216,15 @@ private:
QGCMAVLinkVehicle
*
_findVehicle
(
uint8_t
id
);
private:
int
_selectedSystemID
=
0
;
///< Currently selected system
int
_selectedComponentID
=
0
;
///< Currently selected component
quint32
_timeScale
=
10
;
///< 10 Seconds
QDateTime
_rangeXMin
;
QDateTime
_rangeXMax
;
QGCMAVLinkVehicle
*
_activeVehicle
=
nullptr
;
int
_selectedSystemID
=
0
;
///< Currently selected system
int
_selectedComponentID
=
0
;
///< Currently selected component
QStringList
_timeScales
;
quint32
_timeScale
=
0
;
///< 5 Seconds
QDateTime
_rangeXMin
;
QDateTime
_rangeXMax
;
QGCMAVLinkVehicle
*
_activeVehicle
=
nullptr
;
QTimer
_updateTimer
;
QStringList
_vehicleNames
;
QmlObjectListModel
_vehicles
;
//--
List of QGCMAVLinkVehicle
QmlObjectListModel
_vehicles
;
///<
List of QGCMAVLinkVehicle
QVariantList
_chartFields
;
};
src/AnalyzeView/MAVLinkInspectorPage.qml
View file @
00cf60ca
...
...
@@ -44,50 +44,64 @@ AnalyzePage {
Rectangle
{
color
:
qgcPal
.
window
anchors.fill
:
parent
QGCComboBox
{
id
:
timeScaleSelector
anchors.margins
:
ScreenTools
.
defaultFontPixelWidth
anchors.right
:
parent
.
right
anchors.top
:
parent
.
top
width
:
ScreenTools
.
defaultFontPixelWidth
*
10
height
:
ScreenTools
.
defaultFontPixelHeight
*
1.5
model
:
controller
.
timeScales
currentIndex
:
controller
.
timeScale
onActivated
:
controller
.
timeScale
=
index
}
ChartView
{
id
:
chartView
anchors.fill
:
parent
anchors.right
:
parent
.
right
anchors.left
:
parent
.
left
anchors.top
:
timeScaleSelector
.
bottom
anchors.bottom
:
parent
.
bottom
theme
:
ChartView
.
ChartThemeDark
antialiasing
:
true
animationOptions
:
ChartView
.
NoAnimation
ValueAxis
{
id
:
axisY1
min
:
visible
?
controller
.
chartFields
[
0
].
rangeMin
:
0
max
:
visible
?
controller
.
chartFields
[
0
].
rangeMax
:
0
visible
:
controller
.
chartFieldCount
>
0
id
:
axisY1
min
:
visible
?
controller
.
chartFields
[
0
].
rangeMin
:
0
max
:
visible
?
controller
.
chartFields
[
0
].
rangeMax
:
0
visible
:
controller
.
chartFieldCount
>
0
}
ValueAxis
{
id
:
axisY2
min
:
visible
?
controller
.
chartFields
[
1
].
rangeMin
:
0
max
:
visible
?
controller
.
chartFields
[
1
].
rangeMax
:
0
visible
:
controller
.
chartFieldCount
>
1
id
:
axisY2
min
:
visible
?
controller
.
chartFields
[
1
].
rangeMin
:
0
max
:
visible
?
controller
.
chartFields
[
1
].
rangeMax
:
0
visible
:
controller
.
chartFieldCount
>
1
}
DateTimeAxis
{
id
:
axisX
min
:
visible
?
controller
.
rangeXMin
:
new
Date
()
max
:
visible
?
controller
.
rangeXMax
:
new
Date
()
format
:
"
hh:mm:ss.zzz
"
tickCount
:
6
visible
:
controller
.
chartFieldCount
>
0
id
:
axisX
min
:
visible
?
controller
.
rangeXMin
:
new
Date
()
max
:
visible
?
controller
.
rangeXMax
:
new
Date
()
visible
:
controller
.
chartFieldCount
>
0
}
LineSeries
{
id
:
lineSeries1
name
:
controller
.
chartFieldCount
?
controller
.
chartFields
[
0
].
name
:
""
axisX
:
axisX
axisY
:
axisY1
useOpenGL
:
true
id
:
lineSeries1
name
:
controller
.
chartFieldCount
?
controller
.
chartFields
[
0
].
label
:
""
axisX
:
axisX
axisY
:
axisY1
color
:
qgcPal
.
colorRed
useOpenGL
:
true
}
LineSeries
{
id
:
lineSeries2
name
:
controller
.
chartFieldCount
>
1
?
controller
.
chartFields
[
1
].
name
:
""
axisX
:
axisX
axisYRight
:
axisY2
useOpenGL
:
true
id
:
lineSeries2
name
:
controller
.
chartFieldCount
>
1
?
controller
.
chartFields
[
1
].
label
:
""
axisX
:
axisX
axisYRight
:
axisY2
color
:
qgcPal
.
colorGreen
useOpenGL
:
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