diff --git a/flight/modules/Receiver/receiver.c b/flight/modules/Receiver/receiver.c index 78ae0f70f..842644138 100644 --- a/flight/modules/Receiver/receiver.c +++ b/flight/modules/Receiver/receiver.c @@ -655,8 +655,8 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT: group = RECEIVERACTIVITY_ACTIVEGROUP_DSMFLEXIPORT; break; - case MANUALCONTROLSETTINGS_CHANNELGROUPS_JETIEXBUSFLEXIPORT: - group = RECEIVERACTIVITY_ACTIVEGROUP_JETIEXBUSFLEXIPORT; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS: + group = RECEIVERACTIVITY_ACTIVEGROUP_EXBUS; break; case MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS: group = RECEIVERACTIVITY_ACTIVEGROUP_SBUS; diff --git a/flight/targets/boards/coptercontrol/firmware/pios_board.c b/flight/targets/boards/coptercontrol/firmware/pios_board.c index a344e181e..6ee7f635c 100644 --- a/flight/targets/boards/coptercontrol/firmware/pios_board.c +++ b/flight/targets/boards/coptercontrol/firmware/pios_board.c @@ -674,7 +674,7 @@ void PIOS_Board_Init(void) } #endif /* PIOS_INCLUDE_DSM */ break; - case HWSETTINGS_CC_FLEXIPORT_JETIEXBUS: + case HWSETTINGS_CC_FLEXIPORT_EXBUS: #if defined(PIOS_INCLUDE_EXBUS) { uint32_t pios_usart_exbus_id; @@ -691,7 +691,7 @@ void PIOS_Board_Init(void) if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) { PIOS_Assert(0); } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_JETIEXBUSFLEXIPORT] = pios_exbus_rcvr_id; + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id; } #endif /* PIOS_INCLUDE_EXBUS */ break; diff --git a/flight/targets/boards/revolution/board_hw_defs.c b/flight/targets/boards/revolution/board_hw_defs.c index f914cf866..d062315d5 100644 --- a/flight/targets/boards/revolution/board_hw_defs.c +++ b/flight/targets/boards/revolution/board_hw_defs.c @@ -1101,46 +1101,6 @@ static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = { }, }; -static const struct pios_usart_cfg pios_usart_exbus_main_cfg = { - .regs = USART1, - .remap = GPIO_AF_USART1, - .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 = USART1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; #endif /* PIOS_INCLUDE_EXBUS */ /* diff --git a/flight/targets/boards/revolution/firmware/pios_board.c b/flight/targets/boards/revolution/firmware/pios_board.c index 0385f4dc2..2e1ee2723 100644 --- a/flight/targets/boards/revolution/firmware/pios_board.c +++ b/flight/targets/boards/revolution/firmware/pios_board.c @@ -520,7 +520,7 @@ void PIOS_Board_Init(void) } #endif break; - case HWSETTINGS_RM_FLEXIPORT_JETIEXBUS: + case HWSETTINGS_RM_FLEXIPORT_EXBUS: #if defined(PIOS_INCLUDE_EXBUS) { uint32_t pios_usart_exbus_id; @@ -537,7 +537,7 @@ void PIOS_Board_Init(void) if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) { PIOS_Assert(0); } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_JETIEXBUSFLEXIPORT] = pios_exbus_rcvr_id; + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id; } #endif /* PIOS_INCLUDE_EXBUS */ break; @@ -718,27 +718,6 @@ void PIOS_Board_Init(void) } #endif break; - case HWSETTINGS_RM_MAINPORT_JETIEXBUS: -#if defined(PIOS_INCLUDE_EXBUS) - { - uint32_t pios_usart_exbus_id; - if (PIOS_USART_Init(&pios_usart_exbus_id, &pios_usart_exbus_main_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_JETIEXBUSMAINPORT] = pios_exbus_rcvr_id; - } -#endif /* PIOS_INCLUDE_EXBUS */ - break; case HWSETTINGS_RM_MAINPORT_DSM: // Force binding to zero on the main port hwsettings_DSMxBind = 0; diff --git a/flight/targets/boards/revolution/pios_board.h b/flight/targets/boards/revolution/pios_board.h index 712906504..6941bc49e 100644 --- a/flight/targets/boards/revolution/pios_board.h +++ b/flight/targets/boards/revolution/pios_board.h @@ -260,7 +260,7 @@ extern uint32_t pios_packet_handler; // ------------------------- // Receiver EX.Bus input // ------------------------- -#define PIOS_EXBUS_MAX_DEVS 2 +#define PIOS_EXBUS_MAX_DEVS 1 #define PIOS_EXBUS_NUM_INPUTS 16 // ------------------------- diff --git a/flight/targets/boards/revonano/board_hw_defs.c b/flight/targets/boards/revonano/board_hw_defs.c index fbf04026a..399704ac8 100644 --- a/flight/targets/boards/revonano/board_hw_defs.c +++ b/flight/targets/boards/revonano/board_hw_defs.c @@ -631,46 +631,7 @@ static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = { }, }; -static const struct pios_usart_cfg pios_usart_exbus_main_cfg = { - .regs = MAIN_USART_REGS, - .remap = MAIN_USART_REMAP, - .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 = MAIN_USART_IRQ, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = MAIN_USART_RX_GPIO, - .init = { - .GPIO_Pin = MAIN_USART_RX_PIN, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = MAIN_USART_TX_GPIO, - .init = { - .GPIO_Pin = MAIN_USART_TX_PIN, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; + #endif /* PIOS_INCLUDE_EXBUS */ /* * HK OSD diff --git a/flight/targets/boards/revonano/firmware/pios_board.c b/flight/targets/boards/revonano/firmware/pios_board.c index dfd9dd3fe..e03afbf38 100644 --- a/flight/targets/boards/revonano/firmware/pios_board.c +++ b/flight/targets/boards/revonano/firmware/pios_board.c @@ -576,27 +576,6 @@ void PIOS_Board_Init(void) } #endif break; - case HWSETTINGS_RM_MAINPORT_JETIEXBUS: -#if defined(PIOS_INCLUDE_EXBUS) - { - uint32_t pios_usart_exbus_id; - if (PIOS_USART_Init(&pios_usart_exbus_id, &pios_usart_exbus_main_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_JETIEXBUSMAINPORT] = pios_exbus_rcvr_id; - } -#endif /* PIOS_INCLUDE_EXBUS */ - break; case HWSETTINGS_RM_MAINPORT_DSM: { // Force binding to zero on the main port @@ -687,7 +666,7 @@ void PIOS_Board_Init(void) } #endif break; - case HWSETTINGS_RM_FLEXIPORT_JETIEXBUS: + case HWSETTINGS_RM_FLEXIPORT_EXBUS: #if defined(PIOS_INCLUDE_EXBUS) { uint32_t pios_usart_exbus_id; @@ -704,7 +683,7 @@ void PIOS_Board_Init(void) if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) { PIOS_Assert(0); } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_JETIEXBUSFLEXIPORT] = pios_exbus_rcvr_id; + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id; } #endif /* PIOS_INCLUDE_EXBUS */ break; diff --git a/flight/targets/boards/revonano/pios_board.h b/flight/targets/boards/revonano/pios_board.h index 3c3e34fca..6c5a09d99 100644 --- a/flight/targets/boards/revonano/pios_board.h +++ b/flight/targets/boards/revonano/pios_board.h @@ -260,7 +260,7 @@ extern uint32_t pios_packet_handler; // ------------------------- // Receiver EX.Bus input // ------------------------- -#define PIOS_EXBUS_MAX_DEVS 2 +#define PIOS_EXBUS_MAX_DEVS 1 #define PIOS_EXBUS_NUM_INPUTS 16 // ------------------------- diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 9339f4787..163e0dec0 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -3,7 +3,7 @@ Selection of optional hardware configurations. - + @@ -15,8 +15,8 @@ - - + + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index b5cf0bf12..4d7a02a39 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -3,7 +3,7 @@ Settings to indicate how to decode receiver input by @ref ManualControlModule. + options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),EX.Bus,S.Bus,SRXL,GCS,OPLink,None" defaultvalue="None"/> Monitors which receiver channels have been active within the last second.