From b3bc0528e033a63e9820918ec5e2f8d90f882628 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 23 Jan 2025 15:47:00 +1100 Subject: [PATCH] Tools: create and use AP_PERIPH_BATTERY_ENABLED ... and AP_PERIPH_BATTERY_BALANCE_ENABLED while we're here --- Tools/AP_Periph/AP_Periph.cpp | 6 +++--- Tools/AP_Periph/AP_Periph.h | 4 ++-- Tools/AP_Periph/Parameters.cpp | 4 ++-- Tools/AP_Periph/Parameters.h | 2 +- Tools/AP_Periph/batt_balance.cpp | 4 ++-- Tools/AP_Periph/batt_balance.h | 4 ++-- Tools/AP_Periph/battery.cpp | 5 ++--- Tools/AP_Periph/can.cpp | 4 ++-- Tools/ardupilotwaf/boards.py | 4 ++-- 9 files changed, 18 insertions(+), 19 deletions(-) diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 9da1fe2e73..91fc21c4d6 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -177,7 +177,7 @@ void AP_Periph_FW::init() } #endif -#ifdef HAL_PERIPH_ENABLE_BATTERY +#if AP_PERIPH_BATTERY_ENABLED battery_lib.init(); #endif @@ -485,7 +485,7 @@ void AP_Periph_FW::update() #endif } -#ifdef HAL_PERIPH_ENABLE_BATTERY +#if AP_PERIPH_BATTERY_ENABLED if (now - battery.last_read_ms >= 100) { // update battery at 10Hz battery.last_read_ms = now; @@ -497,7 +497,7 @@ void AP_Periph_FW::update() rcin_update(); #endif -#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE +#if AP_PERIPH_BATTERY_BALANCE_ENABLED batt_balance_update(); #endif diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 59c7e7861c..8aaca9475d 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -249,7 +249,7 @@ public: #endif #endif // HAL_PERIPH_ENABLE_RPM -#ifdef HAL_PERIPH_ENABLE_BATTERY +#if AP_PERIPH_BATTERY_ENABLED void handle_battery_failsafe(const char* type_str, const int8_t action) { } AP_BattMonitor battery_lib{0, FUNCTOR_BIND_MEMBER(&AP_Periph_FW::handle_battery_failsafe, void, const char*, const int8_t), nullptr}; struct { @@ -379,7 +379,7 @@ public: Parameters_RCIN g_rcin; #endif -#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE +#if AP_PERIPH_BATTERY_BALANCE_ENABLED void batt_balance_update(); BattBalance battery_balance; #endif diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 15ea7e175b..bfb3b8c354 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -250,7 +250,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { #endif #endif -#ifdef HAL_PERIPH_ENABLE_BATTERY +#if AP_PERIPH_BATTERY_ENABLED // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp GOBJECT(battery_lib, "BATT", AP_BattMonitor), @@ -637,7 +637,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GOBJECT(g_rcin, "RC", Parameters_RCIN), #endif -#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE +#if AP_PERIPH_BATTERY_BALANCE_ENABLED // @Group: BAL // @Path: batt_balance.cpp GOBJECT(battery_balance, "BAL", BattBalance), diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 9d245f8a36..5634038034 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -204,7 +204,7 @@ public: AP_Int16 sysid_this_mav; #endif -#ifdef HAL_PERIPH_ENABLE_BATTERY +#if AP_PERIPH_BATTERY_ENABLED AP_Int32 battery_hide_mask; #endif diff --git a/Tools/AP_Periph/batt_balance.cpp b/Tools/AP_Periph/batt_balance.cpp index e7869e01b4..ec60e55398 100644 --- a/Tools/AP_Periph/batt_balance.cpp +++ b/Tools/AP_Periph/batt_balance.cpp @@ -15,7 +15,7 @@ #include "AP_Periph.h" -#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE +#if AP_PERIPH_BATTERY_BALANCE_ENABLED #include @@ -134,5 +134,5 @@ void AP_Periph_FW::batt_balance_update() delete [] buffer; } -#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE +#endif // AP_PERIPH_BATTERY_BALANCE_ENABLED diff --git a/Tools/AP_Periph/batt_balance.h b/Tools/AP_Periph/batt_balance.h index 961875c660..72ec213174 100644 --- a/Tools/AP_Periph/batt_balance.h +++ b/Tools/AP_Periph/batt_balance.h @@ -1,6 +1,6 @@ #pragma once -#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE +#if AP_PERIPH_BATTERY_BALANCE_ENABLED class BattBalance { public: @@ -20,5 +20,5 @@ private: uint8_t cells_allocated; }; -#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE +#endif // AP_PERIPH_BATTERY_BALANCE_ENABLED diff --git a/Tools/AP_Periph/battery.cpp b/Tools/AP_Periph/battery.cpp index 942e5b2136..dfea5d67cb 100644 --- a/Tools/AP_Periph/battery.cpp +++ b/Tools/AP_Periph/battery.cpp @@ -1,6 +1,6 @@ #include "AP_Periph.h" -#ifdef HAL_PERIPH_ENABLE_BATTERY +#if AP_PERIPH_BATTERY_ENABLED /* battery support @@ -124,5 +124,4 @@ void AP_Periph_FW::can_battery_send_cells(uint8_t instance) delete [] buffer; } -#endif // HAL_PERIPH_ENABLE_BATTERY - +#endif // AP_PERIPH_BATTERY_ENABLED diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index fcbcbf5a27..1eccb770d8 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -349,7 +349,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C #if AP_PERIPH_GPS_ENABLED AP_Param::setup_object_defaults(&gps, gps.var_info); #endif -#ifdef HAL_PERIPH_ENABLE_BATTERY +#if AP_PERIPH_BATTERY_ENABLED AP_Param::setup_object_defaults(&battery, battery_lib.var_info); #endif #ifdef HAL_PERIPH_ENABLE_MAG @@ -1891,7 +1891,7 @@ void AP_Periph_FW::can_update() #if AP_UART_MONITOR_ENABLED send_serial_monitor_data(); #endif -#ifdef HAL_PERIPH_ENABLE_BATTERY +#if AP_PERIPH_BATTERY_ENABLED can_battery_update(); #endif #ifdef HAL_PERIPH_ENABLE_BARO diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index bf1bebf04e..99ce069db5 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -958,7 +958,7 @@ class sitl_periph_universal(sitl_periph): HAL_PERIPH_ENABLE_BARO = 1, HAL_PERIPH_ENABLE_IMU = 1, HAL_PERIPH_ENABLE_RANGEFINDER = 1, - HAL_PERIPH_ENABLE_BATTERY = 1, + AP_PERIPH_BATTERY_ENABLED = 1, HAL_PERIPH_ENABLE_EFI = 1, HAL_PERIPH_ENABLE_RPM = 1, HAL_PERIPH_ENABLE_RPM_STREAM = 1, @@ -997,7 +997,7 @@ class sitl_periph_battmon(sitl_periph): CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_battmon"', APJ_BOARD_ID = 101, - HAL_PERIPH_ENABLE_BATTERY = 1, + AP_PERIPH_BATTERY_ENABLED = 1, ) class esp32(Board):