Tools: create and use AP_PERIPH_BATTERY_ENABLED

... and AP_PERIPH_BATTERY_BALANCE_ENABLED while we're here
This commit is contained in:
Peter Barker 2025-01-23 15:47:00 +11:00 committed by Peter Barker
parent a8717fe6a2
commit b3bc0528e0
9 changed files with 18 additions and 19 deletions

View File

@ -177,7 +177,7 @@ void AP_Periph_FW::init()
} }
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY #if AP_PERIPH_BATTERY_ENABLED
battery_lib.init(); battery_lib.init();
#endif #endif
@ -485,7 +485,7 @@ void AP_Periph_FW::update()
#endif #endif
} }
#ifdef HAL_PERIPH_ENABLE_BATTERY #if AP_PERIPH_BATTERY_ENABLED
if (now - battery.last_read_ms >= 100) { if (now - battery.last_read_ms >= 100) {
// update battery at 10Hz // update battery at 10Hz
battery.last_read_ms = now; battery.last_read_ms = now;
@ -497,7 +497,7 @@ void AP_Periph_FW::update()
rcin_update(); rcin_update();
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE #if AP_PERIPH_BATTERY_BALANCE_ENABLED
batt_balance_update(); batt_balance_update();
#endif #endif

View File

@ -249,7 +249,7 @@ public:
#endif #endif
#endif // HAL_PERIPH_ENABLE_RPM #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) { } 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}; AP_BattMonitor battery_lib{0, FUNCTOR_BIND_MEMBER(&AP_Periph_FW::handle_battery_failsafe, void, const char*, const int8_t), nullptr};
struct { struct {
@ -379,7 +379,7 @@ public:
Parameters_RCIN g_rcin; Parameters_RCIN g_rcin;
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE #if AP_PERIPH_BATTERY_BALANCE_ENABLED
void batt_balance_update(); void batt_balance_update();
BattBalance battery_balance; BattBalance battery_balance;
#endif #endif

View File

@ -250,7 +250,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
#endif #endif
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY #if AP_PERIPH_BATTERY_ENABLED
// @Group: BATT // @Group: BATT
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT(battery_lib, "BATT", AP_BattMonitor), 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), GOBJECT(g_rcin, "RC", Parameters_RCIN),
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE #if AP_PERIPH_BATTERY_BALANCE_ENABLED
// @Group: BAL // @Group: BAL
// @Path: batt_balance.cpp // @Path: batt_balance.cpp
GOBJECT(battery_balance, "BAL", BattBalance), GOBJECT(battery_balance, "BAL", BattBalance),

View File

@ -204,7 +204,7 @@ public:
AP_Int16 sysid_this_mav; AP_Int16 sysid_this_mav;
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY #if AP_PERIPH_BATTERY_ENABLED
AP_Int32 battery_hide_mask; AP_Int32 battery_hide_mask;
#endif #endif

View File

@ -15,7 +15,7 @@
#include "AP_Periph.h" #include "AP_Periph.h"
#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE #if AP_PERIPH_BATTERY_BALANCE_ENABLED
#include <dronecan_msgs.h> #include <dronecan_msgs.h>
@ -134,5 +134,5 @@ void AP_Periph_FW::batt_balance_update()
delete [] buffer; delete [] buffer;
} }
#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE #endif // AP_PERIPH_BATTERY_BALANCE_ENABLED

View File

@ -1,6 +1,6 @@
#pragma once #pragma once
#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE #if AP_PERIPH_BATTERY_BALANCE_ENABLED
class BattBalance { class BattBalance {
public: public:
@ -20,5 +20,5 @@ private:
uint8_t cells_allocated; uint8_t cells_allocated;
}; };
#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE #endif // AP_PERIPH_BATTERY_BALANCE_ENABLED

View File

@ -1,6 +1,6 @@
#include "AP_Periph.h" #include "AP_Periph.h"
#ifdef HAL_PERIPH_ENABLE_BATTERY #if AP_PERIPH_BATTERY_ENABLED
/* /*
battery support battery support
@ -124,5 +124,4 @@ void AP_Periph_FW::can_battery_send_cells(uint8_t instance)
delete [] buffer; delete [] buffer;
} }
#endif // HAL_PERIPH_ENABLE_BATTERY #endif // AP_PERIPH_BATTERY_ENABLED

View File

@ -349,7 +349,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C
#if AP_PERIPH_GPS_ENABLED #if AP_PERIPH_GPS_ENABLED
AP_Param::setup_object_defaults(&gps, gps.var_info); AP_Param::setup_object_defaults(&gps, gps.var_info);
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY #if AP_PERIPH_BATTERY_ENABLED
AP_Param::setup_object_defaults(&battery, battery_lib.var_info); AP_Param::setup_object_defaults(&battery, battery_lib.var_info);
#endif #endif
#ifdef HAL_PERIPH_ENABLE_MAG #ifdef HAL_PERIPH_ENABLE_MAG
@ -1891,7 +1891,7 @@ void AP_Periph_FW::can_update()
#if AP_UART_MONITOR_ENABLED #if AP_UART_MONITOR_ENABLED
send_serial_monitor_data(); send_serial_monitor_data();
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY #if AP_PERIPH_BATTERY_ENABLED
can_battery_update(); can_battery_update();
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BARO #ifdef HAL_PERIPH_ENABLE_BARO

View File

@ -958,7 +958,7 @@ class sitl_periph_universal(sitl_periph):
HAL_PERIPH_ENABLE_BARO = 1, HAL_PERIPH_ENABLE_BARO = 1,
HAL_PERIPH_ENABLE_IMU = 1, HAL_PERIPH_ENABLE_IMU = 1,
HAL_PERIPH_ENABLE_RANGEFINDER = 1, HAL_PERIPH_ENABLE_RANGEFINDER = 1,
HAL_PERIPH_ENABLE_BATTERY = 1, AP_PERIPH_BATTERY_ENABLED = 1,
HAL_PERIPH_ENABLE_EFI = 1, HAL_PERIPH_ENABLE_EFI = 1,
HAL_PERIPH_ENABLE_RPM = 1, HAL_PERIPH_ENABLE_RPM = 1,
HAL_PERIPH_ENABLE_RPM_STREAM = 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"', CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_battmon"',
APJ_BOARD_ID = 101, APJ_BOARD_ID = 101,
HAL_PERIPH_ENABLE_BATTERY = 1, AP_PERIPH_BATTERY_ENABLED = 1,
) )
class esp32(Board): class esp32(Board):