Tools: use new AP_PERIPH_ESC_APD_ENABLED define

This commit is contained in:
Shiv Tyagi 2025-03-05 00:46:35 +05:30 committed by Peter Barker
parent 3798d6fd32
commit a313c2a063
8 changed files with 17 additions and 14 deletions

View File

@ -273,7 +273,7 @@ void AP_Periph_FW::init()
hwesc_telem.init(hal.serial(HAL_PERIPH_HWESC_SERIAL_PORT));
#endif
#ifdef HAL_PERIPH_ENABLE_ESC_APD
#if AP_PERIPH_ESC_APD_ENABLED
for (uint8_t i = 0; i < ESC_NUMBERS; i++) {
const uint8_t port = g.esc_serial_port[i];
if (port < SERIALMANAGER_NUM_PORTS) { // skip bad ports

View File

@ -335,7 +335,7 @@ public:
AP_KDECAN kdecan;
#endif
#ifdef HAL_PERIPH_ENABLE_ESC_APD
#if AP_PERIPH_ESC_APD_ENABLED
ESC_APD_Telem *apd_esc_telem[APD_ESC_INSTANCES];
void apd_esc_telem_update();
#endif

View File

@ -392,7 +392,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GSCALAR(hardpoint_rate, "HARDPOINT_RATE", 100),
#endif
#if AP_PERIPH_HOBBYWING_ESC_ENABLED || defined(HAL_PERIPH_ENABLE_ESC_APD)
#if AP_PERIPH_HOBBYWING_ESC_ENABLED || AP_PERIPH_ESC_APD_ENABLED
// @Param: ESC_NUMBER
// @DisplayName: ESC number
// @Description: This is the ESC number to report as in UAVCAN ESC telemetry feedback packets.
@ -589,11 +589,11 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(kdecan, "KDE_", AP_KDECAN),
#endif
#if defined(HAL_PERIPH_ENABLE_ESC_APD)
#if AP_PERIPH_ESC_APD_ENABLED
GARRAY(pole_count, 0, "ESC_NUM_POLES", 22),
#endif
#if defined(HAL_PERIPH_ENABLE_ESC_APD)
#if AP_PERIPH_ESC_APD_ENABLED
// @Param: ESC_APD_SERIAL_1
// @DisplayName: ESC APD Serial 1
// @Description: Which serial port to use for APD ESC data

View File

@ -149,7 +149,7 @@ public:
AP_Int8 hardpoint_rate;
#endif
#if AP_PERIPH_HOBBYWING_ESC_ENABLED || defined(HAL_PERIPH_ENABLE_ESC_APD)
#if AP_PERIPH_HOBBYWING_ESC_ENABLED || AP_PERIPH_ESC_APD_ENABLED
#if defined ESC_NUMBERS
#error "ESC_NUMBERS should not have been previously defined"
#endif

View File

@ -1839,7 +1839,7 @@ void AP_Periph_FW::esc_telem_extended_update(const uint32_t &now_ms)
}
#endif
#ifdef HAL_PERIPH_ENABLE_ESC_APD
#if AP_PERIPH_ESC_APD_ENABLED
void AP_Periph_FW::apd_esc_telem_update()
{
for(uint8_t i = 0; i < ARRAY_SIZE(apd_esc_telem); i++) {
@ -1872,7 +1872,7 @@ void AP_Periph_FW::apd_esc_telem_update()
}
}
#endif // HAL_PERIPH_ENABLE_ESC_APD
#endif // AP_PERIPH_ESC_APD_ENABLED
#endif // AP_PERIPH_RC_OUT_ENABLED
void AP_Periph_FW::can_update()
@ -1951,7 +1951,7 @@ void AP_Periph_FW::can_update()
#if AP_PERIPH_HOBBYWING_ESC_ENABLED
hwesc_telem_update();
#endif
#ifdef HAL_PERIPH_ENABLE_ESC_APD
#if AP_PERIPH_ESC_APD_ENABLED
apd_esc_telem_update();
#endif
#if AP_PERIPH_MSP_ENABLED

View File

@ -9,7 +9,7 @@
#include <AP_Math/definitions.h>
#include <string.h>
#ifdef HAL_PERIPH_ENABLE_ESC_APD
#if AP_PERIPH_ESC_APD_ENABLED
extern const AP_HAL::HAL& hal;
@ -95,4 +95,4 @@ float ESC_APD_Telem::convert_temperature(uint16_t raw) const {
return temperature;
}
#endif // HAL_PERIPH_ENABLE_ESC_APD
#endif // AP_PERIPH_ESC_APD_ENABLED

View File

@ -6,7 +6,7 @@
#include <AP_HAL/AP_HAL.h>
#ifdef HAL_PERIPH_ENABLE_ESC_APD
#if AP_PERIPH_ESC_APD_ENABLED
class ESC_APD_Telem {
public:
@ -58,4 +58,4 @@ private:
void shift_buffer(void);
};
#endif // HAL_PERIPH_ENABLE_ESC_APD
#endif // AP_PERIPH_ESC_APD_ENABLED

View File

@ -984,6 +984,7 @@ class sitl_periph_universal(sitl_periph):
AP_PERIPH_NETWORKING_ENABLED = 0,
AP_PERIPH_NOTIFY_ENABLED = 0,
AP_PERIPH_PWM_HARDPOINT_ENABLED = 0,
AP_PERIPH_ESC_APD_ENABLED = 0,
)
class sitl_periph_gps(sitl_periph):
@ -1019,7 +1020,8 @@ class sitl_periph_gps(sitl_periph):
AP_PERIPH_HOBBYWING_ESC_ENABLED = 0,
AP_PERIPH_NETWORKING_ENABLED = 0,
AP_PERIPH_NOTIFY_ENABLED = 0,
AP_PERIPH_PWM_HARDPOINT_ENABLED =0,
AP_PERIPH_PWM_HARDPOINT_ENABLED = 0,
AP_PERIPH_ESC_APD_ENABLED = 0,
)
class sitl_periph_battmon(sitl_periph):
@ -1056,6 +1058,7 @@ class sitl_periph_battmon(sitl_periph):
AP_PERIPH_NETWORKING_ENABLED = 0,
AP_PERIPH_NOTIFY_ENABLED = 0,
AP_PERIPH_PWM_HARDPOINT_ENABLED = 0,
AP_PERIPH_ESC_APD_ENABLED = 0,
)
class esp32(Board):