1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-03-16 08:29:15 +01:00

LP-72 move flexi from rm_ to spk2_ port msp wizard and sbus fixes usagetracker

This commit is contained in:
Cliff Geerdes 2016-05-21 15:48:28 -04:00 committed by Laurent Lalanne
parent ab61317b85
commit c7f450f82e
6 changed files with 78 additions and 20 deletions

View File

@ -206,6 +206,9 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
#define PIOS_COM_HKOSD_RX_BUF_LEN 22 #define PIOS_COM_HKOSD_RX_BUF_LEN 22
#define PIOS_COM_HKOSD_TX_BUF_LEN 22 #define PIOS_COM_HKOSD_TX_BUF_LEN 22
#define PIOS_COM_MSP_TX_BUF_LEN 128
#define PIOS_COM_MSP_RX_BUF_LEN 64
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) #if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 #define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
uint32_t pios_com_debug_id; uint32_t pios_com_debug_id;
@ -218,6 +221,7 @@ uint32_t pios_com_rf_id = 0;
uint32_t pios_com_bridge_id = 0; uint32_t pios_com_bridge_id = 0;
uint32_t pios_com_overo_id = 0; uint32_t pios_com_overo_id = 0;
uint32_t pios_com_hkosd_id = 0; uint32_t pios_com_hkosd_id = 0;
uint32_t pios_com_msp_id = 0;
uint32_t pios_com_vcp_id = 0; uint32_t pios_com_vcp_id = 0;
@ -436,12 +440,12 @@ void PIOS_Board_Init(void)
uint8_t hwsettings_flexiport; uint8_t hwsettings_flexiport;
HwSettingsRM_FlexiPortGet(&hwsettings_flexiport); HwSettingsRM_FlexiPortGet(&hwsettings_flexiport);
switch (hwsettings_flexiport) { switch (hwsettings_flexiport) {
case HWSETTINGS_RM_FLEXIPORT_DISABLED: case HWSETTINGS_SPK2_FLEXIPORT_DISABLED:
break; break;
case HWSETTINGS_RM_FLEXIPORT_TELEMETRY: case HWSETTINGS_SPK2_FLEXIPORT_TELEMETRY:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
break; break;
case HWSETTINGS_RM_FLEXIPORT_I2C: case HWSETTINGS_SPK2_FLEXIPORT_I2C:
#if defined(PIOS_INCLUDE_I2C) #if defined(PIOS_INCLUDE_I2C)
#if defined(PIOS_INCLUDE_HMC5X83) #if defined(PIOS_INCLUDE_HMC5X83)
{ {
@ -480,28 +484,31 @@ void PIOS_Board_Init(void)
#endif /* PIOS_INCLUDE_HMC5X83 */ #endif /* PIOS_INCLUDE_HMC5X83 */
#endif /* PIOS_INCLUDE_I2C */ #endif /* PIOS_INCLUDE_I2C */
break; break;
case HWSETTINGS_RM_FLEXIPORT_GPS: case HWSETTINGS_SPK2_FLEXIPORT_GPS:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
break; break;
case HWSETTINGS_RM_FLEXIPORT_DSM: case HWSETTINGS_SPK2_FLEXIPORT_DSM:
// TODO: Define the various Channelgroup for Sparky2 dsm inputs and handle here // TODO: Define the various Channelgroup for Sparky2 dsm inputs and handle here
PIOS_Board_configure_dsm(&pios_usart_dsm_flexi_cfg, &pios_dsm_flexi_cfg, PIOS_Board_configure_dsm(&pios_usart_dsm_flexi_cfg, &pios_dsm_flexi_cfg,
&pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT, &hwsettings_DSMxBind); &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT, &hwsettings_DSMxBind);
break; break;
case HWSETTINGS_RM_FLEXIPORT_DEBUGCONSOLE: case HWSETTINGS_SPK2_FLEXIPORT_DEBUGCONSOLE:
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) #if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
{ {
PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
} }
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
break; break;
case HWSETTINGS_RM_FLEXIPORT_COMBRIDGE: case HWSETTINGS_SPK2_FLEXIPORT_COMBRIDGE:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break; break;
case HWSETTINGS_RM_FLEXIPORT_OSDHK: case HWSETTINGS_SPK2_FLEXIPORT_MSP:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_SPK2_FLEXIPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_flexi_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id); PIOS_Board_configure_com(&pios_usart_hkosd_flexi_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
break; break;
case HWSETTINGS_RM_FLEXIPORT_SRXL: case HWSETTINGS_SPK2_FLEXIPORT_SRXL:
#if defined(PIOS_INCLUDE_SRXL) #if defined(PIOS_INCLUDE_SRXL)
{ {
uint32_t pios_usart_srxl_id; uint32_t pios_usart_srxl_id;
@ -523,8 +530,8 @@ void PIOS_Board_Init(void)
#endif /* PIOS_INCLUDE_SRXL */ #endif /* PIOS_INCLUDE_SRXL */
break; break;
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD: case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD:
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMH: case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT) #if defined(PIOS_INCLUDE_HOTT)
{ {
uint32_t pios_usart_hott_id; uint32_t pios_usart_hott_id;
@ -534,7 +541,7 @@ void PIOS_Board_Init(void)
uint32_t pios_hott_id; uint32_t pios_hott_id;
if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id, if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id,
hwsettings_flexiport == HWSETTINGS_RM_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH)) { hwsettings_flexiport == HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH)) {
PIOS_Assert(0); PIOS_Assert(0);
} }
@ -547,7 +554,7 @@ void PIOS_Board_Init(void)
#endif /* PIOS_INCLUDE_HOTT */ #endif /* PIOS_INCLUDE_HOTT */
break; break;
case HWSETTINGS_RM_FLEXIPORT_EXBUS: case HWSETTINGS_SPK2_FLEXIPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS) #if defined(PIOS_INCLUDE_EXBUS)
{ {
uint32_t pios_usart_exbus_id; uint32_t pios_usart_exbus_id;
@ -741,6 +748,9 @@ void PIOS_Board_Init(void)
case HWSETTINGS_SPK2_MAINPORT_COMBRIDGE: case HWSETTINGS_SPK2_MAINPORT_COMBRIDGE:
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break; break;
case HWSETTINGS_RM_MAINPORT_MSP:
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_SPK2_MAINPORT_OSDHK: case HWSETTINGS_SPK2_MAINPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_main_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id); PIOS_Board_configure_com(&pios_usart_hkosd_main_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
break; break;

View File

@ -39,7 +39,9 @@ void GpsPage::initializePage(VehicleConfigurationSource *settings)
{ {
// Enable all // Enable all
setItemDisabled(-1, false); setItemDisabled(-1, false);
if (settings->getInputType() == VehicleConfigurationSource::INPUT_SBUS || // sbus is on rcvrport for sparky2, that leaves mainport/flexiport available for gps/auxmag
// it is not even possible to put sbus on mainport on sparky2 because hardware inverter is on rcvrport
if ((settings->getInputType() == VehicleConfigurationSource::INPUT_SBUS && settings->getControllerType() != VehicleConfigurationSource::CONTROLLER_SPARKY2) ||
settings->getInputType() == VehicleConfigurationSource::INPUT_DSM || settings->getInputType() == VehicleConfigurationSource::INPUT_DSM ||
settings->getInputType() == VehicleConfigurationSource::INPUT_HOTT_SUMD || settings->getInputType() == VehicleConfigurationSource::INPUT_HOTT_SUMD ||
settings->getInputType() == VehicleConfigurationSource::INPUT_EXBUS || settings->getInputType() == VehicleConfigurationSource::INPUT_EXBUS ||

View File

@ -112,7 +112,6 @@ bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedTyp
case SetupWizard::CONTROLLER_REVO: case SetupWizard::CONTROLLER_REVO:
case SetupWizard::CONTROLLER_DISCOVERYF4: case SetupWizard::CONTROLLER_DISCOVERYF4:
case SetupWizard::CONTROLLER_NANO: case SetupWizard::CONTROLLER_NANO:
case SetupWizard::CONTROLLER_SPARKY2:
{ {
switch (selectedType) { switch (selectedType) {
case VehicleConfigurationSource::INPUT_PWM: case VehicleConfigurationSource::INPUT_PWM:
@ -141,6 +140,32 @@ bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedTyp
} }
break; break;
} }
case SetupWizard::CONTROLLER_SPARKY2:
{
switch (selectedType) {
case VehicleConfigurationSource::INPUT_PPM:
return data.SPK2_RcvrPort != HwSettings::SPK2_RCVRPORT_PPM;
case VehicleConfigurationSource::INPUT_SBUS:
return data.SPK2_RcvrPort != HwSettings::SPK2_RCVRPORT_SBUS;
case VehicleConfigurationSource::INPUT_HOTT_SUMD:
return data.SPK2_FlexiPort != HwSettings::SPK2_FLEXIPORT_HOTTSUMD;
case VehicleConfigurationSource::INPUT_EXBUS:
return data.SPK2_FlexiPort != HwSettings::SPK2_FLEXIPORT_EXBUS;
case VehicleConfigurationSource::INPUT_SRXL:
return data.SPK2_FlexiPort != HwSettings::SPK2_FLEXIPORT_SRXL;
case VehicleConfigurationSource::INPUT_DSM:
// TODO: Handle all of the DSM types ?? Which is most common?
return data.SPK2_MainPort != HwSettings::SPK2_MAINPORT_DSM;
default: return true;
}
break;
}
default: return true; default: return true;
} }
} }

View File

@ -164,7 +164,7 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
} }
break; break;
case VehicleConfigurationSource::INPUT_SBUS: case VehicleConfigurationSource::INPUT_SBUS:
// We have to set teletry on flexiport since s.bus needs the mainport. // We have to set telemetry on flexiport since s.bus needs the mainport.
data.CC_MainPort = HwSettings::CC_MAINPORT_SBUS; data.CC_MainPort = HwSettings::CC_MAINPORT_SBUS;
data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_TELEMETRY; data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_TELEMETRY;
break; break;
@ -191,11 +191,14 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
// Reset all ports to their defaults // Reset all ports to their defaults
data.RM_RcvrPort = HwSettings::RM_RCVRPORT_DISABLED; data.RM_RcvrPort = HwSettings::RM_RCVRPORT_DISABLED;
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_DISABLED; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_DISABLED;
data.SPK2_RcvrPort = HwSettings::SPK2_RCVRPORT_DISABLED;
data.SPK2_FlexiPort = HwSettings::SPK2_FLEXIPORT_DISABLED;
// Revo/Sparky2 uses inbuilt Modem do not set mainport to be active telemetry link for Revo/Sparky2 // Revo/Sparky2 uses inbuilt Modem do not set mainport to be active telemetry link for Revo/Sparky2
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO
|| m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_SPARKY2) { || m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_SPARKY2) {
data.RM_MainPort = HwSettings::RM_MAINPORT_DISABLED; data.RM_MainPort = HwSettings::RM_MAINPORT_DISABLED;
data.RM_MainPort = HwSettings::SPK2_MAINPORT_DISABLED;
} else { } else {
data.RM_MainPort = HwSettings::RM_MAINPORT_TELEMETRY; data.RM_MainPort = HwSettings::RM_MAINPORT_TELEMETRY;
} }
@ -203,9 +206,12 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
switch (m_configSource->getInputType()) { switch (m_configSource->getInputType()) {
case VehicleConfigurationSource::INPUT_PWM: case VehicleConfigurationSource::INPUT_PWM:
data.RM_RcvrPort = HwSettings::RM_RCVRPORT_PWM; data.RM_RcvrPort = HwSettings::RM_RCVRPORT_PWM;
// this should not happen, sparky2 does not allow pwm
data.SPK2_RcvrPort = HwSettings::SPK2_RCVRPORT_DISABLED;
break; break;
case VehicleConfigurationSource::INPUT_PPM: case VehicleConfigurationSource::INPUT_PPM:
data.RM_RcvrPort = HwSettings::RM_RCVRPORT_PPM; data.RM_RcvrPort = HwSettings::RM_RCVRPORT_PPM;
data.SPK2_RcvrPort = HwSettings::SPK2_RCVRPORT_PPM;
break; break;
case VehicleConfigurationSource::INPUT_SBUS: case VehicleConfigurationSource::INPUT_SBUS:
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_SPARKY2) { if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_SPARKY2) {
@ -220,15 +226,19 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
break; break;
case VehicleConfigurationSource::INPUT_DSM: case VehicleConfigurationSource::INPUT_DSM:
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_DSM; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_DSM;
data.SPK2_FlexiPort = HwSettings::SPK2_FLEXIPORT_DSM;
break; break;
case VehicleConfigurationSource::INPUT_SRXL: case VehicleConfigurationSource::INPUT_SRXL:
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_SRXL; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_SRXL;
data.SPK2_FlexiPort = HwSettings::SPK2_FLEXIPORT_SRXL;
break; break;
case VehicleConfigurationSource::INPUT_HOTT_SUMD: case VehicleConfigurationSource::INPUT_HOTT_SUMD:
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_HOTTSUMD; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_HOTTSUMD;
data.SPK2_FlexiPort = HwSettings::SPK2_FLEXIPORT_HOTTSUMD;
break; break;
case VehicleConfigurationSource::INPUT_EXBUS: case VehicleConfigurationSource::INPUT_EXBUS:
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_EXBUS; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_EXBUS;
data.SPK2_FlexiPort = HwSettings::SPK2_FLEXIPORT_EXBUS;
break; break;
default: default:
break; break;
@ -245,6 +255,7 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_GPS; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_GPS;
} else { } else {
data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; data.RM_MainPort = HwSettings::RM_MAINPORT_GPS;
data.SPK2_MainPort = HwSettings::SPK2_MAINPORT_GPS;
} }
GPSSettings *gpsSettings = GPSSettings::GetInstance(m_uavoManager); GPSSettings *gpsSettings = GPSSettings::GetInstance(m_uavoManager);
@ -291,6 +302,7 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBX; gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBX;
gpsData.UbxAutoConfig = GPSSettings::UBXAUTOCONFIG_AUTOBAUDANDCONFIGURE; gpsData.UbxAutoConfig = GPSSettings::UBXAUTOCONFIG_AUTOBAUDANDCONFIGURE;
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_I2C; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_I2C;
data.SPK2_FlexiPort = HwSettings::SPK2_FLEXIPORT_I2C;
AuxMagSettings *magSettings = AuxMagSettings::GetInstance(m_uavoManager); AuxMagSettings *magSettings = AuxMagSettings::GetInstance(m_uavoManager);
Q_ASSERT(magSettings); Q_ASSERT(magSettings);
AuxMagSettings::DataFields magsData = magSettings->getData(); AuxMagSettings::DataFields magsData = magSettings->getData();
@ -325,11 +337,15 @@ void VehicleConfigurationHelper::applyHardwareConfiguration()
case VehicleConfigurationSource::AIRSPEED_EAGLETREE: case VehicleConfigurationSource::AIRSPEED_EAGLETREE:
data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 1; data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 1;
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_I2C; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_I2C;
// sparky2: put I2C airspeed on flexiport, but it could be put on i2cport
data.SPK2_FlexiPort = HwSettings::SPK2_FLEXIPORT_I2C;
airspeedData.AirspeedSensorType = AirspeedSettings::AIRSPEEDSENSORTYPE_EAGLETREEAIRSPEEDV3; airspeedData.AirspeedSensorType = AirspeedSettings::AIRSPEEDSENSORTYPE_EAGLETREEAIRSPEEDV3;
break; break;
case VehicleConfigurationSource::AIRSPEED_MS4525: case VehicleConfigurationSource::AIRSPEED_MS4525:
data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 1; data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 1;
data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_I2C; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_I2C;
// sparky2: put I2C airspeed on flexiport, but it could be put on i2cport
data.SPK2_FlexiPort = HwSettings::SPK2_FLEXIPORT_I2C;
airspeedData.AirspeedSensorType = AirspeedSettings::AIRSPEEDSENSORTYPE_PIXHAWKAIRSPEEDMS4525DO; airspeedData.AirspeedSensorType = AirspeedSettings::AIRSPEEDSENSORTYPE_PIXHAWKAIRSPEEDMS4525DO;
break; break;
default: default:

