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
06244548
Commit
06244548
authored
Apr 30, 2010
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Switched to QTreeWidget for parameter view, receiving data works already
parent
f64f15df
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
35 additions
and
14 deletions
+35
-14
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+2
-2
UAS.cc
src/uas/UAS.cc
+2
-2
ParameterInterface.cc
src/ui/ParameterInterface.cc
+19
-7
ParameterInterface.h
src/ui/ParameterInterface.h
+2
-0
ParamTreeItem.cc
src/ui/param/ParamTreeItem.cc
+6
-1
ParamTreeItem.h
src/ui/param/ParamTreeItem.h
+2
-1
ParamTreeModel.cc
src/ui/param/ParamTreeModel.cc
+2
-1
No files found.
src/comm/MAVLinkSimulationLink.cc
View file @
06244548
...
...
@@ -147,7 +147,7 @@ void MAVLinkSimulationLink::mainloop()
static
float
fullVoltage
=
4.2
*
3
;
static
float
emptyVoltage
=
3.35
*
3
;
static
float
voltage
=
fullVoltage
;
static
float
drainRate
=
0.0
0
25
;
// x.xx% of the capacity is linearly drained per second
static
float
drainRate
=
0.025
;
// x.xx% of the capacity is linearly drained per second
attitude_t
attitude
;
raw_aux_t
rawAuxValues
;
...
...
@@ -352,7 +352,7 @@ void MAVLinkSimulationLink::mainloop()
}
statusCounter
++
;
status
.
vbat
=
voltage
;
status
.
vbat
=
voltage
*
1000
;
// millivolts
// Pack message and get size of encoded byte string
messageSize
=
message_sys_status_encode
(
systemId
,
componentId
,
&
msg
,
&
status
);
...
...
src/uas/UAS.cc
View file @
06244548
...
...
@@ -52,8 +52,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) :
thrustSum
(
0
),
thrustMax
(
10
),
startVoltage
(
0
),
currentVoltage
(
0
.0
f
),
lpVoltage
(
0
.0
f
),
currentVoltage
(
12
.0
f
),
lpVoltage
(
12
.0
f
),
mode
(
MAV_MODE_UNINIT
),
status
(
MAV_STATE_UNINIT
),
onboardTimeOffset
(
0
),
...
...
src/ui/ParameterInterface.cc
View file @
06244548
...
...
@@ -16,12 +16,20 @@ ParameterInterface::ParameterInterface(QWidget *parent) :
tree
=
new
ParamTreeModel
();
treeView
=
new
QTreeView
(
this
);
treeView
->
setModel
(
tree
);
//treeView = new QTreeView(this);
//treeView->setModel(tree);
treeWidget
=
new
QTreeWidget
(
this
);
QStringList
headerItems
;
headerItems
.
append
(
"Parameter"
);
headerItems
.
append
(
"Value"
);
treeWidget
->
setHeaderLabels
(
headerItems
);
QStackedWidget
*
stack
=
m_ui
->
stackedWidget
;
stack
->
addWidget
(
treeView
);
stack
->
setCurrentWidget
(
treeView
);
//stack->addWidget(treeView);
//stack->setCurrentWidget(treeView);
stack
->
addWidget
(
treeWidget
);
stack
->
setCurrentWidget
(
treeWidget
);
}
...
...
@@ -56,6 +64,8 @@ void ParameterInterface::addUAS(UASInterface* uas)
void
ParameterInterface
::
requestParameterList
()
{
mav
->
requestParameters
();
// Clear view
treeWidget
->
clear
();
}
/**
...
...
@@ -73,9 +83,11 @@ void ParameterInterface::receiveParameter(int uas, int component, QString parame
{
Q_UNUSED
(
uas
);
// Insert parameter into map
tree
->
appendParam
(
component
,
parameterName
,
value
);
// Refresh view
treeView
->
update
();
//tree->appendParam(component, parameterName, value);
QStringList
list
;
list
.
append
(
parameterName
);
list
.
append
(
QString
::
number
(
value
));
treeWidget
->
addTopLevelItem
(
new
QTreeWidgetItem
(
list
));
}
/**
...
...
src/ui/ParameterInterface.h
View file @
06244548
...
...
@@ -3,6 +3,7 @@
#include <QtGui/QWidget>
#include <QtGui/QTreeView>
#include <QtGui/QTreeWidget>
#include "ui_ParameterInterface.h"
#include "UASInterface.h"
#include "ParamTreeModel.h"
...
...
@@ -31,6 +32,7 @@ protected:
UASInterface
*
mav
;
ParamTreeModel
*
tree
;
QTreeView
*
treeView
;
QTreeWidget
*
treeWidget
;
private:
Ui
::
parameterWidget
*
m_ui
;
...
...
src/ui/param/ParamTreeItem.cc
View file @
06244548
...
...
@@ -107,11 +107,16 @@ QVariant ParamTreeItem::data(int column) const
}
}
ParamTreeItem
*
ParamTreeItem
::
parent
()
ParamTreeItem
*
ParamTreeItem
::
parent
()
const
{
return
parentItem
;
}
const
QList
<
ParamTreeItem
*>*
ParamTreeItem
::
children
()
const
{
return
&
childItems
;
}
int
ParamTreeItem
::
row
()
const
{
if
(
parentItem
)
...
...
src/ui/param/ParamTreeItem.h
View file @
06244548
...
...
@@ -53,7 +53,8 @@ public:
int
columnCount
()
const
;
QVariant
data
(
int
column
)
const
;
int
row
()
const
;
ParamTreeItem
*
parent
();
ParamTreeItem
*
parent
()
const
;
const
QList
<
ParamTreeItem
*>*
children
()
const
;
protected:
QString
paramName
;
...
...
src/ui/param/ParamTreeModel.cc
View file @
06244548
...
...
@@ -172,11 +172,11 @@ void ParamTreeModel::appendComponent(int componentId)
ParamTreeItem
*
item
=
new
ParamTreeItem
(
QString
(
"Component #"
)
+
QString
::
number
(
componentId
)
+
QString
(
""
),
0
,
rootItem
);
components
.
insert
(
componentId
,
item
);
}
//emit dataChanged();
}
void
ParamTreeModel
::
appendParam
(
int
componentId
,
QString
name
,
float
value
)
{
// If component does not exist yet
if
(
!
components
.
contains
(
componentId
))
{
...
...
@@ -186,6 +186,7 @@ void ParamTreeModel::appendParam(int componentId, QString name, float value)
// FIXME Children may be double here
comp
->
appendChild
(
new
ParamTreeItem
(
name
,
value
,
comp
));
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"Added param"
<<
name
<<
value
<<
"for component"
<<
comp
->
getParamName
();
emit
dataChanged
(
createIndex
(
0
,
0
,
rootItem
),
createIndex
(
0
,
0
,
rootItem
));
}
void
ParamTreeModel
::
setupModelData
(
const
QStringList
&
lines
,
ParamTreeItem
*
parent
)
...
...
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