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
fdb99e73
Commit
fdb99e73
authored
May 08, 2017
by
Don Gagne
Committed by
GitHub
May 08, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #5104 from DonLakeFlyer/APMCamera
ArduPilot Camera Setup: Fix parameter mapping
parents
ec41c41e
6b7d5010
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
134 additions
and
9 deletions
+134
-9
APMCameraComponent.qml
src/AutoPilotPlugins/APM/APMCameraComponent.qml
+2
-9
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+33
-0
ArduPlaneFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
+33
-0
ArduRoverFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
+33
-0
ArduSubFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc
+33
-0
No files found.
src/AutoPilotPlugins/APM/APMCameraComponent.qml
View file @
fdb99e73
...
@@ -92,19 +92,12 @@ SetupPage {
...
@@ -92,19 +92,12 @@ SetupPage {
}
}
function
setGimbalSettingsServoInfo
(
loader
,
channel
)
{
function
setGimbalSettingsServoInfo
(
loader
,
channel
)
{
var
rcPrefix
=
"
RC
"
+
channel
+
"
_
"
var
rcPrefix
=
"
r.SERVO
"
+
channel
+
"
_
"
loader
.
gimbalOutIndex
=
channel
-
4
loader
.
gimbalOutIndex
=
channel
-
4
loader
.
servoPWMMinFact
=
controller
.
getParameterFact
(
-
1
,
rcPrefix
+
"
MIN
"
)
loader
.
servoPWMMinFact
=
controller
.
getParameterFact
(
-
1
,
rcPrefix
+
"
MIN
"
)
loader
.
servoPWMMaxFact
=
controller
.
getParameterFact
(
-
1
,
rcPrefix
+
"
MAX
"
)
loader
.
servoPWMMaxFact
=
controller
.
getParameterFact
(
-
1
,
rcPrefix
+
"
MAX
"
)
if
(
controller
.
parameterExists
(
-
1
,
"
RC5_REVERSED
"
))
{
loader
.
servoReverseFact
=
controller
.
getParameterFact
(
-
1
,
rcPrefix
+
"
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 SERVO#_FUNCTION parameters. We need to loop through those
/// Gimbal output channels are stored in SERVO#_FUNCTION parameters. We need to loop through those
...
...
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
fdb99e73
...
@@ -108,6 +108,39 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
...
@@ -108,6 +108,39 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
remapV3_5
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_5
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_5
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
remapV3_5
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
remapV3_5
[
"SERVO5_MIN"
]
=
QStringLiteral
(
"RC5_MIN"
);
remapV3_5
[
"SERVO6_MIN"
]
=
QStringLiteral
(
"RC6_MIN"
);
remapV3_5
[
"SERVO7_MIN"
]
=
QStringLiteral
(
"RC7_MIN"
);
remapV3_5
[
"SERVO8_MIN"
]
=
QStringLiteral
(
"RC8_MIN"
);
remapV3_5
[
"SERVO9_MIN"
]
=
QStringLiteral
(
"RC9_MIN"
);
remapV3_5
[
"SERVO10_MIN"
]
=
QStringLiteral
(
"RC10_MIN"
);
remapV3_5
[
"SERVO11_MIN"
]
=
QStringLiteral
(
"RC11_MIN"
);
remapV3_5
[
"SERVO12_MIN"
]
=
QStringLiteral
(
"RC12_MIN"
);
remapV3_5
[
"SERVO13_MIN"
]
=
QStringLiteral
(
"RC13_MIN"
);
remapV3_5
[
"SERVO14_MIN"
]
=
QStringLiteral
(
"RC14_MIN"
);
remapV3_5
[
"SERVO5_MAX"
]
=
QStringLiteral
(
"RC5_MAX"
);
remapV3_5
[
"SERVO6_MAX"
]
=
QStringLiteral
(
"RC6_MAX"
);
remapV3_5
[
"SERVO7_MAX"
]
=
QStringLiteral
(
"RC7_MAX"
);
remapV3_5
[
"SERVO8_MAX"
]
=
QStringLiteral
(
"RC8_MAX"
);
remapV3_5
[
"SERVO9_MAX"
]
=
QStringLiteral
(
"RC9_MAX"
);
remapV3_5
[
"SERVO10_MAX"
]
=
QStringLiteral
(
"RC10_MAX"
);
remapV3_5
[
"SERVO11_MAX"
]
=
QStringLiteral
(
"RC11_MAX"
);
remapV3_5
[
"SERVO12_MAX"
]
=
QStringLiteral
(
"RC12_MAX"
);
remapV3_5
[
"SERVO13_MAX"
]
=
QStringLiteral
(
"RC13_MAX"
);
remapV3_5
[
"SERVO14_MAX"
]
=
QStringLiteral
(
"RC14_MAX"
);
remapV3_5
[
"SERVO5_REVERSED"
]
=
QStringLiteral
(
"RC5_REVERSED"
);
remapV3_5
[
"SERVO6_REVERSED"
]
=
QStringLiteral
(
"RC6_REVERSED"
);
remapV3_5
[
"SERVO7_REVERSED"
]
=
QStringLiteral
(
"RC7_REVERSED"
);
remapV3_5
[
"SERVO8_REVERSED"
]
=
QStringLiteral
(
"RC8_REVERSED"
);
remapV3_5
[
"SERVO9_REVERSED"
]
=
QStringLiteral
(
"RC9_REVERSED"
);
remapV3_5
[
"SERVO10_REVERSED"
]
=
QStringLiteral
(
"RC10_REVERSED"
);
remapV3_5
[
"SERVO11_REVERSED"
]
=
QStringLiteral
(
"RC11_REVERSED"
);
remapV3_5
[
"SERVO12_REVERSED"
]
=
QStringLiteral
(
"RC12_REVERSED"
);
remapV3_5
[
"SERVO13_REVERSED"
]
=
QStringLiteral
(
"RC13_REVERSED"
);
remapV3_5
[
"SERVO14_REVERSED"
]
=
QStringLiteral
(
"RC14_REVERSED"
);
_remapParamNameIntialized
=
true
;
_remapParamNameIntialized
=
true
;
}
}
}
}
...
...
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
View file @
fdb99e73
...
@@ -77,6 +77,39 @@ ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(void)
...
@@ -77,6 +77,39 @@ ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(void)
remapV3_8
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_8
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_8
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
remapV3_8
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
remapV3_8
[
"SERVO5_MIN"
]
=
QStringLiteral
(
"RC5_MIN"
);
remapV3_8
[
"SERVO6_MIN"
]
=
QStringLiteral
(
"RC6_MIN"
);
remapV3_8
[
"SERVO7_MIN"
]
=
QStringLiteral
(
"RC7_MIN"
);
remapV3_8
[
"SERVO8_MIN"
]
=
QStringLiteral
(
"RC8_MIN"
);
remapV3_8
[
"SERVO9_MIN"
]
=
QStringLiteral
(
"RC9_MIN"
);
remapV3_8
[
"SERVO10_MIN"
]
=
QStringLiteral
(
"RC10_MIN"
);
remapV3_8
[
"SERVO11_MIN"
]
=
QStringLiteral
(
"RC11_MIN"
);
remapV3_8
[
"SERVO12_MIN"
]
=
QStringLiteral
(
"RC12_MIN"
);
remapV3_8
[
"SERVO13_MIN"
]
=
QStringLiteral
(
"RC13_MIN"
);
remapV3_8
[
"SERVO14_MIN"
]
=
QStringLiteral
(
"RC14_MIN"
);
remapV3_8
[
"SERVO5_MAX"
]
=
QStringLiteral
(
"RC5_MAX"
);
remapV3_8
[
"SERVO6_MAX"
]
=
QStringLiteral
(
"RC6_MAX"
);
remapV3_8
[
"SERVO7_MAX"
]
=
QStringLiteral
(
"RC7_MAX"
);
remapV3_8
[
"SERVO8_MAX"
]
=
QStringLiteral
(
"RC8_MAX"
);
remapV3_8
[
"SERVO9_MAX"
]
=
QStringLiteral
(
"RC9_MAX"
);
remapV3_8
[
"SERVO10_MAX"
]
=
QStringLiteral
(
"RC10_MAX"
);
remapV3_8
[
"SERVO11_MAX"
]
=
QStringLiteral
(
"RC11_MAX"
);
remapV3_8
[
"SERVO12_MAX"
]
=
QStringLiteral
(
"RC12_MAX"
);
remapV3_8
[
"SERVO13_MAX"
]
=
QStringLiteral
(
"RC13_MAX"
);
remapV3_8
[
"SERVO14_MAX"
]
=
QStringLiteral
(
"RC14_MAX"
);
remapV3_8
[
"SERVO5_REVERSED"
]
=
QStringLiteral
(
"RC5_REVERSED"
);
remapV3_8
[
"SERVO6_REVERSED"
]
=
QStringLiteral
(
"RC6_REVERSED"
);
remapV3_8
[
"SERVO7_REVERSED"
]
=
QStringLiteral
(
"RC7_REVERSED"
);
remapV3_8
[
"SERVO8_REVERSED"
]
=
QStringLiteral
(
"RC8_REVERSED"
);
remapV3_8
[
"SERVO9_REVERSED"
]
=
QStringLiteral
(
"RC9_REVERSED"
);
remapV3_8
[
"SERVO10_REVERSED"
]
=
QStringLiteral
(
"RC10_REVERSED"
);
remapV3_8
[
"SERVO11_REVERSED"
]
=
QStringLiteral
(
"RC11_REVERSED"
);
remapV3_8
[
"SERVO12_REVERSED"
]
=
QStringLiteral
(
"RC12_REVERSED"
);
remapV3_8
[
"SERVO13_REVERSED"
]
=
QStringLiteral
(
"RC13_REVERSED"
);
remapV3_8
[
"SERVO14_REVERSED"
]
=
QStringLiteral
(
"RC14_REVERSED"
);
_remapParamNameIntialized
=
true
;
_remapParamNameIntialized
=
true
;
}
}
}
}
...
...
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
View file @
fdb99e73
...
@@ -55,6 +55,39 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void)
...
@@ -55,6 +55,39 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void)
remapV3_2
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_2
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_2
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
remapV3_2
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
remapV3_2
[
"SERVO5_MIN"
]
=
QStringLiteral
(
"RC5_MIN"
);
remapV3_2
[
"SERVO6_MIN"
]
=
QStringLiteral
(
"RC6_MIN"
);
remapV3_2
[
"SERVO7_MIN"
]
=
QStringLiteral
(
"RC7_MIN"
);
remapV3_2
[
"SERVO8_MIN"
]
=
QStringLiteral
(
"RC8_MIN"
);
remapV3_2
[
"SERVO9_MIN"
]
=
QStringLiteral
(
"RC9_MIN"
);
remapV3_2
[
"SERVO10_MIN"
]
=
QStringLiteral
(
"RC10_MIN"
);
remapV3_2
[
"SERVO11_MIN"
]
=
QStringLiteral
(
"RC11_MIN"
);
remapV3_2
[
"SERVO12_MIN"
]
=
QStringLiteral
(
"RC12_MIN"
);
remapV3_2
[
"SERVO13_MIN"
]
=
QStringLiteral
(
"RC13_MIN"
);
remapV3_2
[
"SERVO14_MIN"
]
=
QStringLiteral
(
"RC14_MIN"
);
remapV3_2
[
"SERVO5_MAX"
]
=
QStringLiteral
(
"RC5_MAX"
);
remapV3_2
[
"SERVO6_MAX"
]
=
QStringLiteral
(
"RC6_MAX"
);
remapV3_2
[
"SERVO7_MAX"
]
=
QStringLiteral
(
"RC7_MAX"
);
remapV3_2
[
"SERVO8_MAX"
]
=
QStringLiteral
(
"RC8_MAX"
);
remapV3_2
[
"SERVO9_MAX"
]
=
QStringLiteral
(
"RC9_MAX"
);
remapV3_2
[
"SERVO10_MAX"
]
=
QStringLiteral
(
"RC10_MAX"
);
remapV3_2
[
"SERVO11_MAX"
]
=
QStringLiteral
(
"RC11_MAX"
);
remapV3_2
[
"SERVO12_MAX"
]
=
QStringLiteral
(
"RC12_MAX"
);
remapV3_2
[
"SERVO13_MAX"
]
=
QStringLiteral
(
"RC13_MAX"
);
remapV3_2
[
"SERVO14_MAX"
]
=
QStringLiteral
(
"RC14_MAX"
);
remapV3_2
[
"SERVO5_REVERSED"
]
=
QStringLiteral
(
"RC5_REVERSED"
);
remapV3_2
[
"SERVO6_REVERSED"
]
=
QStringLiteral
(
"RC6_REVERSED"
);
remapV3_2
[
"SERVO7_REVERSED"
]
=
QStringLiteral
(
"RC7_REVERSED"
);
remapV3_2
[
"SERVO8_REVERSED"
]
=
QStringLiteral
(
"RC8_REVERSED"
);
remapV3_2
[
"SERVO9_REVERSED"
]
=
QStringLiteral
(
"RC9_REVERSED"
);
remapV3_2
[
"SERVO10_REVERSED"
]
=
QStringLiteral
(
"RC10_REVERSED"
);
remapV3_2
[
"SERVO11_REVERSED"
]
=
QStringLiteral
(
"RC11_REVERSED"
);
remapV3_2
[
"SERVO12_REVERSED"
]
=
QStringLiteral
(
"RC12_REVERSED"
);
remapV3_2
[
"SERVO13_REVERSED"
]
=
QStringLiteral
(
"RC13_REVERSED"
);
remapV3_2
[
"SERVO14_REVERSED"
]
=
QStringLiteral
(
"RC14_REVERSED"
);
_remapParamNameIntialized
=
true
;
_remapParamNameIntialized
=
true
;
}
}
}
}
...
...
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc
View file @
fdb99e73
...
@@ -62,6 +62,39 @@ ArduSubFirmwarePlugin::ArduSubFirmwarePlugin(void)
...
@@ -62,6 +62,39 @@ ArduSubFirmwarePlugin::ArduSubFirmwarePlugin(void)
remapV3_5
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_5
[
"SERVO13_FUNCTION"
]
=
QStringLiteral
(
"RC13_FUNCTION"
);
remapV3_5
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
remapV3_5
[
"SERVO14_FUNCTION"
]
=
QStringLiteral
(
"RC14_FUNCTION"
);
remapV3_5
[
"SERVO5_MIN"
]
=
QStringLiteral
(
"RC5_MIN"
);
remapV3_5
[
"SERVO6_MIN"
]
=
QStringLiteral
(
"RC6_MIN"
);
remapV3_5
[
"SERVO7_MIN"
]
=
QStringLiteral
(
"RC7_MIN"
);
remapV3_5
[
"SERVO8_MIN"
]
=
QStringLiteral
(
"RC8_MIN"
);
remapV3_5
[
"SERVO9_MIN"
]
=
QStringLiteral
(
"RC9_MIN"
);
remapV3_5
[
"SERVO10_MIN"
]
=
QStringLiteral
(
"RC10_MIN"
);
remapV3_5
[
"SERVO11_MIN"
]
=
QStringLiteral
(
"RC11_MIN"
);
remapV3_5
[
"SERVO12_MIN"
]
=
QStringLiteral
(
"RC12_MIN"
);
remapV3_5
[
"SERVO13_MIN"
]
=
QStringLiteral
(
"RC13_MIN"
);
remapV3_5
[
"SERVO14_MIN"
]
=
QStringLiteral
(
"RC14_MIN"
);
remapV3_5
[
"SERVO5_MAX"
]
=
QStringLiteral
(
"RC5_MAX"
);
remapV3_5
[
"SERVO6_MAX"
]
=
QStringLiteral
(
"RC6_MAX"
);
remapV3_5
[
"SERVO7_MAX"
]
=
QStringLiteral
(
"RC7_MAX"
);
remapV3_5
[
"SERVO8_MAX"
]
=
QStringLiteral
(
"RC8_MAX"
);
remapV3_5
[
"SERVO9_MAX"
]
=
QStringLiteral
(
"RC9_MAX"
);
remapV3_5
[
"SERVO10_MAX"
]
=
QStringLiteral
(
"RC10_MAX"
);
remapV3_5
[
"SERVO11_MAX"
]
=
QStringLiteral
(
"RC11_MAX"
);
remapV3_5
[
"SERVO12_MAX"
]
=
QStringLiteral
(
"RC12_MAX"
);
remapV3_5
[
"SERVO13_MAX"
]
=
QStringLiteral
(
"RC13_MAX"
);
remapV3_5
[
"SERVO14_MAX"
]
=
QStringLiteral
(
"RC14_MAX"
);
remapV3_5
[
"SERVO5_REVERSED"
]
=
QStringLiteral
(
"RC5_REVERSED"
);
remapV3_5
[
"SERVO6_REVERSED"
]
=
QStringLiteral
(
"RC6_REVERSED"
);
remapV3_5
[
"SERVO7_REVERSED"
]
=
QStringLiteral
(
"RC7_REVERSED"
);
remapV3_5
[
"SERVO8_REVERSED"
]
=
QStringLiteral
(
"RC8_REVERSED"
);
remapV3_5
[
"SERVO9_REVERSED"
]
=
QStringLiteral
(
"RC9_REVERSED"
);
remapV3_5
[
"SERVO10_REVERSED"
]
=
QStringLiteral
(
"RC10_REVERSED"
);
remapV3_5
[
"SERVO11_REVERSED"
]
=
QStringLiteral
(
"RC11_REVERSED"
);
remapV3_5
[
"SERVO12_REVERSED"
]
=
QStringLiteral
(
"RC12_REVERSED"
);
remapV3_5
[
"SERVO13_REVERSED"
]
=
QStringLiteral
(
"RC13_REVERSED"
);
remapV3_5
[
"SERVO14_REVERSED"
]
=
QStringLiteral
(
"RC14_REVERSED"
);
remapV3_5
[
"FENCE_ALT_MIN"
]
=
QStringLiteral
(
"FENCE_DEPTH_MAX"
);
remapV3_5
[
"FENCE_ALT_MIN"
]
=
QStringLiteral
(
"FENCE_DEPTH_MAX"
);
_remapParamNameIntialized
=
true
;
_remapParamNameIntialized
=
true
;
...
...
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