AP_Periph: added ADSB_BAUDRATE parameter
This commit is contained in:
parent
5ae24a7aac
commit
e64682a834
@ -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
|
||||
};
|
||||
|
@ -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() {}
|
||||
};
|
||||
|
||||
|
@ -22,6 +22,7 @@
|
||||
#ifdef HAL_PERIPH_ENABLE_ADSB
|
||||
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user