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

LP-72 Added EX.Bus,HoTT SUMD and HoTT SUMH to RCVRPORT.

This commit is contained in:
Vladimir Zidar 2016-05-23 00:09:56 +02:00 committed by Laurent Lalanne
parent 05b927eefc
commit bcea35a8e1
3 changed files with 120 additions and 36 deletions

View File

@ -839,6 +839,37 @@ static const struct pios_usart_cfg pios_usart_hott_flexi_cfg = {
}, },
}; };
static const struct pios_usart_cfg pios_usart_hott_rcvr_cfg = {
.regs = USART6,
.remap = GPIO_AF_USART6,
.init = {
.USART_BaudRate = 115200,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART6_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_HOTT */ #endif /* PIOS_INCLUDE_HOTT */
#if defined(PIOS_INCLUDE_EXBUS) #if defined(PIOS_INCLUDE_EXBUS)
@ -888,6 +919,37 @@ static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = {
}, },
}; };
static const struct pios_usart_cfg pios_usart_exbus_rcvr_cfg = {
.regs = USART6,
.remap = GPIO_AF_USART6,
.init = {
.USART_BaudRate = 125000,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART6_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_EXBUS */ #endif /* PIOS_INCLUDE_EXBUS */
/* /*

View File

@ -323,6 +323,47 @@ static void PIOS_Board_configure_srxl(const struct pios_usart_cfg *usart_cfg)
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id; pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id;
} }
static void PIOS_Board_configure_exbus(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_exbus_id;
if (PIOS_USART_Init(&pios_usart_exbus_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_id;
if (PIOS_EXBUS_Init(&pios_exbus_id, &pios_usart_com_driver, pios_usart_exbus_id)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_rcvr_id;
if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id;
}
static void PIOS_Board_configure_hott(const struct pios_usart_cfg *usart_cfg, enum pios_hott_proto proto)
{
uint32_t pios_usart_hott_id;
if (PIOS_USART_Init(&pios_usart_hott_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_hott_id;
if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id, proto)) {
PIOS_Assert(0);
}
uint32_t pios_hott_rcvr_id;
if (PIOS_RCVR_Init(&pios_hott_rcvr_id, &pios_hott_rcvr_driver, pios_hott_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT] = pios_hott_rcvr_id;
}
static void PIOS_Board_PPM_callback(const int16_t *channels) static void PIOS_Board_PPM_callback(const int16_t *channels)
{ {
uint8_t max_chan = (RFM22B_PPM_NUM_CHANNELS < OPLINKRECEIVER_CHANNEL_NUMELEM) ? RFM22B_PPM_NUM_CHANNELS : OPLINKRECEIVER_CHANNEL_NUMELEM; uint8_t max_chan = (RFM22B_PPM_NUM_CHANNELS < OPLINKRECEIVER_CHANNEL_NUMELEM) ? RFM22B_PPM_NUM_CHANNELS : OPLINKRECEIVER_CHANNEL_NUMELEM;
@ -538,46 +579,14 @@ void PIOS_Board_Init(void)
case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD: case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD:
case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMH: case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT) #if defined(PIOS_INCLUDE_HOTT)
{ PIOS_Board_configure_hott(&pios_usart_hott_flexi_cfg,
uint32_t pios_usart_hott_id; hwsettings_flexiport == HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH);
if (PIOS_USART_Init(&pios_usart_hott_id, &pios_usart_hott_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_hott_id;
if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id,
hwsettings_flexiport == HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH)) {
PIOS_Assert(0);
}
uint32_t pios_hott_rcvr_id;
if (PIOS_RCVR_Init(&pios_hott_rcvr_id, &pios_hott_rcvr_driver, pios_hott_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT] = pios_hott_rcvr_id;
}
#endif /* PIOS_INCLUDE_HOTT */ #endif /* PIOS_INCLUDE_HOTT */
break; break;
case HWSETTINGS_SPK2_FLEXIPORT_EXBUS: case HWSETTINGS_SPK2_FLEXIPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS) #if defined(PIOS_INCLUDE_EXBUS)
{ PIOS_Board_configure_exbus(&pios_usart_exbus_flexi_cfg);
uint32_t pios_usart_exbus_id;
if (PIOS_USART_Init(&pios_usart_exbus_id, &pios_usart_exbus_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_id;
if (PIOS_EXBUS_Init(&pios_exbus_id, &pios_usart_com_driver, pios_usart_exbus_id)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_rcvr_id;
if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id;
}
#endif /* PIOS_INCLUDE_EXBUS */ #endif /* PIOS_INCLUDE_EXBUS */
break; break;
} /* hwsettings_rm_flexiport */ } /* hwsettings_rm_flexiport */
@ -920,6 +929,19 @@ void PIOS_Board_Init(void)
PIOS_Board_configure_srxl(&pios_usart_srxl_rcvr_cfg); PIOS_Board_configure_srxl(&pios_usart_srxl_rcvr_cfg);
#endif /* PIOS_INCLUDE_SRXL */ #endif /* PIOS_INCLUDE_SRXL */
break; break;
case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMD:
case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT)
PIOS_Board_configure_hott(&pios_usart_hott_rcvr_cfg,
hwsettings_flexiport == HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH);
#endif /* PIOS_INCLUDE_HOTT */
break;
case HWSETTINGS_SPK2_RCVRPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS)
PIOS_Board_configure_exbus(&pios_usart_exbus_rcvr_cfg);
#endif /* PIOS_INCLUDE_EXBUS */
break;
case HWSETTINGS_SPK2_RCVRPORT_DSM: case HWSETTINGS_SPK2_RCVRPORT_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_rcvr_cfg, &pios_dsm_rcvr_cfg, PIOS_Board_configure_dsm(&pios_usart_dsm_rcvr_cfg, &pios_dsm_rcvr_cfg,

View File

@ -17,7 +17,7 @@
<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" defaultvalue="S.Bus"/> <field name="SPK2_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PPM,S.Bus,DSM,SRXL,EX.Bus,HoTT SUMD,HoTT SUMH" defaultvalue="S.Bus"/>
<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_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="SPK2_I2CPort" units="function" type="enum" elements="1" options="Disabled,I2C" defaultvalue="Disabled"/>