AP_BoardConfig: support flow control on UARTs 6->8

This commit is contained in:
Andy Piper 2025-01-23 10:42:03 +00:00 committed by Randy Mackay
parent 26abfc542d
commit 1cbc372c01
3 changed files with 44 additions and 1 deletions

View File

@ -152,6 +152,30 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
// @Description: Enable flow control on serial 5. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. // @Description: Enable flow control on serial 5. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
AP_GROUPINFO("SER5_RTSCTS", 25, AP_BoardConfig, state.ser_rtscts[5], 2), AP_GROUPINFO("SER5_RTSCTS", 25, AP_BoardConfig, state.ser_rtscts[5], 2),
#endif #endif
#ifdef HAL_HAVE_RTSCTS_SERIAL6
// @Param: SER6_RTSCTS
// @CopyFieldsFrom: BRD_SER1_RTSCTS
// @DisplayName: Serial 6 flow control
// @Description: Enable flow control on serial 6. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
AP_GROUPINFO("SER6_RTSCTS", 30, AP_BoardConfig, state.ser_rtscts[6], 2),
#endif
#ifdef HAL_HAVE_RTSCTS_SERIAL7
// @Param: SER7_RTSCTS
// @CopyFieldsFrom: BRD_SER1_RTSCTS
// @DisplayName: Serial 7 flow control
// @Description: Enable flow control on serial 7. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
AP_GROUPINFO("SER7_RTSCTS", 31, AP_BoardConfig, state.ser_rtscts[7], 2),
#endif
#ifdef HAL_HAVE_RTSCTS_SERIAL8
// @Param: SER8_RTSCTS
// @CopyFieldsFrom: BRD_SER8_RTSCTS
// @DisplayName: Serial 8 flow control
// @Description: Enable flow control on serial 8. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
AP_GROUPINFO("SER8_RTSCTS", 32, AP_BoardConfig, state.ser_rtscts[8], 2),
#endif
#endif #endif
// @Param: SAFETY_DEFLT // @Param: SAFETY_DEFLT
@ -370,6 +394,10 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
// @User: Advanced // @User: Advanced
AP_GROUPINFO("IO_DSHOT", 28, AP_BoardConfig, state.io_dshot, 0), AP_GROUPINFO("IO_DSHOT", 28, AP_BoardConfig, state.io_dshot, 0),
#endif #endif
// index 30 used by SER6_RTSCTS
// index 31 used by SER7_RTSCTS
// index 32 used by SER8_RTSCTS
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -239,7 +239,7 @@ private:
AP_Int16 safety_option; AP_Int16 safety_option;
AP_Int32 ignore_safety_channels; AP_Int32 ignore_safety_channels;
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
AP_Int8 ser_rtscts[6]; AP_Int8 ser_rtscts[9];
AP_Int8 sbus_out_rate; AP_Int8 sbus_out_rate;
#endif #endif
AP_Int8 board_type; AP_Int8 board_type;

View File

@ -415,6 +415,21 @@ void AP_BoardConfig::board_setup_uart()
hal.serial(5)->set_flow_control((AP_HAL::UARTDriver::flow_control)state.ser_rtscts[5].get()); hal.serial(5)->set_flow_control((AP_HAL::UARTDriver::flow_control)state.ser_rtscts[5].get());
} }
#endif #endif
#ifdef HAL_HAVE_RTSCTS_SERIAL6
if (hal.serial(6) != nullptr) {
hal.serial(6)->set_flow_control((AP_HAL::UARTDriver::flow_control)state.ser_rtscts[6].get());
}
#endif
#ifdef HAL_HAVE_RTSCTS_SERIAL7
if (hal.serial(7) != nullptr) {
hal.serial(7)->set_flow_control((AP_HAL::UARTDriver::flow_control)state.ser_rtscts[7].get());
}
#endif
#ifdef HAL_HAVE_RTSCTS_SERIAL8
if (hal.serial(8) != nullptr) {
hal.serial(8)->set_flow_control((AP_HAL::UARTDriver::flow_control)state.ser_rtscts[8].get());
}
#endif
#endif #endif
} }