AP_Periph: change ADSB to use param ADSB_PORT instead of define

This commit is contained in:
Tom Pittenger 2020-12-17 18:12:25 -08:00 committed by Tom Pittenger
parent 84e578b3df
commit 2a4fef73dd
3 changed files with 19 additions and 3 deletions

View File

@ -9,6 +9,9 @@ extern const AP_HAL::HAL &hal;
#ifndef HAL_PERIPH_ADSB_BAUD_DEFAULT
#define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600
#endif
#ifndef HAL_PERIPH_ADSB_PORT_DEFAULT
#define HAL_PERIPH_ADSB_PORT_DEFAULT 1
#endif
/*
* AP_Periph parameter definitions
@ -98,6 +101,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
#ifdef HAL_PERIPH_ENABLE_ADSB
GSCALAR(adsb_baudrate, "ADSB_BAUDRATE", HAL_PERIPH_ADSB_BAUD_DEFAULT),
GSCALAR(adsb_port, "ADSB_PORT", HAL_PERIPH_ADSB_PORT_DEFAULT),
#endif
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT

View File

@ -31,6 +31,7 @@ public:
k_param_battery,
k_param_debug,
k_param_serial_number,
k_param_adsb_port,
};
AP_Int16 format_version;
@ -55,6 +56,7 @@ public:
#ifdef HAL_PERIPH_ENABLE_ADSB
AP_Int32 adsb_baudrate;
AP_Int8 adsb_port;
#endif
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT

View File

@ -40,7 +40,11 @@ extern const AP_HAL::HAL &hal;
void AP_Periph_FW::adsb_init(void)
{
if (g.adsb_baudrate > 0) {
ADSB_PORT->begin(AP_SerialManager::map_baudrate(g.adsb_baudrate), 256, 256);
auto *uart = hal.serial(g.adsb_port);
if (uart == nullptr) {
return;
}
uart->begin(AP_SerialManager::map_baudrate(g.adsb_baudrate), 256, 256);
}
}
@ -53,10 +57,16 @@ void AP_Periph_FW::adsb_update(void)
if (g.adsb_baudrate <= 0) {
return;
}
auto *uart = hal.serial(g.adsb_port);
if (uart == nullptr) {
return;
}
// look for incoming MAVLink ADSB_VEHICLE packets
const uint16_t nbytes = ADSB_PORT->available();
const uint16_t nbytes = uart->available();
for (uint16_t i=0; i<nbytes; i++) {
const uint8_t c = (uint8_t)ADSB_PORT->read();
const uint8_t c = (uint8_t)uart->read();
// Try to get a new message
if (mavlink_parse_char(MAVLINK_COMM_0, c, &adsb.msg, &adsb.status)) {