diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 1bc668b10e..dcb4878bcc 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -80,6 +80,10 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Path: ../../libraries/AP_RangeFinder/Rangefinder.cpp GOBJECT(rangefinder, "RNGFND", RangeFinder), #endif + +#ifdef HAL_PERIPH_ENABLE_ADSB + GSCALAR(adsb_baudrate, "ADSB_BAUDRATE", 57600), +#endif AP_VAREND }; diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 6e8ab2e0c1..a07dcb0378 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -23,6 +23,7 @@ public: k_param_rangefinder, k_param_flash_bootloader, k_param_rangefinder_baud, + k_param_adsb_baudrate, }; AP_Int16 format_version; @@ -42,6 +43,11 @@ public: #ifdef HAL_PERIPH_ENABLE_RANGEFINDER AP_Int32 rangefinder_baud; #endif + +#ifdef HAL_PERIPH_ENABLE_ADSB + AP_Int32 adsb_baudrate; +#endif + Parameters() {} }; diff --git a/Tools/AP_Periph/adsb.cpp b/Tools/AP_Periph/adsb.cpp index f25b747a6e..5212482fba 100644 --- a/Tools/AP_Periph/adsb.cpp +++ b/Tools/AP_Periph/adsb.cpp @@ -22,6 +22,7 @@ #ifdef HAL_PERIPH_ENABLE_ADSB #include +#include extern const AP_HAL::HAL &hal; @@ -30,7 +31,7 @@ extern const AP_HAL::HAL &hal; */ void AP_Periph_FW::adsb_init(void) { - ADSB_PORT->begin(57600, 256, 256); + ADSB_PORT->begin(AP_SerialManager::map_baudrate(g.adsb_baudrate), 256, 256); }