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
4dab0e1e
Commit
4dab0e1e
authored
Feb 15, 2017
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Handle ArudPilot parameter changes in newer firmwares
parent
1a2ce057
Changes
18
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
18 changed files
with
22488 additions
and
3585 deletions
+22488
-3585
APMCameraComponent.qml
src/AutoPilotPlugins/APM/APMCameraComponent.qml
+33
-18
APMLightsComponent.qml
src/AutoPilotPlugins/APM/APMLightsComponent.qml
+15
-15
APMLightsComponentSummary.qml
src/AutoPilotPlugins/APM/APMLightsComponentSummary.qml
+13
-13
APMTuningComponentCopter.qml
src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml
+1
-1
RadioComponentController.cc
src/AutoPilotPlugins/Common/RadioComponentController.cc
+134
-93
RadioComponentController.h
src/AutoPilotPlugins/Common/RadioComponentController.h
+14
-5
FactCheckBox.qml
src/FactSystem/FactControls/FactCheckBox.qml
+2
-5
FactPanelController.cc
src/FactSystem/FactControls/FactPanelController.cc
+2
-1
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+47
-9
APMParameterFactMetaData.Copter.3.5.xml
...irmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml
+5126
-3392
APMParameterFactMetaData.Plane.3.8.xml
...FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml
+8496
-0
APMParameterFactMetaData.Rover.3.2.xml
...FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml
+8496
-0
APMResources.qrc
src/FirmwarePlugin/APM/APMResources.qrc
+2
-0
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+40
-25
ArduPlaneFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
+26
-4
ArduPlaneFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h
+6
-0
ArduRoverFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
+27
-4
ArduRoverFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h
+8
-0
No files found.
src/AutoPilotPlugins/APM/APMCameraComponent.qml
View file @
4dab0e1e
...
...
@@ -55,21 +55,23 @@ SetupPage {
property
Fact
_mountAngMinPan
:
controller
.
getParameterFact
(
-
1
,
"
MNT_ANGMIN_PAN
"
)
property
Fact
_mountAngMaxPan
:
controller
.
getParameterFact
(
-
1
,
"
MNT_ANGMAX_PAN
"
)
property
Fact
_rc5Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
5_FUNCTION
"
)
property
Fact
_rc6Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
6_FUNCTION
"
)
property
Fact
_rc7Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
7_FUNCTION
"
)
property
Fact
_rc8Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
8_FUNCTION
"
)
property
Fact
_rc9Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
9_FUNCTION
"
)
property
Fact
_rc10Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
10_FUNCTION
"
)
property
Fact
_rc11Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
11_FUNCTION
"
)
property
Fact
_rc12Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
12_FUNCTION
"
)
property
Fact
_rc13Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
13_FUNCTION
"
)
property
Fact
_rc14Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
14_FUNCTION
"
)
property
Fact
_rc5Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
5_FUNCTION
"
)
property
Fact
_rc6Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
6_FUNCTION
"
)
property
Fact
_rc7Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
7_FUNCTION
"
)
property
Fact
_rc8Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
8_FUNCTION
"
)
property
Fact
_rc9Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
9_FUNCTION
"
)
property
Fact
_rc10Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
10_FUNCTION
"
)
property
Fact
_rc11Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
11_FUNCTION
"
)
property
Fact
_rc12Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
12_FUNCTION
"
)
property
Fact
_rc13Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
13_FUNCTION
"
)
property
Fact
_rc14Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
14_FUNCTION
"
)
property
bool
_tiltEnabled
:
false
property
bool
_panEnabled
:
false
property
bool
_rollEnabled
:
false
property
bool
_servoReverseIsBool
:
controller
.
parameterExists
(
-
1
,
"
RC5_REVERSED
"
)
// Gimbal Settings not available on older firmware
property
bool
_showGimbaLSettings
:
controller
.
parameterExists
(
-
1
,
"
MNT_DEFLT_MODE
"
)
...
...
@@ -95,10 +97,17 @@ SetupPage {
loader
.
gimbalOutIndex
=
channel
-
4
loader
.
servoPWMMinFact
=
controller
.
getParameterFact
(
-
1
,
rcPrefix
+
"
MIN
"
)
loader
.
servoPWMMaxFact
=
controller
.
getParameterFact
(
-
1
,
rcPrefix
+
"
MAX
"
)
loader
.
servoReverseFact
=
controller
.
getParameterFact
(
-
1
,
rcPrefix
+
"
REV
"
)
if
(
controller
.
parameterExists
(
-
1
,
"
RC5_REVERSED
"
))
{
// Newer firmware parameter
loader
.
servoReverseFact
=
controller
.
getParameterFact
(
-
1
,
rcPrefix
+
"
REVERSED
"
)
}
else
{
// Older firmware parameter
loader
.
servoReverseFact
=
controller
.
getParameterFact
(
-
1
,
rcPrefix
+
"
REV
"
)
}
}
/// Gimbal output channels are stored in
RC
#_FUNCTION parameters. We need to loop through those
/// Gimbal output channels are stored in
SERVO
#_FUNCTION parameters. We need to loop through those
/// to find them and setup the ui accordindly.
function
calcGimbalOutValues
()
{
gimbalDirectionTiltLoader
.
gimbalOutIndex
=
0
...
...
@@ -108,7 +117,7 @@ SetupPage {
_panEnabled
=
false
_rollEnabled
=
false
for
(
var
channel
=
_firstGimbalOutChannel
;
channel
<=
_lastGimbalOutChannel
;
channel
++
)
{
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
RC
"
+
channel
+
"
_FUNCTION
"
)
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
"
+
channel
+
"
_FUNCTION
"
)
if
(
functionFact
.
value
==
_rcFunctionMountTilt
)
{
_tiltEnabled
=
true
setGimbalSettingsServoInfo
(
gimbalDirectionTiltLoader
,
channel
)
...
...
@@ -125,7 +134,7 @@ SetupPage {
function
setRCFunction
(
channel
,
rcFunction
)
{
// First clear any previous settings for this function
for
(
var
index
=
_firstGimbalOutChannel
;
index
<=
_lastGimbalOutChannel
;
index
++
)
{
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
RC
"
+
index
+
"
_FUNCTION
"
)
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
"
+
index
+
"
_FUNCTION
"
)
if
(
functionFact
.
value
!=
_rcFunctionDisabled
&&
functionFact
.
value
==
rcFunction
)
{
functionFact
.
value
=
_rcFunctionDisabled
}
...
...
@@ -133,12 +142,12 @@ SetupPage {
// Now set the function into the new channel
if
(
channel
!=
0
)
{
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
RC
"
+
channel
+
"
_FUNCTION
"
)
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
"
+
channel
+
"
_FUNCTION
"
)
functionFact
.
value
=
rcFunction
}
}
// Whenever any
RC#_FUNCTION parameters chagn
es we need to go looking for gimbal output channels again
// Whenever any
SERVO#_FUNCTION parameters chang
es we need to go looking for gimbal output channels again
Connections
{
target
:
_rc5Function
;
onValueChanged
:
calcGimbalOutValues
()
}
Connections
{
target
:
_rc6Function
;
onValueChanged
:
calcGimbalOutValues
()
}
Connections
{
target
:
_rc7Function
;
onValueChanged
:
calcGimbalOutValues
()
}
...
...
@@ -195,6 +204,7 @@ SetupPage {
// property Fact servoPWMMinFact
// property Fact servoPWMMaxFact
// property Fact servoReverseFact
// property bool servoReverseIsBool
// property int rcFunction
Item
{
...
...
@@ -234,10 +244,12 @@ SetupPage {
anchors.top
:
mountStabCheckBox
.
bottom
anchors.right
:
parent
.
right
text
:
qsTr
(
"
Servo reverse
"
)
checkedValue
:
1
uncheckedValue
:
0
checkedValue
:
_servoReverseIsBool
?
1
:
-
1
uncheckedValue
:
_servoReverseIsBool
?
0
:
1
fact
:
servoReverseFact
enabled
:
directionEnabled
property
bool
_servoReverseIsBool
:
servoReverseIsBool
}
QGCLabel
{
...
...
@@ -462,6 +474,7 @@ SetupPage {
property
Fact
servoPWMMinFact
:
Fact
{
}
property
Fact
servoPWMMaxFact
:
Fact
{
}
property
Fact
servoReverseFact
:
Fact
{
}
property
bool
servoReverseIsBool
:
_servoReverseIsBool
property
int
rcFunction
:
_rcFunctionMountTilt
}
...
...
@@ -479,6 +492,7 @@ SetupPage {
property
Fact
servoPWMMinFact
:
Fact
{
}
property
Fact
servoPWMMaxFact
:
Fact
{
}
property
Fact
servoReverseFact
:
Fact
{
}
property
bool
servoReverseIsBool
:
_servoReverseIsBool
property
int
rcFunction
:
_rcFunctionMountRoll
}
...
...
@@ -496,6 +510,7 @@ SetupPage {
property
Fact
servoPWMMinFact
:
Fact
{
}
property
Fact
servoPWMMaxFact
:
Fact
{
}
property
Fact
servoReverseFact
:
Fact
{
}
property
bool
servoReverseIsBool
:
_servoReverseIsBool
property
int
rcFunction
:
_rcFunctionMountPan
}
...
...
src/AutoPilotPlugins/APM/APMLightsComponent.qml
View file @
4dab0e1e
...
...
@@ -32,16 +32,16 @@ SetupPage {
QGCPalette
{
id
:
palette
;
colorGroupEnabled
:
true
}
property
Fact
_rc5Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
5_FUNCTION
"
)
property
Fact
_rc6Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
6_FUNCTION
"
)
property
Fact
_rc7Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
7_FUNCTION
"
)
property
Fact
_rc8Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
8_FUNCTION
"
)
property
Fact
_rc9Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
9_FUNCTION
"
)
property
Fact
_rc10Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
10_FUNCTION
"
)
property
Fact
_rc11Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
11_FUNCTION
"
)
property
Fact
_rc12Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
12_FUNCTION
"
)
property
Fact
_rc13Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
13_FUNCTION
"
)
property
Fact
_rc14Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
14_FUNCTION
"
)
property
Fact
_rc5Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
5_FUNCTION
"
)
property
Fact
_rc6Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
6_FUNCTION
"
)
property
Fact
_rc7Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
7_FUNCTION
"
)
property
Fact
_rc8Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
8_FUNCTION
"
)
property
Fact
_rc9Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
9_FUNCTION
"
)
property
Fact
_rc10Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
10_FUNCTION
"
)
property
Fact
_rc11Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
11_FUNCTION
"
)
property
Fact
_rc12Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
12_FUNCTION
"
)
property
Fact
_rc13Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
13_FUNCTION
"
)
property
Fact
_rc14Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
14_FUNCTION
"
)
readonly
property
real
_margins
:
ScreenTools
.
defaultFontPixelHeight
readonly
property
int
_rcFunctionDisabled
:
0
...
...
@@ -54,13 +54,13 @@ SetupPage {
calcLightOutValues
()
}
/// Light output channels are stored in
RC
#_FUNCTION parameters. We need to loop through those
/// Light output channels are stored in
SERVO
#_FUNCTION parameters. We need to loop through those
/// to find them and setup the ui accordindly.
function
calcLightOutValues
()
{
lightsLoader
.
lights1OutIndex
=
0
lightsLoader
.
lights2OutIndex
=
0
for
(
var
channel
=
_firstLightsOutChannel
;
channel
<=
_lastLightsOutChannel
;
channel
++
)
{
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
RC
"
+
channel
+
"
_FUNCTION
"
)
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
"
+
channel
+
"
_FUNCTION
"
)
if
(
functionFact
.
value
==
_rcFunctionRCIN9
)
{
lightsLoader
.
lights1OutIndex
=
channel
-
4
}
else
if
(
functionFact
.
value
==
_rcFunctionRCIN10
)
{
...
...
@@ -72,7 +72,7 @@ SetupPage {
function
setRCFunction
(
channel
,
rcFunction
)
{
// First clear any previous settings for this function
for
(
var
index
=
_firstLightsOutChannel
;
index
<=
_lastLightsOutChannel
;
index
++
)
{
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
RC
"
+
index
+
"
_FUNCTION
"
)
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
"
+
index
+
"
_FUNCTION
"
)
if
(
functionFact
.
value
!=
_rcFunctionDisabled
&&
functionFact
.
value
==
rcFunction
)
{
functionFact
.
value
=
_rcFunctionDisabled
}
...
...
@@ -80,12 +80,12 @@ SetupPage {
// Now set the function into the new channel
if
(
channel
!=
0
)
{
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
RC
"
+
channel
+
"
_FUNCTION
"
)
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
"
+
channel
+
"
_FUNCTION
"
)
functionFact
.
value
=
rcFunction
}
}
// Whenever any
RC
#_FUNCTION parameters chagnes we need to go looking for light output channels again
// Whenever any
SERVO
#_FUNCTION parameters chagnes we need to go looking for light output channels again
Connections
{
target
:
_rc5Function
;
onValueChanged
:
calcLightOutValues
()
}
Connections
{
target
:
_rc6Function
;
onValueChanged
:
calcLightOutValues
()
}
Connections
{
target
:
_rc7Function
;
onValueChanged
:
calcLightOutValues
()
}
...
...
src/AutoPilotPlugins/APM/APMLightsComponentSummary.qml
View file @
4dab0e1e
...
...
@@ -14,16 +14,16 @@ FactPanel {
QGCPalette
{
id
:
qgcPal
;
colorGroupEnabled
:
enabled
}
FactPanelController
{
id
:
controller
;
factPanel
:
panel
}
property
Fact
_rc5Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
5_FUNCTION
"
)
property
Fact
_rc6Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
6_FUNCTION
"
)
property
Fact
_rc7Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
7_FUNCTION
"
)
property
Fact
_rc8Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
8_FUNCTION
"
)
property
Fact
_rc9Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
9_FUNCTION
"
)
property
Fact
_rc10Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
10_FUNCTION
"
)
property
Fact
_rc11Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
11_FUNCTION
"
)
property
Fact
_rc12Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
12_FUNCTION
"
)
property
Fact
_rc13Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
13_FUNCTION
"
)
property
Fact
_rc14Function
:
controller
.
getParameterFact
(
-
1
,
"
RC
14_FUNCTION
"
)
property
Fact
_rc5Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
5_FUNCTION
"
)
property
Fact
_rc6Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
6_FUNCTION
"
)
property
Fact
_rc7Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
7_FUNCTION
"
)
property
Fact
_rc8Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
8_FUNCTION
"
)
property
Fact
_rc9Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
9_FUNCTION
"
)
property
Fact
_rc10Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
10_FUNCTION
"
)
property
Fact
_rc11Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
11_FUNCTION
"
)
property
Fact
_rc12Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
12_FUNCTION
"
)
property
Fact
_rc13Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
13_FUNCTION
"
)
property
Fact
_rc14Function
:
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
14_FUNCTION
"
)
readonly
property
int
_rcFunctionRCIN9
:
59
readonly
property
int
_rcFunctionRCIN10
:
60
...
...
@@ -34,13 +34,13 @@ FactPanel {
calcLightOutValues
()
}
/// Light output channels are stored in
RC
#_FUNCTION parameters. We need to loop through those
/// Light output channels are stored in
SERVO
#_FUNCTION parameters. We need to loop through those
/// to find them and setup the ui accordindly.
function
calcLightOutValues
()
{
lightsLoader
.
lights1OutIndex
=
0
lightsLoader
.
lights2OutIndex
=
0
for
(
var
channel
=
_firstLightsOutChannel
;
channel
<=
_lastLightsOutChannel
;
channel
++
)
{
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
RC
"
+
channel
+
"
_FUNCTION
"
)
var
functionFact
=
controller
.
getParameterFact
(
-
1
,
"
r.SERVO
"
+
channel
+
"
_FUNCTION
"
)
if
(
functionFact
.
value
==
_rcFunctionRCIN9
)
{
lightsLoader
.
lights1OutIndex
=
channel
-
4
}
else
if
(
functionFact
.
value
==
_rcFunctionRCIN10
)
{
...
...
@@ -49,7 +49,7 @@ FactPanel {
}
}
// Whenever any
RC
#_FUNCTION parameters chagnes we need to go looking for light output channels again
// Whenever any
SERVO
#_FUNCTION parameters chagnes we need to go looking for light output channels again
Connections
{
target
:
_rc5Function
;
onValueChanged
:
calcLightOutValues
()
}
Connections
{
target
:
_rc6Function
;
onValueChanged
:
calcLightOutValues
()
}
Connections
{
target
:
_rc7Function
;
onValueChanged
:
calcLightOutValues
()
}
...
...
src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml
View file @
4dab0e1e
...
...
@@ -84,7 +84,7 @@ SetupPage {
calcAutoTuneChannel
()
}
/// The AutoTune switch is stored in one of the
RC#_FUNCTION
parameters. We need to loop through those
/// The AutoTune switch is stored in one of the
CH#_OPT
parameters. We need to loop through those
/// to find them and setup the ui accordindly.
function
calcAutoTuneChannel
()
{
_autoTuneSwitchChannelIndex
=
0
...
...
src/AutoPilotPlugins/Common/RadioComponentController.cc
View file @
4dab0e1e
This diff is collapsed.
Click to expand it.
src/AutoPilotPlugins/Common/RadioComponentController.h
View file @
4dab0e1e
...
...
@@ -24,6 +24,7 @@
#include "AutoPilotPlugin.h"
Q_DECLARE_LOGGING_CATEGORY
(
RadioComponentControllerLog
)
Q_DECLARE_LOGGING_CATEGORY
(
RadioComponentControllerVerboseLog
)
class
RadioConfigest
;
...
...
@@ -232,7 +233,10 @@ private:
void
_signalAllAttiudeValueChanges
(
void
);
int
_chanMax
(
void
)
const
;
bool
_channelReversedParamValue
(
int
channel
);
void
_setChannelReversedParamValue
(
int
channel
,
bool
reversed
);
// @brief Called by unit test code to set the mode to unit testing
void
_setUnitTestMode
(
void
){
_unitTestMode
=
true
;
}
...
...
@@ -259,20 +263,20 @@ private:
int
_transmitterMode
;
///< 1: transmitter is mode 1, 2: transmitted is mode 2
static
const
int
_updateInterval
;
///< Interval for ui update timer
static
const
struct
FunctionInfo
_rgFunctionInfoAPM
[
rcCalFunctionMax
];
///< Information associated with each function, PX4 firmware
static
const
struct
FunctionInfo
_rgFunctionInfoPX4
[
rcCalFunctionMax
];
///< Information associated with each function, APM firmware
int
_rgFunctionChannelMapping
[
rcCalFunctionMax
];
///< Maps from rcCalFunctions to channel index. _chanMax indicates channel not set for this function.
static
const
int
_attitudeControls
=
5
;
int
_chanCount
;
///< Number of actual rc channels available
static
const
int
_chanMaxPX4
=
18
;
///< Maximum number of supported rc channels, PX4 Firmware
static
const
int
_chanMaxAPM
=
14
;
///< Maximum number of supported rc channels, APM firmware
static
const
int
_chanMaxAny
=
18
;
///< Maximum number of support rc channels by this implementation
static
const
int
_chanMinimum
=
5
;
///< Minimum numner of channels required to run
struct
ChannelInfo
_rgChannelInfo
[
_chanMaxAny
];
///< Information associated with each rc channel
QList
<
int
>
_apmPossibleMissingRCChannelParams
;
///< List of possible missing RC*_* params for APM stack
...
...
@@ -292,7 +296,12 @@ private:
static
const
int
_rcCalMoveDelta
;
static
const
int
_rcCalSettleDelta
;
static
const
int
_rcCalMinDelta
;
static
const
char
*
_px4RevParamFormat
;
static
const
char
*
_apmNewRevParamFormat
;
QString
_revParamFormat
;
bool
_revParamIsBool
;
int
_rcValueSave
[
_chanMaxAny
];
///< Saved values prior to detecting channel movement
int
_rcRawValue
[
_chanMaxAny
];
///< Current set of raw channel values
...
...
src/FactSystem/FactControls/FactCheckBox.qml
View file @
4dab0e1e
...
...
@@ -11,12 +11,9 @@ QGCCheckBox {
property
variant
checkedValue
:
1
property
variant
uncheckedValue
:
0
partiallyCheckedEnabled
:
fact
?
fact
.
value
!==
checkedValue
&&
fact
.
value
!==
uncheckedValue
:
false
checkedState
:
fact
?
fact
.
value
===
checkedValue
?
Qt
.
Checked
:
(
fact
.
value
===
uncheckedValue
?
Qt
.
Unchecked
:
Qt
.
PartiallyChecked
)
:
false
checkedState
:
fact
?
(
fact
.
value
===
checkedValue
?
Qt
.
Checked
:
Qt
.
Unchecked
)
:
Qt
.
Unchecked
text
:
qsTr
(
"
Label
"
)
onClicked
:
{
fact
.
value
=
checked
?
checkedValue
:
uncheckedValue
}
onClicked
:
fact
.
value
=
checked
?
checkedValue
:
uncheckedValue
}
src/FactSystem/FactControls/FactPanelController.cc
View file @
4dab0e1e
...
...
@@ -127,8 +127,9 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name
QQmlEngine
::
setObjectOwnership
(
fact
,
QQmlEngine
::
CppOwnership
);
return
fact
;
}
else
{
if
(
reportMissing
)
if
(
reportMissing
)
{
_reportMissingParameter
(
componentId
,
name
);
}
return
NULL
;
}
}
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
4dab0e1e
...
...
@@ -735,6 +735,9 @@ void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketErr
QString
APMFirmwarePlugin
::
internalParameterMetaDataFile
(
Vehicle
*
vehicle
)
{
int
majorVersion
=
vehicle
->
firmwareMajorVersion
();
int
minorVersion
=
vehicle
->
firmwareMinorVersion
();
switch
(
vehicle
->
vehicleType
())
{
case
MAV_TYPE_QUADROTOR
:
case
MAV_TYPE_HEXAROTOR
:
...
...
@@ -742,22 +745,57 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case
MAV_TYPE_TRICOPTER
:
case
MAV_TYPE_COAXIAL
:
case
MAV_TYPE_HELICOPTER
:
if
(
vehicle
->
firmwareMajorVersion
()
<
3
||
(
vehicle
->
firmwareMajorVersion
()
==
3
&&
vehicle
->
firmwareMinorVersion
()
<=
3
)
)
{
if
(
majorVersion
<
3
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"
);
}
else
if
(
vehicle
->
firmwareMajorVersion
()
==
3
&&
vehicle
->
firmwareMinorVersion
()
==
4
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml"
);
}
else
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"
);
}
else
if
(
majorVersion
==
3
)
{
switch
(
minorVersion
)
{
case
3
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"
);
case
4
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml"
);
case
5
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"
);
default:
if
(
minorVersion
<
3
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"
);
}
}
}
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"
);
case
MAV_TYPE_FIXED_WING
:
if
(
vehicle
->
firmwareMajorVersion
()
<
3
||
(
vehicle
->
firmwareMajorVersion
()
==
3
&&
vehicle
->
firmwareMinorVersion
()
<=
3
)
)
{
if
(
majorVersion
<
3
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"
);
}
else
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml"
);
}
else
if
(
majorVersion
==
3
)
{
switch
(
minorVersion
)
{
case
3
:
case
4
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"
);
case
5
:
case
6
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml"
);
case
7
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.7.xml"
);
default:
if
(
minorVersion
<
3
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"
);
}
}
}
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml"
);
case
MAV_TYPE_GROUND_ROVER
:
case
MAV_TYPE_SURFACE_BOAT
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"
);
if
(
majorVersion
<
3
)
{
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"
);
}
else
if
(
majorVersion
==
3
)
{
switch
(
minorVersion
)
{
case
0
:
case
1
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"
);
default:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"
);
}
}
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"
);
case
MAV_TYPE_SUBMARINE
:
return
QStringLiteral
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml"
);
default:
...
...
src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml
View file @
4dab0e1e
This diff is collapsed.
Click to expand it.
src/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml
0 → 100644
View file @
4dab0e1e
This diff is collapsed.
Click to expand it.
src/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml
0 → 100644
View file @
4dab0e1e
This diff is collapsed.
Click to expand it.
src/FirmwarePlugin/APM/APMResources.qrc
View file @
4dab0e1e
...
...
@@ -43,10 +43,12 @@
<file alias="APMParameterFactMetaData.Plane.3.3.xml">APMParameterFactMetaData.Plane.3.3.xml</file>
<file alias="APMParameterFactMetaData.Plane.3.5.xml">APMParameterFactMetaData.Plane.3.5.xml</file>
<file alias="APMParameterFactMetaData.Plane.3.7.xml">APMParameterFactMetaData.Plane.3.7.xml</file>
<file alias="APMParameterFactMetaData.Plane.3.8.xml">APMParameterFactMetaData.Plane.3.8.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.3.xml">APMParameterFactMetaData.Copter.3.3.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.4.xml">APMParameterFactMetaData.Copter.3.4.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.5.xml">APMParameterFactMetaData.Copter.3.5.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.0.xml">APMParameterFactMetaData.Rover.3.0.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.2.xml">APMParameterFactMetaData.Rover.3.2.xml</file>
<file alias="APMParameterFactMetaData.Sub.3.4.xml">APMParameterFactMetaData.Sub.3.4.xml</file>
<file alias="CopterGeoFenceEditor.qml">CopterGeoFenceEditor.qml</file>
<file alias="PlaneGeoFenceEditor.qml">PlaneGeoFenceEditor.qml</file>
...
...
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
4dab0e1e
...
...
@@ -67,36 +67,51 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
setSupportedModes
(
supportedFlightModes
);
if
(
!
_remapParamNameIntialized
)
{
FirmwarePlugin
::
remapParamNameMap_t
&
remap
=
_remapParamName
[
3
][
4
];
remap
[
"ATC_ANG_RLL_P"
]
=
QStringLiteral
(
"STB_RLL_P"
);
remap
[
"ATC_ANG_PIT_P"
]
=
QStringLiteral
(
"STB_PIT_P"
);
remap
[
"ATC_ANG_YAW_P"
]
=
QStringLiteral
(
"STB_YAW_P"
);
remap
[
"ATC_RAT_RLL_P"
]
=
QStringLiteral
(
"RATE_RLL_P"
);
remap
[
"ATC_RAT_RLL_I"
]
=
QStringLiteral
(
"RATE_RLL_I"
);
remap
[
"ATC_RAT_RLL_IMAX"
]
=
QStringLiteral
(
"RATE_RLL_IMAX"
);
remap
[
"ATC_RAT_RLL_D"
]
=
QStringLiteral
(
"RATE_RLL_D"
);
remap
[
"ATC_RAT_RLL_FILT"
]
=
QStringLiteral
(
"RATE_RLL_FILT_HZ"
);
remap
[
"ATC_RAT_PIT_P"
]
=
QStringLiteral
(
"RATE_PIT_P"
);
remap
[
"ATC_RAT_PIT_I"
]
=
QStringLiteral
(
"RATE_PIT_I"
);
remap
[
"ATC_RAT_PIT_IMAX"
]
=
QStringLiteral
(
"RATE_PIT_IMAX"
);
remap
[
"ATC_RAT_PIT_D"
]
=
QStringLiteral
(
"RATE_PIT_D"
);
remap
[
"ATC_RAT_PIT_FILT"
]
=
QStringLiteral
(
"RATE_PIT_FILT_HZ"
);
remap
[
"ATC_RAT_YAW_P"
]
=
QStringLiteral
(
"RATE_YAW_P"
);
remap
[
"ATC_RAT_YAW_I"
]
=
QStringLiteral
(
"RATE_YAW_I"
);
remap
[
"ATC_RAT_YAW_IMAX"
]
=
QStringLiteral
(
"RATE_YAW_IMAX"
);
remap
[
"ATC_RAT_YAW_D"
]
=
QStringLiteral
(
"RATE_YAW_D"
);
remap
[
"ATC_RAT_YAW_FILT"
]
=
QStringLiteral
(
"RATE_YAW_FILT_HZ"
);
FirmwarePlugin
::
remapParamNameMap_t
&
remapV3_4
=
_remapParamName
[
3
][
4
];
remapV3_4
[
"ATC_ANG_RLL_P"
]
=
QStringLiteral
(
"STB_RLL_P"
);
remapV3_4
[
"ATC_ANG_PIT_P"
]
=
QStringLiteral
(
"STB_PIT_P"
);
remapV3_4
[
"ATC_ANG_YAW_P"
]
=
QStringLiteral
(
"STB_YAW_P"
);
remapV3_4
[
"ATC_RAT_RLL_P"
]
=
QStringLiteral
(
"RATE_RLL_P"
);
remapV3_4
[
"ATC_RAT_RLL_I"
]
=
QStringLiteral
(
"RATE_RLL_I"
);
remapV3_4
[
"ATC_RAT_RLL_IMAX"
]
=
QStringLiteral
(
"RATE_RLL_IMAX"
);
remapV3_4
[
"ATC_RAT_RLL_D"
]
=
QStringLiteral
(
"RATE_RLL_D"
);
remapV3_4
[
"ATC_RAT_RLL_FILT"
]
=
QStringLiteral
(
"RATE_RLL_FILT_HZ"
);
remapV3_4
[
"ATC_RAT_PIT_P"
]
=
QStringLiteral
(
"RATE_PIT_P"
);
remapV3_4
[
"ATC_RAT_PIT_I"
]
=
QStringLiteral
(
"RATE_PIT_I"
);
remapV3_4
[
"ATC_RAT_PIT_IMAX"
]
=
QStringLiteral
(
"RATE_PIT_IMAX"
);
remapV3_4
[
"ATC_RAT_PIT_D"
]
=
QStringLiteral
(
"RATE_PIT_D"
);
remapV3_4
[
"ATC_RAT_PIT_FILT"
]
=
QStringLiteral
(
"RATE_PIT_FILT_HZ"
);
remapV3_4
[
"ATC_RAT_YAW_P"
]
=
QStringLiteral
(
"RATE_YAW_P"
);
remapV3_4
[
"ATC_RAT_YAW_I"
]
=
QStringLiteral
(
"RATE_YAW_I"
);
remapV3_4
[
"ATC_RAT_YAW_IMAX"
]
=
QStringLiteral
(
"RATE_YAW_IMAX"
);
remapV3_4
[
"ATC_RAT_YAW_D"
]
=
QStringLiteral
(
"RATE_YAW_D"
);
remapV3_4
[
"ATC_RAT_YAW_FILT"
]
=
QStringLiteral
(
"RATE_YAW_FILT_HZ"
);
FirmwarePlugin
::
remapParamNameMap_t
&
remapV3_5
=
_remapParamName
[
3
][
5
];
remapV3_5
[
"SERVO5_FUNCTION"
]
=
QStringLiteral
(
"RC5_FUNCTION"
);
remapV3_5
[
"SERVO6_FUNCTION"
]
=
QStringLiteral
(
"RC6_FUNCTION"
);
remapV3_5
[
"SERVO7_FUNCTION"
]
=
QStringLiteral
(
"RC7_FUNCTION"
);
remapV3_5
[
"SERVO8_FUNCTION"
]
=
QStringLiteral
(
"RC8_FUNCTION"
);
remapV3_5
[
"SERVO9_FUNCTION"
]
=
QStringLiteral
(
"RC9_FUNCTION"
);
remapV3_5
[
"SERVO10_FUNCTION"
]
=
QStringLiteral
(
"RC10_FUNCTION"
);
remapV3_5
[
"SERVO11_FUNCTION"
]
=
QStringLiteral
(
"RC11_FUNCTION"
);
remapV3_5
[
"SERVO12_FUNCTION"
]
=
QStringLiteral
(
"RC12_FUNCTION"
);
remapV3_5
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_5
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
_remapParamNameIntialized
=
true
;
}
}
int
ArduCopterFirmwarePlugin
::
remapParamNameHigestMinorVersionNumber
(
int
majorVersionNumber
)
const
{
// Remapping supports up to 3.
4
return
majorVersionNumber
==
3
?
4
:
Vehicle
::
versionNotSetValue
;
// Remapping supports up to 3.
5
return
majorVersionNumber
==
3
?
5
:
Vehicle
::
versionNotSetValue
;
}
bool
ArduCopterFirmwarePlugin
::
isCapable
(
const
Vehicle
*
vehicle
,
FirmwareCapabilities
capabilities
)
...
...
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
View file @
4dab0e1e
...
...
@@ -7,12 +7,11 @@
*
****************************************************************************/
/// @file
/// @author Pritam Ghanghas <pritam.ghanghas@gmail.com>
#include "ArduPlaneFirmwarePlugin.h"
bool
ArduPlaneFirmwarePlugin
::
_remapParamNameIntialized
=
false
;
FirmwarePlugin
::
remapParamNameMajorVersionMap_t
ArduPlaneFirmwarePlugin
::
_remapParamName
;
APMPlaneMode
::
APMPlaneMode
(
uint32_t
mode
,
bool
settable
)
:
APMCustomMode
(
mode
,
settable
)
{
...
...
@@ -63,6 +62,29 @@ ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(void)
supportedFlightModes
<<
APMPlaneMode
(
APMPlaneMode
::
QLAND
,
true
);
supportedFlightModes
<<
APMPlaneMode
(
APMPlaneMode
::
QRTL
,
true
);
setSupportedModes
(
supportedFlightModes
);
if
(
!
_remapParamNameIntialized
)
{
FirmwarePlugin
::
remapParamNameMap_t
&
remapV3_8
=
_remapParamName
[
3
][
8
];
remapV3_8
[
"SERVO5_FUNCTION"
]
=
QStringLiteral
(
"RC5_FUNCTION"
);
remapV3_8
[
"SERVO6_FUNCTION"
]
=
QStringLiteral
(
"RC6_FUNCTION"
);
remapV3_8
[
"SERVO7_FUNCTION"
]
=
QStringLiteral
(
"RC7_FUNCTION"
);
remapV3_8
[
"SERVO8_FUNCTION"
]
=
QStringLiteral
(
"RC8_FUNCTION"
);
remapV3_8
[
"SERVO9_FUNCTION"
]
=
QStringLiteral
(
"RC9_FUNCTION"
);
remapV3_8
[
"SERVO10_FUNCTION"
]
=
QStringLiteral
(
"RC10_FUNCTION"
);
remapV3_8
[
"SERVO11_FUNCTION"
]
=
QStringLiteral
(
"RC11_FUNCTION"
);
remapV3_8
[
"SERVO12_FUNCTION"
]
=
QStringLiteral
(
"RC12_FUNCTION"
);
remapV3_8
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_8
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
_remapParamNameIntialized
=
true
;
}
}
int
ArduPlaneFirmwarePlugin
::
remapParamNameHigestMinorVersionNumber
(
int
majorVersionNumber
)
const
{
// Remapping supports up to 3.8
return
majorVersionNumber
==
3
?
8
:
Vehicle
::
versionNotSetValue
;
}
QString
ArduPlaneFirmwarePlugin
::
takeControlFlightMode
(
void
)
...
...
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h
View file @
4dab0e1e
...
...
@@ -58,6 +58,12 @@ public:
// Overrides from FirmwarePlugin
QString
offlineEditingParamFile
(
Vehicle
*
vehicle
)
final
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
":/FirmwarePlugin/APM/Plane.OfflineEditing.params"
);
}
QString
takeControlFlightMode
(
void
)
final
;
const
FirmwarePlugin
::
remapParamNameMajorVersionMap_t
&
paramNameRemapMajorVersionMap
(
void
)
const
final
{
return
_remapParamName
;
}
int
remapParamNameHigestMinorVersionNumber
(
int
majorVersionNumber
)
const
final
;
private:
static
bool
_remapParamNameIntialized
;
static
FirmwarePlugin
::
remapParamNameMajorVersionMap_t
_remapParamName
;
};
#endif
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
View file @
4dab0e1e
...
...
@@ -7,12 +7,11 @@
*
****************************************************************************/
/// @file
/// @author Pritam Ghanghas <pritam.ghanghas@gmail.com>
#include "ArduRoverFirmwarePlugin.h"
bool
ArduRoverFirmwarePlugin
::
_remapParamNameIntialized
=
false
;
FirmwarePlugin
::
remapParamNameMajorVersionMap_t
ArduRoverFirmwarePlugin
::
_remapParamName
;
APMRoverMode
::
APMRoverMode
(
uint32_t
mode
,
bool
settable
)
:
APMCustomMode
(
mode
,
settable
)
{
...
...
@@ -41,4 +40,28 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void)
supportedFlightModes
<<
APMRoverMode
(
APMRoverMode
::
GUIDED
,
true
);
supportedFlightModes
<<
APMRoverMode
(
APMRoverMode
::
INITIALIZING
,
false
);
setSupportedModes
(
supportedFlightModes
);
if
(
!
_remapParamNameIntialized
)
{
FirmwarePlugin
::
remapParamNameMap_t
&
remapV3_2
=
_remapParamName
[
3
][
2
];
remapV3_2
[
"SERVO5_FUNCTION"
]
=
QStringLiteral
(
"RC5_FUNCTION"
);
remapV3_2
[
"SERVO6_FUNCTION"
]
=
QStringLiteral
(
"RC6_FUNCTION"
);
remapV3_2
[
"SERVO7_FUNCTION"
]
=
QStringLiteral
(
"RC7_FUNCTION"
);
remapV3_2
[
"SERVO8_FUNCTION"
]
=
QStringLiteral
(
"RC8_FUNCTION"
);
remapV3_2
[
"SERVO9_FUNCTION"
]
=
QStringLiteral
(
"RC9_FUNCTION"
);
remapV3_2
[
"SERVO10_FUNCTION"
]
=
QStringLiteral
(
"RC10_FUNCTION"
);
remapV3_2
[
"SERVO11_FUNCTION"
]
=
QStringLiteral
(
"RC11_FUNCTION"
);
remapV3_2
[
"SERVO12_FUNCTION"
]
=
QStringLiteral
(
"RC12_FUNCTION"
);
remapV3_2
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_2
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
_remapParamNameIntialized
=
true
;
}
}
int
ArduRoverFirmwarePlugin
::
remapParamNameHigestMinorVersionNumber
(
int
majorVersionNumber
)
const
{
// Remapping supports up to 3.2
return
majorVersionNumber
==
3
?
2
:
Vehicle
::
versionNotSetValue
;
}
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h
View file @
4dab0e1e
...
...
@@ -49,6 +49,14 @@ class ArduRoverFirmwarePlugin : public APMFirmwarePlugin
public:
ArduRoverFirmwarePlugin
(
void
);
// Overrides from FirmwarePlugin
const
FirmwarePlugin
::
remapParamNameMajorVersionMap_t
&
paramNameRemapMajorVersionMap
(
void
)
const
final
{
return
_remapParamName
;
}
int
remapParamNameHigestMinorVersionNumber
(
int
majorVersionNumber
)
const
final
;
private:
static
bool
_remapParamNameIntialized
;
static
FirmwarePlugin
::
remapParamNameMajorVersionMap_t
_remapParamName
;
};
#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