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
e3132e65
Commit
e3132e65
authored
Aug 24, 2014
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #836 from DonLakeFlyer/RCWidget
RC Calibration Updates
parents
768e2408
0b1f2f63
Changes
11
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
11 changed files
with
981 additions
and
590 deletions
+981
-590
qgroundcontrol.pro
qgroundcontrol.pro
+13
-11
MockQGCUASParamManager.h
src/qgcunittest/MockQGCUASParamManager.h
+1
-1
PX4RCCalibrationTest.cc
src/qgcunittest/PX4RCCalibrationTest.cc
+3
-33
PX4RCCalibrationTest.h
src/qgcunittest/PX4RCCalibrationTest.h
+1
-2
QGCVehicleConfig.cc
src/ui/QGCVehicleConfig.cc
+16
-16
RadioCalibrationConfig.cc
src/ui/configuration/RadioCalibrationConfig.cc
+16
-16
RCChannelWidget.cc
src/ui/designer/RCChannelWidget.cc
+223
-0
RCChannelWidget.h
src/ui/designer/RCChannelWidget.h
+83
-0
PX4RCCalibration.cc
src/ui/px4_configuration/PX4RCCalibration.cc
+156
-74
PX4RCCalibration.h
src/ui/px4_configuration/PX4RCCalibration.h
+9
-3
PX4RCCalibration.ui
src/ui/px4_configuration/PX4RCCalibration.ui
+460
-434
No files found.
qgroundcontrol.pro
View file @
e3132e65
...
...
@@ -274,6 +274,9 @@ FORMS += \
src
/
ui
/
designer
/
QGCParamSlider
.
ui
\
src
/
ui
/
designer
/
QGCActionButton
.
ui
\
src
/
ui
/
designer
/
QGCCommandButton
.
ui
\
src
/
ui
/
designer
/
QGCComboBox
.
ui
\
src
/
ui
/
designer
/
QGCTextLabel
.
ui
\
src
/
ui
/
designer
/
QGCXYPlot
.
ui
\
src
/
ui
/
QGCMAVLinkLogPlayer
.
ui
\
src
/
ui
/
QGCWaypointListMulti
.
ui
\
src
/
ui
/
QGCUASFileViewMulti
.
ui
\
...
...
@@ -309,8 +312,6 @@ FORMS += \
src
/
ui
/
QGCHilFlightGearConfiguration
.
ui
\
src
/
ui
/
QGCHilJSBSimConfiguration
.
ui
\
src
/
ui
/
QGCHilXPlaneConfiguration
.
ui
\
src
/
ui
/
designer
/
QGCComboBox
.
ui
\
src
/
ui
/
designer
/
QGCTextLabel
.
ui
\
src
/
ui
/
uas
/
UASQuickView
.
ui
\
src
/
ui
/
uas
/
UASQuickViewItemSelect
.
ui
\
src
/
ui
/
uas
/
UASActionsWidget
.
ui
\
...
...
@@ -355,7 +356,6 @@ FORMS += \
src
/
ui
/
px4_configuration
/
QGCPX4MulticopterConfig
.
ui
\
src
/
ui
/
px4_configuration
/
QGCPX4SensorCalibration
.
ui
\
src
/
ui
/
px4_configuration
/
PX4RCCalibration
.
ui
\
src
/
ui
/
designer
/
QGCXYPlot
.
ui
\
src
/
ui
/
QGCUASFileView
.
ui
HEADERS
+=
\
...
...
@@ -435,6 +435,11 @@ HEADERS += \
src
/
ui
/
designer
/
QGCParamSlider
.
h
\
src
/
ui
/
designer
/
QGCCommandButton
.
h
\
src
/
ui
/
designer
/
QGCToolWidgetItem
.
h
\
src
/
ui
/
designer
/
QGCComboBox
.
h
\
src
/
ui
/
designer
/
QGCTextLabel
.
h
\
src
/
ui
/
designer
/
QGCRadioChannelDisplay
.
h
\
src
/
ui
/
designer
/
QGCXYPlot
.
h
\
src
/
ui
/
designer
/
RCChannelWidget
.
h
\
src
/
ui
/
QGCMAVLinkLogPlayer
.
h
\
src
/
comm
/
MAVLinkSimulationWaypointPlanner
.
h
\
src
/
comm
/
MAVLinkSimulationMAV
.
h
\
...
...
@@ -483,8 +488,6 @@ HEADERS += \
src
/
ui
/
QGCHilFlightGearConfiguration
.
h
\
src
/
ui
/
QGCHilJSBSimConfiguration
.
h
\
src
/
ui
/
QGCHilXPlaneConfiguration
.
h
\
src
/
ui
/
designer
/
QGCComboBox
.
h
\
src
/
ui
/
designer
/
QGCTextLabel
.
h
\
src
/
ui
/
submainwindow
.
h
\
src
/
ui
/
uas
/
UASQuickView
.
h
\
src
/
ui
/
uas
/
UASQuickViewItem
.
h
\
...
...
@@ -493,7 +496,6 @@ HEADERS += \
src
/
ui
/
uas
/
UASQuickViewTextItem
.
h
\
src
/
ui
/
uas
/
UASQuickViewGaugeItem
.
h
\
src
/
ui
/
uas
/
UASActionsWidget
.
h
\
src
/
ui
/
designer
/
QGCRadioChannelDisplay
.
h
\
src
/
ui
/
QGCTabbedInfoView
.
h
\
src
/
ui
/
UASRawStatusView
.
h
\
src
/
ui
/
PrimaryFlightDisplay
.
h
\
...
...
@@ -544,7 +546,6 @@ HEADERS += \
src
/
ui
/
px4_configuration
/
QGCPX4MulticopterConfig
.
h
\
src
/
ui
/
px4_configuration
/
QGCPX4SensorCalibration
.
h
\
src
/
ui
/
px4_configuration
/
PX4RCCalibration
.
h
\
src
/
ui
/
designer
/
QGCXYPlot
.
h
\
src
/
ui
/
menuactionhelper
.
h
\
src
/
uas
/
UASManagerInterface
.
h
\
src
/
uas
/
QGCUASParamManagerInterface
.
h
\
...
...
@@ -625,6 +626,11 @@ SOURCES += \
src
/
ui
/
designer
/
QGCParamSlider
.
cc
\
src
/
ui
/
designer
/
QGCCommandButton
.
cc
\
src
/
ui
/
designer
/
QGCToolWidgetItem
.
cc
\
src
/
ui
/
designer
/
QGCComboBox
.
cc
\
src
/
ui
/
designer
/
QGCTextLabel
.
cc
\
src
/
ui
/
designer
/
QGCRadioChannelDisplay
.
cpp
\
src
/
ui
/
designer
/
QGCXYPlot
.
cc
\
src
/
ui
/
designer
/
RCChannelWidget
.
cc
\
src
/
ui
/
QGCMAVLinkLogPlayer
.
cc
\
src
/
comm
/
MAVLinkSimulationWaypointPlanner
.
cc
\
src
/
comm
/
MAVLinkSimulationMAV
.
cc
\
...
...
@@ -671,8 +677,6 @@ SOURCES += \
src
/
ui
/
QGCHilFlightGearConfiguration
.
cc
\
src
/
ui
/
QGCHilJSBSimConfiguration
.
cc
\
src
/
ui
/
QGCHilXPlaneConfiguration
.
cc
\
src
/
ui
/
designer
/
QGCComboBox
.
cc
\
src
/
ui
/
designer
/
QGCTextLabel
.
cc
\
src
/
ui
/
submainwindow
.
cpp
\
src
/
ui
/
uas
/
UASQuickViewItem
.
cc
\
src
/
ui
/
uas
/
UASQuickView
.
cc
\
...
...
@@ -681,7 +685,6 @@ SOURCES += \
src
/
ui
/
uas
/
UASQuickViewGaugeItem
.
cc
\
src
/
ui
/
uas
/
UASQuickViewItemSelect
.
cc
\
src
/
ui
/
uas
/
UASActionsWidget
.
cpp
\
src
/
ui
/
designer
/
QGCRadioChannelDisplay
.
cpp
\
src
/
ui
/
QGCTabbedInfoView
.
cpp
\
src
/
ui
/
UASRawStatusView
.
cpp
\
src
/
ui
/
PrimaryFlightDisplay
.
cc
\
...
...
@@ -732,7 +735,6 @@ SOURCES += \
src
/
ui
/
px4_configuration
/
QGCPX4MulticopterConfig
.
cc
\
src
/
ui
/
px4_configuration
/
QGCPX4SensorCalibration
.
cc
\
src
/
ui
/
px4_configuration
/
PX4RCCalibration
.
cc
\
src
/
ui
/
designer
/
QGCXYPlot
.
cc
\
src
/
ui
/
menuactionhelper
.
cpp
\
src
/
uas
/
QGCUASFileManager
.
cc
\
src
/
ui
/
QGCUASFileView
.
cc
\
...
...
src/qgcunittest/MockQGCUASParamManager.h
View file @
e3132e65
...
...
@@ -38,7 +38,7 @@ class MockQGCUASParamManager : public QGCUASParamManagerInterface
signals:
// The following QGCSUASParamManagerInterface signals are supported
// currently none
void
parameterListUpToDate
();
// You can connect to this signal, but it will never be emitted
public:
// Implemented QGCSUASParamManager overrides
...
...
src/qgcunittest/PX4RCCalibrationTest.cc
View file @
e3132e65
...
...
@@ -97,32 +97,13 @@ void PX4RCCalibrationTest::init(void)
_statusLabel
=
_calWidget
->
findChild
<
QLabel
*>
(
"rcCalStatus"
);
Q_ASSERT
(
_statusLabel
);
// Need to make sure standard channel indices are less then 4. Otherwise our _rgRadioWidget array won't work correctly.
Q_ASSERT
(
PX4RCCalibration
::
rcCalFunctionRoll
>=
0
&&
PX4RCCalibration
::
rcCalFunctionRoll
<
4
);
Q_ASSERT
(
PX4RCCalibration
::
rcCalFunctionPitch
>=
0
&&
PX4RCCalibration
::
rcCalFunctionPitch
<
4
);
Q_ASSERT
(
PX4RCCalibration
::
rcCalFunctionYaw
>=
0
&&
PX4RCCalibration
::
rcCalFunctionYaw
<
4
);
Q_ASSERT
(
PX4RCCalibration
::
rcCalFunctionThrottle
>=
0
&&
PX4RCCalibration
::
rcCalFunctionThrottle
<
4
);
_rgAttitudeRadioWidget
[
PX4RCCalibration
::
rcCalFunctionRoll
]
=
_calWidget
->
findChild
<
QGCRadioChannelDisplay
*>
(
"rollWidget"
);
_rgAttitudeRadioWidget
[
PX4RCCalibration
::
rcCalFunctionPitch
]
=
_calWidget
->
findChild
<
QGCRadioChannelDisplay
*>
(
"pitchWidget"
);
_rgAttitudeRadioWidget
[
PX4RCCalibration
::
rcCalFunctionYaw
]
=
_calWidget
->
findChild
<
QGCRadioChannelDisplay
*>
(
"yawWidget"
);
_rgAttitudeRadioWidget
[
PX4RCCalibration
::
rcCalFunctionThrottle
]
=
_calWidget
->
findChild
<
QGCRadioChannelDisplay
*>
(
"throttleWidget"
);
Q_ASSERT
(
_rgAttitudeRadioWidget
[
PX4RCCalibration
::
rcCalFunctionRoll
]);
Q_ASSERT
(
_rgAttitudeRadioWidget
[
PX4RCCalibration
::
rcCalFunctionPitch
]);
Q_ASSERT
(
_rgAttitudeRadioWidget
[
PX4RCCalibration
::
rcCalFunctionYaw
]);
Q_ASSERT
(
_rgAttitudeRadioWidget
[
PX4RCCalibration
::
rcCalFunctionThrottle
]);
for
(
size_t
i
=
0
;
i
<
PX4RCCalibration
::
_chanMax
;
i
++
)
{
QString
radioWidgetName
(
"radio%1Widget"
);
QString
radioWidgetUserName
(
"Radio %1"
);
QGCRadioChannelDisplay
*
radioWidget
=
_calWidget
->
findChild
<
QGCRadioChannelDisplay
*>
(
radioWidgetName
.
arg
(
i
+
1
));
RCChannelWidget
*
radioWidget
=
_calWidget
->
findChild
<
RCChannelWidget
*>
(
radioWidgetName
.
arg
(
i
+
1
));
Q_ASSERT
(
radioWidget
);
radioWidget
->
setOrientation
(
Qt
::
Horizontal
);
radioWidget
->
setName
(
radioWidgetUserName
.
arg
(
i
+
1
));
_rgRadioWidget
[
i
]
=
radioWidget
;
}
}
...
...
@@ -177,7 +158,7 @@ void PX4RCCalibrationTest::_liveRC_test(void)
}
for (int i=0; i<PX4RCCalibration::_chanMax; i++) {
QGCRadioChannelDisplay
* radioWidget = _rgRadioWidget[i];
RCChannelWidget
* radioWidget = _rgRadioWidget[i];
Q_ASSERT(radioWidget);
QCOMPARE(radioWidget->value(), PX4RCCalibration::_rcCalPWMValidMinValue);
...
...
@@ -323,20 +304,9 @@ StartOver:
CHK_BUTTONS
(
cancelButtonMask
);
// Also at this point the radio channel widgets should be displaying the current min/max we just set.
// Check both the Attitude Control widgets as well as generic channel widgets.
Q_ASSERT
(
PX4RCCalibration
::
rcCalFunctionFirstAttitudeFunction
==
0
);
for
(
int
i
=
0
;
i
<
PX4RCCalibration
::
rcCalFunctionLastAttitudeFunction
;
i
++
)
{
QGCRadioChannelDisplay
*
radioWidget
=
_rgAttitudeRadioWidget
[
i
];
Q_ASSERT
(
radioWidget
);
QCOMPARE
(
radioWidget
->
isMinMaxShown
(),
true
);
QCOMPARE
(
radioWidget
->
min
(),
PX4RCCalibration
::
_rcCalPWMValidMinValue
);
QCOMPARE
(
radioWidget
->
max
(),
PX4RCCalibration
::
_rcCalPWMValidMaxValue
);
}
for
(
int
i
=
0
;
i
<
PX4RCCalibration
::
_chanMax
;
i
++
)
{
QGCRadioChannelDisplay
*
radioWidget
=
_rgRadioWidget
[
i
];
RCChannelWidget
*
radioWidget
=
_rgRadioWidget
[
i
];
Q_ASSERT
(
radioWidget
);
QCOMPARE
(
radioWidget
->
isMinMaxShown
(),
true
);
...
...
src/qgcunittest/PX4RCCalibrationTest.h
View file @
e3132e65
...
...
@@ -93,8 +93,7 @@ private:
QPushButton
*
_tryAgainButton
;
QLabel
*
_statusLabel
;
QGCRadioChannelDisplay
*
_rgAttitudeRadioWidget
[
4
];
QGCRadioChannelDisplay
*
_rgRadioWidget
[
PX4RCCalibration
::
_chanMax
];
RCChannelWidget
*
_rgRadioWidget
[
PX4RCCalibration
::
_chanMax
];
};
DECLARE_TEST
(
PX4RCCalibrationTest
)
...
...
src/ui/QGCVehicleConfig.cc
View file @
e3132e65
...
...
@@ -206,14 +206,14 @@ void QGCVehicleConfig::startCalibrationRC()
ui
->
rcCalibrationButton
->
setText
(
tr
(
"Stop RC Calibration"
));
resetCalibrationRC
();
calibrationEnabled
=
true
;
ui
->
rollWidget
->
showMinMax
();
ui
->
pitchWidget
->
showMinMax
();
ui
->
yawWidget
->
showMinMax
();
ui
->
throttleWidget
->
showMinMax
();
ui
->
radio5Widget
->
showMinMax
();
ui
->
radio6Widget
->
showMinMax
();
ui
->
radio7Widget
->
showMinMax
();
ui
->
radio8Widget
->
showMinMax
();
ui
->
rollWidget
->
showMinMax
(
true
);
ui
->
pitchWidget
->
showMinMax
(
true
);
ui
->
yawWidget
->
showMinMax
(
true
);
ui
->
throttleWidget
->
showMinMax
(
true
);
ui
->
radio5Widget
->
showMinMax
(
true
);
ui
->
radio6Widget
->
showMinMax
(
true
);
ui
->
radio7Widget
->
showMinMax
(
true
);
ui
->
radio8Widget
->
showMinMax
(
true
);
}
void
QGCVehicleConfig
::
stopCalibrationRC
()
...
...
@@ -222,14 +222,14 @@ void QGCVehicleConfig::stopCalibrationRC()
calibrationEnabled
=
false
;
ui
->
rcTypeComboBox
->
setEnabled
(
true
);
ui
->
rcCalibrationButton
->
setText
(
tr
(
"Start RC Calibration"
));
ui
->
rollWidget
->
hideMinMax
(
);
ui
->
pitchWidget
->
hideMinMax
(
);
ui
->
yawWidget
->
hideMinMax
(
);
ui
->
throttleWidget
->
hideMinMax
(
);
ui
->
radio5Widget
->
hideMinMax
(
);
ui
->
radio6Widget
->
hideMinMax
(
);
ui
->
radio7Widget
->
hideMinMax
(
);
ui
->
radio8Widget
->
hideMinMax
(
);
ui
->
rollWidget
->
showMinMax
(
false
);
ui
->
pitchWidget
->
showMinMax
(
false
);
ui
->
yawWidget
->
showMinMax
(
false
);
ui
->
throttleWidget
->
showMinMax
(
false
);
ui
->
radio5Widget
->
showMinMax
(
false
);
ui
->
radio6Widget
->
showMinMax
(
false
);
ui
->
radio7Widget
->
showMinMax
(
false
);
ui
->
radio8Widget
->
showMinMax
(
false
);
QString
statusstr
;
statusstr
=
"Below you will find the detected radio calibration information that will be sent to the autopilot
\n
"
;
statusstr
+=
"Normal values are around 1100 to 1900, with disconnected channels reading very close to 1500
\n\n
"
;
...
...
src/ui/configuration/RadioCalibrationConfig.cc
View file @
e3132e65
...
...
@@ -176,14 +176,14 @@ void RadioCalibrationConfig::calibrateButtonClicked()
rcMin
[
i
]
=
1500
;
rcMax
[
i
]
=
1500
;
}
ui
.
rollWidget
->
showMinMax
();
ui
.
pitchWidget
->
showMinMax
();
ui
.
yawWidget
->
showMinMax
();
ui
.
radio5Widget
->
showMinMax
();
ui
.
radio6Widget
->
showMinMax
();
ui
.
radio7Widget
->
showMinMax
();
ui
.
throttleWidget
->
showMinMax
();
ui
.
radio8Widget
->
showMinMax
();
ui
.
rollWidget
->
showMinMax
(
true
);
ui
.
pitchWidget
->
showMinMax
(
true
);
ui
.
yawWidget
->
showMinMax
(
true
);
ui
.
radio5Widget
->
showMinMax
(
true
);
ui
.
radio6Widget
->
showMinMax
(
true
);
ui
.
radio7Widget
->
showMinMax
(
true
);
ui
.
throttleWidget
->
showMinMax
(
true
);
ui
.
radio8Widget
->
showMinMax
(
true
);
QMessageBox
::
information
(
0
,
"Information"
,
"Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches"
);
}
else
...
...
@@ -192,14 +192,14 @@ void RadioCalibrationConfig::calibrateButtonClicked()
QMessageBox
::
information
(
0
,
"Trims"
,
"Ensure all sticks are centered and throttle is in the downmost position, click OK to continue"
);
///TODO: Set trims!
m_calibrationEnabled
=
false
;
ui
.
rollWidget
->
hideMinMax
(
);
ui
.
pitchWidget
->
hideMinMax
(
);
ui
.
yawWidget
->
hideMinMax
(
);
ui
.
radio5Widget
->
hideMinMax
(
);
ui
.
radio6Widget
->
hideMinMax
(
);
ui
.
throttleWidget
->
hideMinMax
(
);
ui
.
radio7Widget
->
hideMinMax
(
);
ui
.
radio8Widget
->
hideMinMax
(
);
ui
.
rollWidget
->
showMinMax
(
false
);
ui
.
pitchWidget
->
showMinMax
(
false
);
ui
.
yawWidget
->
showMinMax
(
false
);
ui
.
radio5Widget
->
showMinMax
(
false
);
ui
.
radio6Widget
->
showMinMax
(
false
);
ui
.
throttleWidget
->
showMinMax
(
false
);
ui
.
radio7Widget
->
showMinMax
(
false
);
ui
.
radio8Widget
->
showMinMax
(
false
);
QString
statusstr
;
statusstr
=
"Below you will find the detected radio calibration information that will be sent to the autopilot
\n
"
;
statusstr
+=
"Normal values are around 1100 to 1900, with disconnected channels reading very close to 1500
\n\n
"
;
...
...
src/ui/designer/RCChannelWidget.cc
0 → 100644
View file @
e3132e65
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "RCChannelWidget.h"
#include <QPainter>
#define DIMMEST_COLOR QColor::fromRgb(0,100,0)
#define MIDBRIGHT_COLOR QColor::fromRgb(0,180,0)
#define BRIGHTEST_COLOR QColor::fromRgb(64,255,0)
RCChannelWidget
::
RCChannelWidget
(
QWidget
*
parent
)
:
QGroupBox
(
parent
),
_value
(
_centerValue
),
_min
(
_centerValue
),
_max
(
_centerValue
),
_trim
(
_centerValue
),
_showMinMax
(
false
),
_showTrim
(
false
)
{
}
/// @brief Draws the control
void
RCChannelWidget
::
paintEvent
(
QPaintEvent
*
event
)
{
// Let the group box draw the outer border
QGroupBox
::
paintEvent
(
event
);
// Now we draw the innner contents
QPainter
painter
(
this
);
int
fontHeight
=
painter
.
fontMetrics
().
height
();
int
rowHeigth
=
fontHeight
+
2
;
painter
.
setBrush
(
Qt
::
Dense4Pattern
);
painter
.
setPen
(
QColor
::
fromRgb
(
128
,
128
,
64
));
int
curVal
=
_value
;
if
(
curVal
>
_maxRange
)
{
curVal
=
_maxRange
;
}
if
(
curVal
<
_minRange
)
{
curVal
=
_minRange
;
}
if
(
isEnabled
())
{
QLinearGradient
hGradientBrush
(
0
,
0
,
this
->
width
(),
this
->
height
());
hGradientBrush
.
setColorAt
(
0.0
,
DIMMEST_COLOR
);
hGradientBrush
.
setColorAt
(
0.5
,
MIDBRIGHT_COLOR
);
hGradientBrush
.
setColorAt
(
1.0
,
BRIGHTEST_COLOR
);
// Calculate how much horizontal space we need to show a min/max value. We must be able to display four numeric
// digits for the rc value, plus we add another digit for spacing.
int
minMaxDisplayWidth
=
painter
.
fontMetrics
().
width
(
"00000"
);
// Draw the value axis line with center and end point tick marks. We need to leave enough space on the left and the right
// for the Min/Max value displays.
QRect
rcValueAxis
(
minMaxDisplayWidth
,
rowHeigth
*
2
,
width
()
-
(
minMaxDisplayWidth
*
2
),
rowHeigth
);
int
yLine
=
rcValueAxis
.
y
()
+
rcValueAxis
.
height
()
/
2
;
painter
.
drawLine
(
rcValueAxis
.
left
(),
yLine
,
rcValueAxis
.
right
(),
yLine
);
painter
.
drawLine
(
rcValueAxis
.
left
(),
rcValueAxis
.
top
(),
rcValueAxis
.
left
(),
rcValueAxis
.
bottom
());
painter
.
drawLine
(
rcValueAxis
.
right
(),
rcValueAxis
.
top
(),
rcValueAxis
.
right
(),
rcValueAxis
.
bottom
());
painter
.
drawLine
(
rcValueAxis
.
left
()
+
rcValueAxis
.
width
()
/
2
,
rcValueAxis
.
top
(),
rcValueAxis
.
left
()
+
rcValueAxis
.
width
()
/
2
,
rcValueAxis
.
bottom
());
painter
.
setPen
(
QColor
::
fromRgb
(
50
,
255
,
50
));
painter
.
setBrush
(
hGradientBrush
);
if
(
_showMinMax
)
{
// Draw the Min numeric value display to the left
painter
.
drawText
(
0
,
rowHeigth
,
minMaxDisplayWidth
,
fontHeight
,
Qt
::
AlignHCenter
|
Qt
::
AlignBottom
,
"Min"
);
painter
.
drawText
(
0
,
rowHeigth
*
2
,
minMaxDisplayWidth
,
fontHeight
,
Qt
::
AlignHCenter
|
Qt
::
AlignBottom
,
QString
::
number
(
_min
));
// Draw the Max numeric value display to the right
painter
.
drawText
(
width
()
-
minMaxDisplayWidth
,
rowHeigth
,
minMaxDisplayWidth
,
fontHeight
,
Qt
::
AlignHCenter
|
Qt
::
AlignBottom
,
"Max"
);
painter
.
drawText
(
width
()
-
minMaxDisplayWidth
,
rowHeigth
*
2
,
minMaxDisplayWidth
,
fontHeight
,
Qt
::
AlignHCenter
|
Qt
::
AlignBottom
,
QString
::
number
(
_max
));
// Draw the Min/Max tick marks on the axis
int
xTick
=
rcValueAxis
.
left
()
+
(
rcValueAxis
.
width
()
*
((
float
)(
_min
-
_minRange
)
/
(
_maxRange
-
_minRange
)));
painter
.
drawLine
(
xTick
,
rcValueAxis
.
top
(),
xTick
,
rcValueAxis
.
bottom
());
xTick
=
rcValueAxis
.
left
()
+
(
rcValueAxis
.
width
()
*
((
float
)(
_max
-
_minRange
)
/
(
_maxRange
-
_minRange
)));
painter
.
drawLine
(
xTick
,
rcValueAxis
.
top
(),
xTick
,
rcValueAxis
.
bottom
());
}
if
(
_showTrim
)
{
// Draw the Trim value pointer
_drawValuePointer
(
&
painter
,
rcValueAxis
.
left
()
+
(
rcValueAxis
.
width
()
*
((
float
)(
_trim
-
_minRange
)
/
(
_maxRange
-
_minRange
))),
// x position for tip of triangle
(
rowHeigth
*
2
)
+
(
rowHeigth
/
2
)
-
1
,
// y position for tip of triangle
rowHeigth
/
2
,
// heigth of triangle
false
);
// draw upside down
// Draw the Trim value label
QString
trimStr
=
tr
(
"Trim %1"
).
arg
(
QString
::
number
(
_trim
));
int
trimTextWidth
=
painter
.
fontMetrics
().
width
(
trimStr
);
painter
.
drawText
(
rcValueAxis
.
left
()
+
(
rcValueAxis
.
width
()
*
((
float
)(
_trim
-
_minRange
)
/
(
_maxRange
-
_minRange
)))
-
(
trimTextWidth
/
2
),
rowHeigth
,
trimTextWidth
,
fontHeight
,
Qt
::
AlignLeft
|
Qt
::
AlignBottom
,
trimStr
);
}
// Draw the RC value pointer
_drawValuePointer
(
&
painter
,
rcValueAxis
.
left
()
+
(
rcValueAxis
.
width
()
*
((
float
)(
curVal
-
_minRange
)
/
(
_maxRange
-
_minRange
))),
// x position for tip of triangle
(
rowHeigth
*
2
)
+
(
rowHeigth
/
2
)
+
1
,
// y position for tip of triangle
rowHeigth
/
2
,
// heigth of triangle
true
);
// draw right side up
// Draw the control value
QString
valueStr
=
QString
::
number
(
_value
);
int
valueTextWidth
=
painter
.
fontMetrics
().
width
(
valueStr
);
painter
.
drawText
(
rcValueAxis
.
left
()
+
(
rcValueAxis
.
width
()
*
((
float
)(
_value
-
_minRange
)
/
(
_maxRange
-
_minRange
)))
-
(
valueTextWidth
/
2
),
rowHeigth
*
3
,
valueTextWidth
,
fontHeight
,
Qt
::
AlignLeft
|
Qt
::
AlignBottom
,
valueStr
);
painter
.
setPen
(
QColor
::
fromRgb
(
0
,
128
,
0
));
painter
.
setBrush
(
hGradientBrush
);
}
else
{
painter
.
setPen
(
QColor
(
Qt
::
gray
));
painter
.
drawText
(
0
,
0
,
width
(),
height
(),
Qt
::
AlignHCenter
|
Qt
::
AlignVCenter
,
tr
(
"not available"
));
}
}
void
RCChannelWidget
::
setValue
(
int
value
)
{
_value
=
value
;
update
();
}
void
RCChannelWidget
::
showMinMax
(
bool
show
)
{
_showMinMax
=
show
;
update
();
}
void
RCChannelWidget
::
showTrim
(
bool
show
)
{
_showTrim
=
show
;
update
();
}
void
RCChannelWidget
::
setValueAndMinMax
(
int
val
,
int
min
,
int
max
)
{
setValue
(
val
);
setMinMax
(
min
,
max
);
}
void
RCChannelWidget
::
setMinMax
(
int
min
,
int
max
)
{
_min
=
min
;
_max
=
max
;
update
();
}
void
RCChannelWidget
::
setTrim
(
int
value
)
{
_trim
=
value
;
update
();
}
/// @brief Draw rc value pointer triangle.
/// @param painter Draw using this painter
/// @param x X position for tip of triangle
/// @param y Y position for tip of triangle
/// @param heigth Height of triangle
/// @param rightSideUp true: draw triangle right side up, false: draw triangle upside down
void
RCChannelWidget
::
_drawValuePointer
(
QPainter
*
painter
,
int
xTip
,
int
yTip
,
int
height
,
bool
rightSideUp
)
{
QPointF
trianglePoints
[
3
];
// Topmost tip of triangle points to value
trianglePoints
[
0
].
setX
(
xTip
);
trianglePoints
[
0
].
setY
(
yTip
);
int
yBottom
;
if
(
rightSideUp
)
{
yBottom
=
yTip
+
height
;
}
else
{
yBottom
=
yTip
-
height
;
}
// Right bottom tip of triangle
trianglePoints
[
1
].
setX
(
xTip
+
(
height
*
0.75
));
trianglePoints
[
1
].
setY
(
yBottom
);
// Left bottom tip of triangle
trianglePoints
[
2
].
setX
(
xTip
-
(
height
*
0.75
));
trianglePoints
[
2
].
setY
(
yBottom
);
painter
->
drawPolygon
(
trianglePoints
,
3
);
}
src/ui/designer/RCChannelWidget.h
0 → 100644
View file @
e3132e65
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#ifndef RCChannelWidget_H
#define RCChannelWidget_H
#include <QGroupBox>
/// @brief RC Channel Widget - UI Widget based on QGroupBox which displays the current calibration settings
/// for an RC channel.
class
RCChannelWidget
:
public
QGroupBox
{
Q_OBJECT
public:
explicit
RCChannelWidget
(
QWidget
*
parent
=
0
);
/// @brief Set the current RC value to display
void
setValue
(
int
value
);
/// @brief Set the current RC Value, Minimum RC Value and Maximum RC Value
void
setValueAndMinMax
(
int
val
,
int
min
,
int
max
);
void
setMinMax
(
int
min
,
int
max
);
/// @brief Sets the Trim value for the channel
void
setTrim
(
int
value
);
int
value
(
void
)
{
return
_value
;
}
///< Returns the current RC Value set in the control
int
min
(
void
)
{
return
_min
;
}
///< Returns the min value set in the control
int
max
(
void
)
{
return
_max
;
}
///< Returns the max values set in the control
int
trim
(
void
)
{
return
_trim
;
}
///< Returns the trim value set in the control
void
showMinMax
(
bool
show
);
bool
isMinMaxShown
()
{
return
_showMinMax
;
}
void
showTrim
(
bool
show
);
bool
isTrimShown
()
{
return
_showTrim
;
}
protected:
virtual
void
paintEvent
(
QPaintEvent
*
event
);
private:
void
_drawValuePointer
(
QPainter
*
painter
,
int
xTip
,
int
yTip
,
int
height
,
bool
rightSideUp
);
int
_value
;
///< Current RC value
int
_min
;
///< Min RC value
int
_max
;
///< Max RC value
int
_trim
;
///< RC Value for Trim position
bool
_showMinMax
;
///< true: show min max values on display
bool
_showTrim
;
///< true: show trim value on display
static
const
int
_centerValue
=
1500
;
///< RC Value which is at center
static
const
int
_maxDeltaRange
=
700
;
///< Delta around center value which is the max range for widget
static
const
int
_minRange
=
_centerValue
-
_maxDeltaRange
;
///< Smallest value widget can display
static
const
int
_maxRange
=
_centerValue
+
_maxDeltaRange
;
///< Largest value widget can display
};
#endif
src/ui/px4_configuration/PX4RCCalibration.cc
View file @
e3132e65
This diff is collapsed.
Click to expand it.
src/ui/px4_configuration/PX4RCCalibration.h
View file @
e3132e65
...
...
@@ -65,6 +65,8 @@ private slots:
void
_setActiveUAS
(
UASInterface
*
uas
);
void
_toggleSpektrumPairing
(
bool
enabled
);
void
_parameterListUpToDate
(
void
);
private:
/// @brief These identify the various controls functions. They are also used as indices into the _rgFunctioInfo
/// aray.
...
...
@@ -124,7 +126,8 @@ private:
void
_writeCalibration
(
bool
trimsOnly
);
void
_resetInternalCalibrationValues
(
void
);
void
_copyAndSetTrims
(
void
);
void
_setInternalCalibrationValuesFromParameters
(
void
);
void
_initializeTrims
(
void
);
void
_rcCalChannelWait
(
bool
firstTime
);
void
_rcCalBegin
(
void
);
...
...
@@ -138,6 +141,7 @@ private:
void
_rcCalSaveCurrentValues
(
void
);
void
_showMinMaxOnRadioWidgets
(
bool
show
);
void
_showTrimOnRadioWidgets
(
bool
show
);
void
_unitTestForceCalState
(
enum
rcCalStates
state
);
...
...
@@ -171,10 +175,12 @@ private:
float
_rcRawValue
[
_chanMax
];
///< Current set of raw channel values
QGCRadioChannelDisplay
*
_rgAttitudeRadioWidget
[
4
];
///< Array of Attitide Function radio channel widgets
QGCRadioChannelDisplay
*
_rgRadioWidget
[
_chanMax
];
///< Array of radio channel widgets
RCChannelWidget
*
_rgRadioWidget
[
_chanMax
];
///< Array of radio channel widgets
UASInterface
*
_mav
;
///< The current MAV
QGCUASParamManagerInterface
*
_paramMgr
;
bool
_parameterListUpToDateSignalled
;
///< true: we have received a parameterListUpToDate signal
Ui
::
PX4RCCalibration
*
_ui
;
...
...
src/ui/px4_configuration/PX4RCCalibration.ui
View file @
e3132e65
This diff is collapsed.
Click to expand it.
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