Tools: use new AP_PERIPH_PROXIMITY_ENABLED define

This commit is contained in:
Shiv Tyagi 2025-02-20 22:55:33 +05:30 committed by Peter Barker
parent e4b9f5b474
commit e1bcd39040
8 changed files with 12 additions and 9 deletions

View File

@ -254,7 +254,7 @@ void AP_Periph_FW::init()
}
#endif
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
#if AP_PERIPH_PROXIMITY_ENABLED
if (proximity.get_type(0) != AP_Proximity::Type::None && g.proximity_port >= 0) {
auto *uart = hal.serial(g.proximity_port);
if (uart != nullptr) {

View File

@ -304,7 +304,7 @@ public:
uint32_t last_rangefinder_sample_ms[RANGEFINDER_MAX_INSTANCES];
#endif
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
#if AP_PERIPH_PROXIMITY_ENABLED
AP_Proximity proximity;
#endif

View File

@ -543,7 +543,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(efi, "EFI", AP_EFI),
#endif
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
#if AP_PERIPH_PROXIMITY_ENABLED
// @Param: PRX_BAUDRATE
// @DisplayName: Proximity Sensor serial baudrate
// @Description: Proximity Sensor serial baudrate.
@ -575,7 +575,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
// @Group: PRX
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
GOBJECT(proximity, "PRX", AP_Proximity),
#endif // HAL_PERIPH_ENABLE_PROXIMITY
#endif // AP_PERIPH_PROXIMITY_ENABLED
#if HAL_NMEA_OUTPUT_ENABLED
// @Group: NMEA_

View File

@ -132,7 +132,7 @@ public:
AP_Int16 rangefinder_max_rate;
#endif
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
#if AP_PERIPH_PROXIMITY_ENABLED
AP_Int32 proximity_baud;
AP_Int8 proximity_port;
AP_Int16 proximity_max_rate;

View File

@ -1933,7 +1933,7 @@ void AP_Periph_FW::can_update()
#if AP_PERIPH_RANGEFINDER_ENABLED
can_rangefinder_update();
#endif
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
#if AP_PERIPH_PROXIMITY_ENABLED
can_proximity_update();
#endif
#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || AP_PERIPH_NOTIFY_ENABLED

View File

@ -1,6 +1,6 @@
#include "AP_Periph.h"
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
#if AP_PERIPH_PROXIMITY_ENABLED
/*
proximity support
@ -72,4 +72,4 @@ void AP_Periph_FW::can_proximity_update()
}
}
#endif // HAL_PERIPH_ENABLE_PROXIMITY
#endif // AP_PERIPH_PROXIMITY_ENABLED

View File

@ -58,7 +58,7 @@ int8_t AP_Periph_FW::get_default_tunnel_serial_port(void) const
uart_num = g.adsb_port;
}
#endif
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
#if AP_PERIPH_PROXIMITY_ENABLED
if (uart_num == -1) {
uart_num = g.proximity_port;
}

View File

@ -964,6 +964,7 @@ class sitl_periph_universal(sitl_periph):
AP_PERIPH_EFI_ENABLED = 1,
AP_PERIPH_RPM_ENABLED = 1,
AP_PERIPH_RPM_STREAM_ENABLED = 1,
AP_PERIPH_PROXIMITY_ENABLED = 0,
AP_RPM_STREAM_ENABLED = 1,
AP_PERIPH_RC_OUT_ENABLED = 1,
AP_PERIPH_ADSB_ENABLED = 1,
@ -996,6 +997,7 @@ class sitl_periph_gps(sitl_periph):
AP_PERIPH_BATTERY_ENABLED = 0,
AP_PERIPH_SERIAL_OPTIONS_ENABLED = 0,
AP_PERIPH_ADSB_ENABLED = 0,
AP_PERIPH_PROXIMITY_ENABLED = 0,
AP_PERIPH_GPS_ENABLED = 1,
AP_PERIPH_RELAY_ENABLED = 0,
AP_PERIPH_IMU_ENABLED = 0,
@ -1033,6 +1035,7 @@ class sitl_periph_battmon(sitl_periph):
AP_PERIPH_ADSB_ENABLED = 0,
AP_PERIPH_BARO_ENABLED = 0,
AP_PERIPH_RANGEFINDER_ENABLED = 0,
AP_PERIPH_PROXIMITY_ENABLED = 0,
AP_PERIPH_GPS_ENABLED = 0,
AP_PERIPH_MSP_ENABLED = 0,
AP_PERIPH_IMU_ENABLED = 0,