diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 78cc920c1d..41bf37b92c 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -100,16 +100,16 @@ void AP_Periph_FW::init() can_start(); -#ifdef HAL_PERIPH_ENABLE_NETWORKING - networking_periph.init(); -#endif - #if HAL_GCS_ENABLED stm32_watchdog_pat(); gcs().init(); #endif serial_manager.init(); +#ifdef HAL_PERIPH_ENABLE_NETWORKING + networking_periph.init(); +#endif + #if HAL_GCS_ENABLED gcs().setup_console(); gcs().setup_uarts(); diff --git a/Tools/AP_Periph/networking.cpp b/Tools/AP_Periph/networking.cpp index 8ac256850c..41fb6ee042 100644 --- a/Tools/AP_Periph/networking.cpp +++ b/Tools/AP_Periph/networking.cpp @@ -137,12 +137,32 @@ const AP_Param::GroupInfo Networking_Periph::var_info[] { AP_SUBGROUPINFO(passthru[8], "PASS9_", 19, Networking_Periph, Passthru), #endif +#if AP_NETWORKING_BACKEND_PPP + // @Param: PPP_PORT + // @DisplayName: PPP serial port + // @Description: PPP serial port + // @Range: -1 10 + AP_GROUPINFO("PPP_PORT", 20, Networking_Periph, ppp_port, AP_PERIPH_NET_PPP_PORT_DEFAULT), + + // @Param: PPP_BAUD + // @DisplayName: PPP serial baudrate + // @Description: PPP serial baudrate + // @CopyFieldsFrom: SERIAL1_BAUD + AP_GROUPINFO("PPP_BAUD", 21, Networking_Periph, ppp_baud, AP_PERIPH_NET_PPP_BAUD_DEFAULT), +#endif + AP_GROUPEND }; void Networking_Periph::init(void) { +#if AP_NETWORKING_BACKEND_PPP + if (ppp_port >= 0) { + AP::serialmanager().set_protocol_and_baud(ppp_port, AP_SerialManager::SerialProtocol_PPP, ppp_baud.get()); + } +#endif + networking_lib.init(); #if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 diff --git a/Tools/AP_Periph/networking.h b/Tools/AP_Periph/networking.h index 6b7f857fdc..71cdc1754e 100644 --- a/Tools/AP_Periph/networking.h +++ b/Tools/AP_Periph/networking.h @@ -10,6 +10,14 @@ #define HAL_PERIPH_NETWORK_NUM_PASSTHRU 2 #endif +#ifndef AP_PERIPH_NET_PPP_PORT_DEFAULT +#define AP_PERIPH_NET_PPP_PORT_DEFAULT -1 +#endif + +#ifndef AP_PERIPH_NET_PPP_BAUD_DEFAULT +#define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000 +#endif + class Networking_Periph { public: Networking_Periph() { @@ -54,7 +62,11 @@ private: #endif // HAL_PERIPH_NETWORK_NUM_PASSTHRU AP_Networking networking_lib; + +#if AP_NETWORKING_BACKEND_PPP + AP_Int8 ppp_port; + AP_Int32 ppp_baud; +#endif }; -#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE - +#endif // HAL_PERIPH_ENABLE_NETWORKING