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
39ed495e
Commit
39ed495e
authored
Apr 30, 2014
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'master' of github.com:mavlink/qgroundcontrol into thread_test
parents
68e181e3
0ea78c2f
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
112 additions
and
124 deletions
+112
-124
qwt_math.h
libs/qwt/qwt_math.h
+2
-2
UAS.cc
src/uas/UAS.cc
+64
-98
QGCPX4VehicleConfig.cc
src/ui/QGCPX4VehicleConfig.cc
+4
-4
QGCPX4VehicleConfig.h
src/ui/QGCPX4VehicleConfig.h
+1
-1
QGCXYPlot.cc
src/ui/designer/QGCXYPlot.cc
+38
-18
QGCXYPlot.h
src/ui/designer/QGCXYPlot.h
+3
-1
No files found.
libs/qwt/qwt_math.h
View file @
39ed495e
...
...
@@ -23,8 +23,8 @@
#else // QT_VERSION >= 0x040000
#define qwtMax
qMax
#define qwtMin
qMin
#define qwtMax
(x,y) qMax(qreal(x),qreal(y))
#define qwtMin
(x,y) qMin(qreal(x),qreal(y))
#define qwtAbs qAbs
#endif
...
...
src/uas/UAS.cc
View file @
39ed495e
...
...
@@ -2000,7 +2000,7 @@ void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
*/
float
UAS
::
filterVoltage
(
float
value
)
const
{
return
lpVoltage
*
0.
7
f
+
value
*
0.3
f
;
return
lpVoltage
*
0.
6
f
+
value
*
0.4
f
;
}
/**
...
...
@@ -2551,110 +2551,76 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
parameters
.
insert
(
compId
,
new
QMap
<
QString
,
QVariant
>
());
}
// Insert parameter into registry
if
(
parameters
.
value
(
compId
)
->
contains
(
paramName
))
{
parameters
.
value
(
compId
)
->
remove
(
paramName
);
}
QVariant
param
;
// Insert with correct type
// TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling.
switch
(
rawValue
.
param_type
)
{
case
MAV_PARAM_TYPE_REAL32
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
(
paramValue
.
param_float
);
}
else
{
param
=
QVariant
(
paramValue
.
param_float
);
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
// qDebug() << "RECEIVED PARAM:" << param;
}
break
;
case
MAV_PARAM_TYPE_UINT8
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
(
QChar
((
unsigned
char
)
paramValue
.
param_float
));
}
else
{
param
=
QVariant
(
QChar
((
unsigned
char
)
paramValue
.
param_uint8
));
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
//qDebug() << "RECEIVED PARAM:" << param;
}
break
;
case
MAV_PARAM_TYPE_INT8
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
(
QChar
((
char
)
paramValue
.
param_float
));
}
else
{
param
=
QVariant
(
QChar
((
char
)
paramValue
.
param_int8
));
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
//qDebug() << "RECEIVED PARAM:" << param;
}
break
;
case
MAV_PARAM_TYPE_INT16
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
short
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
(
paramValue
.
param_int16
);
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
//qDebug() << "RECEIVED PARAM:" << param;
}
break
;
case
MAV_PARAM_TYPE_UINT32
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
unsigned
int
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
(
paramValue
.
param_uint32
);
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
}
break
;
case
MAV_PARAM_TYPE_INT32
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
int
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
(
paramValue
.
param_int32
);
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
// qDebug() << "RECEIVED PARAM:" << param;
}
break
;
default:
qCritical
()
<<
"INVALID DATA TYPE USED AS PARAMETER VALUE: "
<<
rawValue
.
param_type
;
switch
(
rawValue
.
param_type
)
{
case
MAV_PARAM_TYPE_REAL32
:
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
(
paramValue
.
param_float
);
}
else
{
param
=
QVariant
(
paramValue
.
param_float
);
}
break
;
case
MAV_PARAM_TYPE_UINT8
:
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
(
QChar
((
unsigned
char
)
paramValue
.
param_float
));
}
else
{
param
=
QVariant
(
QChar
((
quint8
)
paramValue
.
param_float
));
}
break
;
case
MAV_PARAM_TYPE_INT8
:
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
(
QChar
((
char
)
paramValue
.
param_float
));
}
else
{
param
=
QVariant
(
QChar
((
qint8
)
paramValue
.
param_float
));
}
break
;
case
MAV_PARAM_TYPE_INT16
:
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
short
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
((
qint16
)
paramValue
.
param_float
);
}
break
;
case
MAV_PARAM_TYPE_UINT16
:
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
unsigned
short
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
((
quint16
)
paramValue
.
param_float
);
}
break
;
case
MAV_PARAM_TYPE_UINT32
:
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
unsigned
int
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
((
quint32
)
paramValue
.
param_float
);
}
break
;
case
MAV_PARAM_TYPE_INT32
:
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
int
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
((
qint32
)
paramValue
.
param_float
);
}
break
;
default:
qCritical
()
<<
"INVALID DATA TYPE USED AS PARAMETER VALUE: "
<<
rawValue
.
param_type
;
return
;
}
//switch (value.param_type)
// We did not return a critical error, now insert parameter into registry
if
(
parameters
.
value
(
compId
)
->
contains
(
paramName
))
{
parameters
.
value
(
compId
)
->
remove
(
paramName
);
}
// add new values
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
}
/**
...
...
src/ui/QGCPX4VehicleConfig.cc
View file @
39ed495e
...
...
@@ -50,7 +50,7 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
rcThrottle
(
0.0
f
),
rcMode
(
0.0
f
),
rcAssist
(
0.0
f
),
rc
Mission
(
0.0
f
),
rc
Loiter
(
0.0
f
),
rcReturn
(
0.0
f
),
rcFlaps
(
0.0
f
),
rcAux1
(
0.0
f
),
...
...
@@ -72,7 +72,7 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
channelNames
<<
"Throttle"
;
channelNames
<<
"Main Mode Switch"
;
channelNames
<<
"Assist Switch"
;
channelNames
<<
"
Mission
Switch"
;
channelNames
<<
"
Loiter
Switch"
;
channelNames
<<
"Return Switch"
;
channelNames
<<
"Flaps"
;
channelNames
<<
"Aux1"
;
...
...
@@ -1484,7 +1484,7 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float fval)
rcAssist
=
normalized
;
// ASSIST SWITCH
}
else
if
(
chan
==
rcMapping
[
6
])
{
rc
Mission
=
normalized
;
// MISSION
SWITCH
rc
Loiter
=
normalized
;
// LOITER
SWITCH
}
else
if
(
chan
==
rcMapping
[
7
])
{
rcReturn
=
normalized
;
// RETURN SWITCH
...
...
@@ -1948,7 +1948,7 @@ void QGCPX4VehicleConfig::updateRcChanLabels()
}
if
(
rcValue
[
rcMapping
[
6
]]
!=
UINT16_MAX
)
{
ui
->
missionSwChanLabel
->
setText
(
labelForRcValue
(
rc
Mission
));
ui
->
missionSwChanLabel
->
setText
(
labelForRcValue
(
rc
Loiter
));
}
else
{
ui
->
missionSwChanLabel
->
setText
(
blankLabel
);
...
...
src/ui/QGCPX4VehicleConfig.h
View file @
39ed495e
...
...
@@ -306,7 +306,7 @@ protected:
float
rcThrottle
;
///< PPM input channel used as throttle control input
float
rcMode
;
///< PPM input channel used as mode switch control input
float
rcAssist
;
///< PPM input channel used as assist switch control input
float
rc
Mission
;
///< PPM input channel used as mission
switch control input
float
rc
Loiter
;
///< PPM input channel used as loiter
switch control input
float
rcReturn
;
///< PPM input channel used as return switch control input
float
rcFlaps
;
///< PPM input channel used as flaps control input
float
rcAux1
;
///< PPM input channel used as aux 1 input
...
...
src/ui/designer/QGCXYPlot.cc
View file @
39ed495e
...
...
@@ -33,23 +33,28 @@ public:
/** Append data, returning the number of removed items */
int
appendData
(
const
QPointF
&
data
)
{
if
(
!
minMaxSet
)
{
xmin
=
xmax
=
data
.
x
();
ymin
=
ymax
=
data
.
y
();
minMaxSet
=
true
;
}
else
if
(
m_autoScale
)
{
xmin
=
qMin
(
xmin
,
data
.
x
());
xmax
=
qMax
(
xmax
,
data
.
x
());
ymin
=
qMin
(
ymin
,
data
.
y
());
ymax
=
qMax
(
ymax
,
data
.
y
());
}
m_data
.
append
(
data
);
int
removed
=
0
;
while
(
m_data
.
size
()
>
m_maxStore
Points
)
{
while
(
m_data
.
size
()
>
m_maxShow
Points
)
{
++
removed
;
m_data
.
removeFirst
();
}
if
(
!
minMaxSet
)
{
xmin
=
xmax
=
data
.
x
();
ymin
=
ymax
=
data
.
y
();
minMaxSet
=
true
;
previousTime
=
xmin
;
}
else
if
(
m_autoScale
)
{
if
(
m_autoScaleTime
)
{
xmin
+=
removed
*
(
data
.
x
()
-
previousTime
);
previousTime
=
data
.
x
();
}
else
{
xmin
=
qMin
(
qreal
(
xmin
),
data
.
x
());
}
xmax
=
qMax
(
qreal
(
xmax
),
data
.
x
());
ymin
=
qMin
(
qreal
(
ymin
),
data
.
y
());
ymax
=
qMax
(
qreal
(
ymax
),
data
.
y
());
}
itemChanged
();
return
removed
;
}
...
...
@@ -61,6 +66,10 @@ public:
void
setColor
(
const
QColor
&
color
)
{
m_color
=
color
;
}
void
setTimeSerie
(
bool
state
)
{
clear
();
m_autoScaleTime
=
state
;
}
void
unsetMinMax
()
{
if
(
m_autoScale
)
return
;
...
...
@@ -70,13 +79,13 @@ public:
minMaxSet
=
false
;
else
{
minMaxSet
=
true
;
xmax
=
xmin
=
m_data
.
at
(
0
).
x
();
previousTime
=
xmax
=
xmin
=
m_data
.
at
(
0
).
x
();
ymax
=
ymin
=
m_data
.
at
(
0
).
y
();
for
(
int
i
=
1
;
i
<
m_data
.
size
();
i
++
)
{
xmin
=
qMin
(
xmin
,
m_data
.
at
(
i
).
x
());
xmax
=
qMax
(
xmax
,
m_data
.
at
(
i
).
x
());
ymin
=
qMin
(
ymin
,
m_data
.
at
(
i
).
y
());
ymax
=
qMax
(
ymax
,
m_data
.
at
(
i
).
y
());
xmin
=
qMin
(
qreal
(
xmin
)
,
m_data
.
at
(
i
).
x
());
xmax
=
qMax
(
qreal
(
xmax
)
,
m_data
.
at
(
i
).
x
());
ymin
=
qMin
(
qreal
(
ymin
)
,
m_data
.
at
(
i
).
y
());
ymax
=
qMax
(
qreal
(
ymax
)
,
m_data
.
at
(
i
).
y
());
}
}
}
...
...
@@ -164,12 +173,14 @@ private:
int
m_smoothPoints
;
/** Number of points to average across */
mutable
QColor
m_color
;
double
previousTime
;
double
xmin
;
double
xmax
;
double
ymin
;
double
ymax
;
bool
minMaxSet
;
bool
m_autoScale
;
bool
m_autoScaleTime
;
int
m_startIndex
;
};
...
...
@@ -220,6 +231,7 @@ QGCXYPlot::QGCXYPlot(QWidget *parent) :
connect
(
ui
->
minY
,
SIGNAL
(
valueChanged
(
double
)),
this
,
SLOT
(
updateMinMaxSettings
()));
connect
(
ui
->
maxY
,
SIGNAL
(
valueChanged
(
double
)),
this
,
SLOT
(
updateMinMaxSettings
()));
connect
(
ui
->
automaticAxisRange
,
SIGNAL
(
toggled
(
bool
)),
this
,
SLOT
(
updateMinMaxSettings
()));
connect
(
ui
->
timeAxisRange
,
SIGNAL
(
toggled
(
bool
)),
this
,
SLOT
(
setTimeAxis
()));
connect
(
ui
->
maxDataShowSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
this
,
SLOT
(
updateMinMaxSettings
()));
connect
(
ui
->
maxDataStoreSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
this
,
SLOT
(
updateMinMaxSettings
()));
connect
(
ui
->
smoothSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
this
,
SLOT
(
updateMinMaxSettings
()));
...
...
@@ -261,6 +273,7 @@ void QGCXYPlot::setEditMode(bool editMode)
ui
->
maxDataShowSpinBox
->
setVisible
(
editMode
);
ui
->
maxDataStoreSpinBox
->
setVisible
(
editMode
);
ui
->
automaticAxisRange
->
setVisible
(
editMode
);
ui
->
timeAxisRange
->
setVisible
(
editMode
);
ui
->
lblSmooth
->
setVisible
(
editMode
);
ui
->
smoothSpinBox
->
setVisible
(
editMode
);
...
...
@@ -286,7 +299,7 @@ void QGCXYPlot::writeSettings(QSettings& settings)
settings
.
setValue
(
"QGC_XYPLOT_MAXDATA_SHOW"
,
ui
->
maxDataShowSpinBox
->
value
());
settings
.
setValue
(
"QGC_XYPLOT_AUTO"
,
ui
->
automaticAxisRange
->
isChecked
());
settings
.
setValue
(
"QGC_XYPLOT_SMOOTH"
,
ui
->
smoothSpinBox
->
value
());
settings
.
setValue
(
"QGC_XYPLOT_TIME"
,
ui
->
timeAxisRange
->
isChecked
());
settings
.
sync
();
}
void
QGCXYPlot
::
readSettings
(
const
QString
&
pre
,
const
QVariantMap
&
settings
)
...
...
@@ -301,6 +314,7 @@ void QGCXYPlot::readSettings(const QString& pre,const QVariantMap& settings)
ui
->
maxDataStoreSpinBox
->
setValue
(
settings
.
value
(
pre
+
"QGC_XYPLOT_MAXDATA_STORE"
,
10000
).
toInt
());
ui
->
maxDataShowSpinBox
->
setValue
(
settings
.
value
(
pre
+
"QGC_XYPLOT_MAXDATA_SHOW"
,
15
).
toInt
());
ui
->
smoothSpinBox
->
setValue
(
settings
.
value
(
pre
+
"QGC_XYPLOT_SMOOTH"
,
1
).
toInt
());
ui
->
timeAxisRange
->
setChecked
(
settings
.
value
(
pre
+
"QGC_XYPLOT_TIME"
,
true
).
toBool
());
plot
->
setAxisTitle
(
QwtPlot
::
xBottom
,
ui
->
editXParam
->
currentText
());
plot
->
setAxisTitle
(
QwtPlot
::
yLeft
,
ui
->
editYParam
->
currentText
());
updateMinMaxSettings
();
...
...
@@ -318,6 +332,7 @@ void QGCXYPlot::readSettings(const QSettings& settings)
ui
->
maxDataStoreSpinBox
->
setValue
(
settings
.
value
(
"QGC_XYPLOT_MAXDATA_STORE"
,
10000
).
toInt
());
ui
->
maxDataShowSpinBox
->
setValue
(
settings
.
value
(
"QGC_XYPLOT_MAXDATA_SHOW"
,
15
).
toInt
());
ui
->
smoothSpinBox
->
setValue
(
settings
.
value
(
"QGC_XYPLOT_SMOOTH"
,
1
).
toInt
());
ui
->
timeAxisRange
->
setChecked
(
settings
.
value
(
"QGC_XYPLOT_TIME"
,
true
).
toBool
());
plot
->
setAxisTitle
(
QwtPlot
::
xBottom
,
ui
->
editXParam
->
currentText
());
plot
->
setAxisTitle
(
QwtPlot
::
yLeft
,
ui
->
editYParam
->
currentText
());
updateMinMaxSettings
();
...
...
@@ -412,6 +427,11 @@ void QGCXYPlot::updateMinMaxSettings()
xycurve
->
setSmoothPoints
(
ui
->
smoothSpinBox
->
value
());
}
void
QGCXYPlot
::
setTimeAxis
()
{
xycurve
->
setTimeSerie
(
ui
->
timeAxisRange
->
isChecked
());
}
void
QGCXYPlot
::
on_maxDataShowSpinBox_valueChanged
(
int
value
)
{
ui
->
maxDataStoreSpinBox
->
setMinimum
(
value
);
...
...
src/ui/designer/QGCXYPlot.h
View file @
39ed495e
...
...
@@ -31,10 +31,11 @@ public slots:
void
styleChanged
(
MainWindow
::
QGC_MAINWINDOW_STYLE
style
);
void
updateMinMaxSettings
();
private
slots
:
void
on_maxDataShowSpinBox_valueChanged
(
int
value
);
void
on_stopStartButton_toggled
(
bool
checked
);
void
setTimeAxis
();
void
on_timeScrollBar_valueChanged
(
int
value
);
private:
...
...
@@ -42,6 +43,7 @@ private:
QwtPlot
*
plot
;
XYPlotCurve
*
xycurve
;
bool
autoScaleTime
;
double
x
;
/**< Last unused value for the x-coordinate */
quint64
x_timestamp_us
;
/**< Timestamp that we last recieved a value for x */
bool
x_valid
;
/**< Whether we have recieved an x value but so far no corresponding y value */
...
...
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