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
33c9059d
Commit
33c9059d
authored
Dec 05, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Live flight mode config
parent
cfd84bde
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
48 additions
and
127 deletions
+48
-127
APMFlightModesComponent.qml
src/AutoPilotPlugins/APM/APMFlightModesComponent.qml
+9
-50
APMFlightModesComponentController.cc
...AutoPilotPlugins/APM/APMFlightModesComponentController.cc
+24
-63
APMFlightModesComponentController.h
src/AutoPilotPlugins/APM/APMFlightModesComponentController.h
+15
-14
No files found.
src/AutoPilotPlugins/APM/APMFlightModesComponent.qml
View file @
33c9059d
...
@@ -77,11 +77,14 @@ QGCView {
...
@@ -77,11 +77,14 @@ QGCView {
Row
{
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
spacing
:
ScreenTools
.
defaultFontPixelWidth
property
int
index
:
modelData
+
1
property
int
index
:
modelData
+
1
property
var
pwmStrings
:
[
"
PWM 0 - 1230
"
,
"
PWM 1231 - 1360
"
,
"
PWM 1361 - 1490
"
,
"
PWM 1491 - 1620
"
,
"
PWM 1621 - 1749
"
,
"
PWM 1750 +
"
]
QGCLabel
{
QGCLabel
{
anchors.baseline
:
modeCombo
.
baseline
anchors.baseline
:
modeCombo
.
baseline
text
:
"
Flight Mode
"
+
index
+
"
:
"
text
:
"
Flight Mode
"
+
index
+
"
:
"
color
:
controller
.
activeFlightMode
==
index
?
qgcPal
.
buttonHighlight
:
qgcPal
.
text
}
}
FactComboBox
{
FactComboBox
{
...
@@ -91,56 +94,9 @@ QGCView {
...
@@ -91,56 +94,9 @@ QGCView {
indexModel
:
false
indexModel
:
false
}
}
QGCCheckBox
{
QGCLabel
{
id
:
simple
anchors.baseline
:
modeCombo
.
baseline
text
:
"
Simple Mode
"
visible
:
!
controller
.
fixedWing
checked
:
isChecked
()
onClicked
:
{
var
simpleFact
=
controller
.
getParameterFact
(
-
1
,
"
SIMPLE
"
)
if
(
checked
)
{
simpleFact
.
value
|=
1
<<
modelData
}
else
{
simpleFact
.
value
&=
~
modelData
}
}
function
isChecked
()
{
if
(
simple
.
visible
)
{
var
simpleFact
=
controller
.
getParameterFact
(
-
1
,
"
SIMPLE
"
)
return
simpleFact
.
value
&
(
1
<<
modelData
)
}
else
{
return
false
;
}
}
}
QGCCheckBox
{
id
:
superSimple
anchors.baseline
:
modeCombo
.
baseline
anchors.baseline
:
modeCombo
.
baseline
text
:
"
Super Simple Mode
"
text
:
pwmStrings
[
modelData
]
visible
:
!
controller
.
fixedWing
checked
:
isChecked
()
onClicked
:
{
var
simpleFact
=
controller
.
getParameterFact
(
-
1
,
"
SUPER_SIMPLE
"
)
if
(
checked
)
{
simpleFact
.
value
|=
1
<<
modelData
}
else
{
simpleFact
.
value
&=
~
modelData
}
}
function
isChecked
()
{
if
(
superSimple
.
visible
)
{
var
simpleFact
=
controller
.
getParameterFact
(
-
1
,
"
SUPER_SIMPLE
"
)
return
simpleFact
.
value
&
(
1
<<
modelData
)
}
else
{
return
false
;
}
}
}
}
}
}
}
// Repeater - Flight Modes
}
// Repeater - Flight Modes
...
@@ -176,6 +132,9 @@ QGCView {
...
@@ -176,6 +132,9 @@ QGCView {
QGCLabel
{
QGCLabel
{
anchors.baseline
:
optCombo
.
baseline
anchors.baseline
:
optCombo
.
baseline
text
:
"
Channel option
"
+
index
+
"
:
"
text
:
"
Channel option
"
+
index
+
"
:
"
color
:
controller
.
channelOptionEnabled
[
modelData
]
?
qgcPal
.
buttonHighlight
:
qgcPal
.
text
Component.onCompleted
:
console
.
log
(
index
,
controller
.
channelOptionEnabled
[
modelData
])
}
}
FactComboBox
{
FactComboBox
{
...
...
src/AutoPilotPlugins/APM/APMFlightModesComponentController.cc
View file @
33c9059d
...
@@ -29,7 +29,9 @@
...
@@ -29,7 +29,9 @@
#include <QQmlProperty>
#include <QQmlProperty>
APMFlightModesComponentController
::
APMFlightModesComponentController
(
void
)
APMFlightModesComponentController
::
APMFlightModesComponentController
(
void
)
:
_channelCount
(
Vehicle
::
cMaxRcChannels
)
:
_activeFlightMode
(
0
)
,
_channelCount
(
Vehicle
::
cMaxRcChannels
)
,
_fixedWing
(
_vehicle
->
vehicleType
()
==
MAV_TYPE_FIXED_WING
)
{
{
QStringList
usedParams
;
QStringList
usedParams
;
usedParams
<<
"FLTMODE1"
<<
"FLTMODE2"
<<
"FLTMODE3"
<<
"FLTMODE4"
<<
"FLTMODE5"
<<
"FLTMODE6"
;
usedParams
<<
"FLTMODE1"
<<
"FLTMODE2"
<<
"FLTMODE3"
<<
"FLTMODE4"
<<
"FLTMODE5"
<<
"FLTMODE6"
;
...
@@ -37,78 +39,37 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
...
@@ -37,78 +39,37 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
return
;
return
;
}
}
_init
();
_rgChannelOptionEnabled
<<
QVariant
(
false
)
<<
QVariant
(
false
)
<<
QVariant
(
false
)
<<
QVariant
(
false
)
<<
QVariant
(
false
)
<<
QVariant
(
false
);
_validateConfiguration
();
connect
(
_vehicle
,
&
Vehicle
::
rcChannelsChanged
,
this
,
&
APMFlightModesComponentController
::
_rcChannelsChanged
);
connect
(
_vehicle
,
&
Vehicle
::
rcChannelsChanged
,
this
,
&
APMFlightModesComponentController
::
_rcChannelsChanged
);
}
}
void
APMFlightModesComponentController
::
_init
(
void
)
/// Connected to Vehicle::rcChannelsChanged signal
void
APMFlightModesComponentController
::
_rcChannelsChanged
(
int
channelCount
,
int
pwmValues
[
Vehicle
::
cMaxRcChannels
])
{
{
_fixedWing
=
_vehicle
->
vehicleType
()
==
MAV_TYPE_FIXED_WING
;
Q_UNUSED
(
channelCount
);
}
/// This will look for parameter settings which would cause the config to not run correctly.
_activeFlightMode
=
0
;
/// It will set _validConfiguration and _configurationErrors as needed.
void
APMFlightModesComponentController
::
_validateConfiguration
(
void
)
{
_validConfiguration
=
true
;
#if 0
// Make sure switches are valid and within channel range
QStringList switchParams;
QList<int> switchMappings;
switchParams << "RC_MAP_MODE_SW" << "RC_MAP_ACRO_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_OFFB_SW";
for(int i=0; i<switchParams.count(); i++) {
int map = getParameterFact(FactSystem::defaultComponentId, switchParams[i])->rawValue().toInt();
switchMappings << map;
if (map < 0 || map > _channelCount) {
_validConfiguration = false;
_configurationErrors += QString("%1 is set to %2. Mapping must between 0 and %3 (inclusive).\n").arg(switchParams[i]).arg(map).arg(_channelCount);
}
}
// Make sure mode switches are not double-mapped
QStringList attitudeParams;
attitudeParams << "RC_MAP_THROTTLE" << "RC_MAP_YAW" << "RC_MAP_PITCH" << "RC_MAP_ROLL" << "RC_MAP_FLAPS" << "RC_MAP_AUX1" << "RC_MAP_AUX2";
for (int i=0; i<attitudeParams.count(); i++) {
int
channelValue
=
pwmValues
[
4
];
int map = getParameterFact(FactSystem::defaultComponentId, attitudeParams[i])->rawValue().toInt();
if
(
channelValue
!=
-
1
)
{
int
rgThreshold
[]
=
{
1230
,
1360
,
1490
,
1620
,
1749
};
for (int
j=0; j<switchParams.count(); j
++) {
for
(
int
i
=
0
;
i
<
5
;
i
++
)
{
if (
map != 0 && map == switchMappings[j
]) {
if
(
channelValue
<=
rgThreshold
[
i
])
{
_
validConfiguration = false
;
_
activeFlightMode
=
i
+
1
;
_configurationErrors += QString("%1 is set to same channel as %2.\n").arg(switchParams[j]).arg(attitudeParams[i])
;
break
;
}
}
}
}
_activeFlightMode
=
5
;
}
}
emit
activeFlightModeChanged
(
_activeFlightMode
);
// Validate thresholds within range
QStringList thresholdParams;
thresholdParams << "RC_ASSIST_TH" << "RC_AUTO_TH" << "RC_ACRO_TH" << "RC_POSCTL_TH" << "RC_LOITER_TH" << "RC_RETURN_TH" << "RC_OFFB_TH";
foreach(QString thresholdParam, thresholdParams) {
float threshold = getParameterFact(-1, thresholdParam)->rawValue().toFloat();
if (threshold < 0.0f || threshold > 1.0f) {
_validConfiguration = false;
_configurationErrors += QString("%1 is set to %2. Threshold must between 0.0 and 1.0 (inclusive).\n").arg(thresholdParam).arg(threshold);
}
}
#endif
}
/// Connected to Vehicle::rcChannelsChanged signal
for
(
int
i
=
0
;
i
<
6
;
i
++
)
{
void
APMFlightModesComponentController
::
_rcChannelsChanged
(
int
channelCount
,
int
pwmValues
[
Vehicle
::
cMaxRcChannels
])
_rgChannelOptionEnabled
[
i
]
=
QVariant
(
false
);
{
channelValue
=
pwmValues
[
i
+
7
];
for
(
int
channel
=
0
;
channel
<
channelCount
;
channel
++
)
{
if
(
channelValue
!=
-
1
&&
channelValue
>
1800
)
{
_rcValues
[
channel
]
=
pwmValues
[
channel
];
_rgChannelOptionEnabled
[
i
]
=
QVariant
(
true
);
}
}
}
emit
channelOptionEnabledChanged
();
}
}
src/AutoPilotPlugins/APM/APMFlightModesComponentController.h
View file @
33c9059d
...
@@ -42,25 +42,26 @@ class APMFlightModesComponentController : public FactPanelController
...
@@ -42,25 +42,26 @@ class APMFlightModesComponentController : public FactPanelController
public:
public:
APMFlightModesComponentController
(
void
);
APMFlightModesComponentController
(
void
);
Q_PROPERTY
(
int
channelCount
MEMBER
_channelCount
CONSTANT
)
Q_PROPERTY
(
int
activeFlightMode
READ
activeFlightMode
NOTIFY
activeFlightModeChanged
)
Q_PROPERTY
(
bool
fixedWing
MEMBER
_fixedWing
CONSTANT
)
Q_PROPERTY
(
int
channelCount
MEMBER
_channelCount
CONSTANT
)
Q_PROPERTY
(
QString
reservedChannels
MEMBER
_reservedChannels
CONSTANT
)
Q_PROPERTY
(
QVariantList
channelOptionEnabled
READ
channelOptionEnabled
NOTIFY
channelOptionEnabledChanged
)
Q_PROPERTY
(
bool
fixedWing
MEMBER
_fixedWing
CONSTANT
)
int
activeFlightMode
(
void
)
{
return
_activeFlightMode
;
}
QVariantList
channelOptionEnabled
(
void
)
{
return
_rgChannelOptionEnabled
;
}
signals:
void
activeFlightModeChanged
(
int
activeFlightMode
);
void
channelOptionEnabledChanged
(
void
);
private
slots
:
private
slots
:
void
_rcChannelsChanged
(
int
channelCount
,
int
pwmValues
[
Vehicle
::
cMaxRcChannels
]);
void
_rcChannelsChanged
(
int
channelCount
,
int
pwmValues
[
Vehicle
::
cMaxRcChannels
]);
private:
private:
void
_init
(
void
);
int
_activeFlightMode
;
void
_validateConfiguration
(
void
);
int
_channelCount
;
QVariantList
_rgChannelOptionEnabled
;
bool
_fixedWing
;
bool
_fixedWing
;
int
_rcValues
[
Vehicle
::
cMaxRcChannels
];
bool
_validConfiguration
;
QString
_configurationErrors
;
int
_channelCount
;
QString
_reservedChannels
;
};
};
#endif
#endif
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