Commit fdb99e73 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #5104 from DonLakeFlyer/APMCamera

ArduPilot Camera Setup:  Fix parameter mapping
parents ec41c41e 6b7d5010
...@@ -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
......
...@@ -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;
} }
} }
......
...@@ -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;
} }
} }
......
...@@ -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;
} }
} }
......
...@@ -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;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment