Tools: use new AP_PERIPH_ADSB_ENABLED define

This commit is contained in:
Shiv Tyagi 2025-02-20 00:05:12 +05:30 committed by Peter Barker
parent ab725360c1
commit 9b226edf3a
7 changed files with 11 additions and 9 deletions

View File

@ -197,7 +197,7 @@ void AP_Periph_FW::init()
rcout_init();
#endif
#ifdef HAL_PERIPH_ENABLE_ADSB
#if AP_PERIPH_ADSB_ENABLED
adsb_init();
#endif
@ -542,7 +542,7 @@ void AP_Periph_FW::update()
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)
update_rainbow();
#endif
#ifdef HAL_PERIPH_ENABLE_ADSB
#if AP_PERIPH_ADSB_ENABLED
adsb_update();
#endif
}

View File

@ -283,7 +283,7 @@ public:
void send_msp_airspeed(void);
#endif
#ifdef HAL_PERIPH_ENABLE_ADSB
#if AP_PERIPH_ADSB_ENABLED
void adsb_init();
void adsb_update();
void can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg);

View File

@ -355,7 +355,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(rangefinder, "RNGFND", RangeFinder),
#endif
#ifdef HAL_PERIPH_ENABLE_ADSB
#if AP_PERIPH_ADSB_ENABLED
// @Param: ADSB_BAUDRATE
// @DisplayName: ADSB serial baudrate
// @Description: ADSB serial baudrate.

View File

@ -139,7 +139,7 @@ public:
#endif
#ifdef HAL_PERIPH_ENABLE_ADSB
#if AP_PERIPH_ADSB_ENABLED
AP_Int32 adsb_baudrate;
AP_Int8 adsb_port;
#endif

View File

@ -20,7 +20,7 @@
#include <AP_HAL/AP_HAL_Boards.h>
#include "AP_Periph.h"
#ifdef HAL_PERIPH_ENABLE_ADSB
#if AP_PERIPH_ADSB_ENABLED
#include <AP_SerialManager/AP_SerialManager.h>
#include <dronecan_msgs.h>
@ -148,4 +148,4 @@ void AP_Periph_FW::can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg)
total_size);
}
#endif // HAL_PERIPH_ENABLE_ADSB
#endif // AP_PERIPH_ADSB_ENABLED

View File

@ -53,7 +53,7 @@ int8_t AP_Periph_FW::get_default_tunnel_serial_port(void) const
uart_num = g.rangefinder_port[0];
}
#endif
#ifdef HAL_PERIPH_ENABLE_ADSB
#if AP_PERIPH_ADSB_ENABLED
if (uart_num == -1) {
uart_num = g.adsb_port;
}

View File

@ -965,7 +965,7 @@ class sitl_periph_universal(sitl_periph):
AP_PERIPH_RPM_STREAM_ENABLED = 1,
AP_RPM_STREAM_ENABLED = 1,
HAL_PERIPH_ENABLE_RC_OUT = 1,
HAL_PERIPH_ENABLE_ADSB = 1,
AP_PERIPH_ADSB_ENABLED = 1,
HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1,
AP_AIRSPEED_ENABLED = 1,
AP_BATTERY_ESC_ENABLED = 1,
@ -990,6 +990,7 @@ class sitl_periph_gps(sitl_periph):
APJ_BOARD_ID = 101,
AP_PERIPH_BATTERY_ENABLED = 0,
AP_PERIPH_ADSB_ENABLED = 0,
AP_PERIPH_GPS_ENABLED = 1,
AP_PERIPH_IMU_ENABLED = 0,
AP_PERIPH_MAG_ENABLED = 0,
@ -1016,6 +1017,7 @@ class sitl_periph_battmon(sitl_periph):
AP_PERIPH_BATTERY_ENABLED = 1,
AP_PERIPH_BATTERY_BALANCE_ENABLED = 0,
AP_PERIPH_ADSB_ENABLED = 0,
AP_PERIPH_BARO_ENABLED = 0,
AP_PERIPH_RANGEFINDER_ENABLED = 0,
AP_PERIPH_GPS_ENABLED = 0,