AP_Peirph: fix battery parameters

This commit is contained in:
Tom Pittenger 2023-08-22 16:00:26 -07:00 committed by Tom Pittenger
parent cc3fe56a08
commit 4f2344f397
5 changed files with 15 additions and 16 deletions

View File

@ -160,7 +160,7 @@ void AP_Periph_FW::init()
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY #ifdef HAL_PERIPH_ENABLE_BATTERY
battery.lib.init(); battery_lib.init();
#endif #endif
#ifdef HAL_PERIPH_ENABLE_RCIN #ifdef HAL_PERIPH_ENABLE_RCIN
@ -457,7 +457,7 @@ void AP_Periph_FW::update()
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;
battery.lib.read(); battery_lib.read();
} }
#endif #endif

View File

@ -169,10 +169,9 @@ public:
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY #ifdef HAL_PERIPH_ENABLE_BATTERY
struct AP_Periph_Battery { 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 lib{0, FUNCTOR_BIND_MEMBER(&AP_Periph_FW::AP_Periph_Battery::handle_battery_failsafe, void, const char*, const int8_t), nullptr}; struct {
uint32_t last_read_ms; uint32_t last_read_ms;
uint32_t last_can_send_ms; uint32_t last_can_send_ms;
} battery; } battery;

View File

@ -223,7 +223,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
#ifdef HAL_PERIPH_ENABLE_BATTERY #ifdef HAL_PERIPH_ENABLE_BATTERY
// @Group: BATT // @Group: BATT
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT(battery, "BATT", AP_BattMonitor), GOBJECT(battery_lib, "BATT", AP_BattMonitor),
#endif #endif
#ifdef HAL_PERIPH_ENABLE_MAG #ifdef HAL_PERIPH_ENABLE_MAG

View File

@ -31,7 +31,7 @@ public:
k_param_hardpoint_rate, k_param_hardpoint_rate,
k_param_baro_enable, k_param_baro_enable,
k_param_esc_number0, k_param_esc_number0,
k_param_battery, k_param_battery_lib,
k_param_debug, k_param_debug,
k_param_serial_number, k_param_serial_number,
k_param_adsb_port, k_param_adsb_port,

View File

@ -387,7 +387,7 @@ static void handle_param_executeopcode(CanardInstance* canard_instance, CanardRx
AP_Param::setup_object_defaults(&periph.gps, periph.gps.var_info); AP_Param::setup_object_defaults(&periph.gps, periph.gps.var_info);
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BATTERY #ifdef HAL_PERIPH_ENABLE_BATTERY
AP_Param::setup_object_defaults(&periph.battery, periph.battery.lib.var_info); AP_Param::setup_object_defaults(&periph.battery, periph.battery_lib.var_info);
#endif #endif
#ifdef HAL_PERIPH_ENABLE_MAG #ifdef HAL_PERIPH_ENABLE_MAG
AP_Param::setup_object_defaults(&periph.compass, periph.compass.var_info); AP_Param::setup_object_defaults(&periph.compass, periph.compass.var_info);
@ -1977,26 +1977,26 @@ void AP_Periph_FW::can_battery_update(void)
} }
battery.last_can_send_ms = now_ms; battery.last_can_send_ms = now_ms;
const uint8_t battery_instances = battery.lib.num_instances(); const uint8_t battery_instances = battery_lib.num_instances();
for (uint8_t i=0; i<battery_instances; i++) { for (uint8_t i=0; i<battery_instances; i++) {
if (!battery.lib.healthy(i)) { if (!battery_lib.healthy(i)) {
continue; continue;
} }
uavcan_equipment_power_BatteryInfo pkt {}; uavcan_equipment_power_BatteryInfo pkt {};
// if a battery serial number is assigned, use that as the ID. Else, use the index. // if a battery serial number is assigned, use that as the ID. Else, use the index.
const int32_t serial_number = battery.lib.get_serial_number(i); const int32_t serial_number = battery_lib.get_serial_number(i);
pkt.battery_id = (serial_number >= 0) ? serial_number : i+1; pkt.battery_id = (serial_number >= 0) ? serial_number : i+1;
pkt.voltage = battery.lib.voltage(i); pkt.voltage = battery_lib.voltage(i);
float current; float current;
if (battery.lib.current_amps(current, i)) { if (battery_lib.current_amps(current, i)) {
pkt.current = current; pkt.current = current;
} }
float temperature; float temperature;
if (battery.lib.get_temperature(temperature, i)) { if (battery_lib.get_temperature(temperature, i)) {
// Battery lib reports temperature in Celsius. // Battery lib reports temperature in Celsius.
// Convert Celsius to Kelvin for transmission on CAN. // Convert Celsius to Kelvin for transmission on CAN.
pkt.temperature = C_TO_KELVIN(temperature); pkt.temperature = C_TO_KELVIN(temperature);
@ -2004,7 +2004,7 @@ void AP_Periph_FW::can_battery_update(void)
pkt.state_of_health_pct = UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN; pkt.state_of_health_pct = UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN;
uint8_t percentage = 0; uint8_t percentage = 0;
if (battery.lib.capacity_remaining_pct(percentage, i)) { if (battery_lib.capacity_remaining_pct(percentage, i)) {
pkt.state_of_charge_pct = percentage; pkt.state_of_charge_pct = percentage;
} }
pkt.model_instance_id = i+1; pkt.model_instance_id = i+1;