View File

@ -194,6 +194,12 @@ void UsageTrackerPlugin::collectUsageParameters(QMap<QString, QString> &paramete
parameters["conf_mport"] = getUAVFieldValue(objManager, "HwSettings", "RM_MainPort"); parameters["conf_mport"] = getUAVFieldValue(objManager, "HwSettings", "RM_MainPort");
parameters["conf_fport"] = getUAVFieldValue(objManager, "HwSettings", "RM_FlexiPort"); parameters["conf_fport"] = getUAVFieldValue(objManager, "HwSettings", "RM_FlexiPort");
parameters["conf_fusion"] = getUAVFieldValue(objManager, "RevoSettings", "FusionAlgorithm"); parameters["conf_fusion"] = getUAVFieldValue(objManager, "RevoSettings", "FusionAlgorithm");
} else if ((boardModel & 0xff00) == 0x0b00) {
// Sparky2
parameters["conf_rport"] = getUAVFieldValue(objManager, "HwSettings", "SPK2_RcvrPort");
parameters["conf_mport"] = getUAVFieldValue(objManager, "HwSettings", "SPK2_MainPort");
parameters["conf_fport"] = getUAVFieldValue(objManager, "HwSettings", "SPK2_FlexiPort");
parameters["conf_fusion"] = getUAVFieldValue(objManager, "RevoSettings", "FusionAlgorithm");
} }
parameters["conf_uport"] = getUAVFieldValue(objManager, "HwSettings", "USB_HIDPort"); parameters["conf_uport"] = getUAVFieldValue(objManager, "HwSettings", "USB_HIDPort");

View File

@ -17,11 +17,10 @@
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/> <field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/>
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/> <field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/>
<field name="SPK2_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PPM,S.Bus,DSM,SRXL,MSP" <field name="SPK2_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PPM,S.Bus,DSM,SRXL" defaultvalue="S.Bus"/>
defaultvalue="S.Bus"/>
<field name="SPK2_I2CPort" units="function" type="enum" elements="1" options="Disabled,I2C"
defaultvalue="Disabled"/>
<field name="SPK2_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,DSM,DebugConsole,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/> <field name="SPK2_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,DSM,DebugConsole,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/>
<field name="SPK2_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/>
<field name="SPK2_I2CPort" units="function" type="enum" elements="1" options="Disabled,I2C" defaultvalue="Disabled"/>
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/> <field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
<field name="GPSSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200,230400" defaultvalue="57600"/> <field name="GPSSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200,230400" defaultvalue="57600"/>