Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp
9608 views
#include "AP_BattMonitor_config.h"12#if AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED34#include <AP_HAL/AP_HAL.h>5#include "AP_BattMonitor.h"6#include "AP_BattMonitor_DroneCAN.h"78#include <AP_CANManager/AP_CANManager.h>9#include <AP_Common/AP_Common.h>10#include <GCS_MAVLink/GCS.h>11#include <AP_Math/AP_Math.h>12#include <AP_DroneCAN/AP_DroneCAN.h>13#include <AP_BoardConfig/AP_BoardConfig.h>1415#define LOG_TAG "BattMon"1617extern const AP_HAL::HAL& hal;1819const AP_Param::GroupInfo AP_BattMonitor_DroneCAN::var_info[] = {2021// @Param: CURR_MULT22// @DisplayName: Scales reported power monitor current23// @Description: Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications24// @Range: 0.1 1025// @User: Advanced26AP_GROUPINFO("CURR_MULT", 30, AP_BattMonitor_DroneCAN, _curr_mult, 1.0),2728// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS2930AP_GROUPEND31};3233/// Constructor34AP_BattMonitor_DroneCAN::AP_BattMonitor_DroneCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_DroneCAN_Type type, AP_BattMonitor_Params ¶ms) :35AP_BattMonitor_Backend(mon, mon_state, params)36{37AP_Param::setup_object_defaults(this,var_info);38_state.var_info = var_info;3940// starts with not healthy41_state.healthy = false;42}4344bool AP_BattMonitor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)45{46const auto driver_index = ap_dronecan->get_driver_index();4748return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_trampoline, driver_index) != nullptr)49&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_aux_trampoline, driver_index) != nullptr)50&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_mppt_stream_trampoline, driver_index) != nullptr)51;52}5354/*55match a battery ID to driver serial number56when serial number is negative, all batteries are accepted, otherwise it must match57*/58bool AP_BattMonitor_DroneCAN::match_battery_id(uint8_t instance, uint8_t battery_id)59{60const auto serial_num = AP::battery().get_serial_number(instance);61return serial_num < 0 || serial_num == (int32_t)battery_id;62}6364AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id)65{66if (ap_dronecan == nullptr) {67return nullptr;68}69const auto &batt = AP::battery();70for (uint8_t i = 0; i < batt._num_instances; i++) {71if (batt.drivers[i] == nullptr ||72batt.allocated_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) {73continue;74}75AP_BattMonitor_DroneCAN* driver = (AP_BattMonitor_DroneCAN*)batt.drivers[i];76if (driver->_ap_dronecan == ap_dronecan && match_battery_id(i, battery_id)) {77if (driver->_node_id == node_id) {78return driver;79} else if (!driver->_interim_state.healthy && driver->option_is_set(AP_BattMonitor_Params::Options::AllowDynamicNodeUpdate)) {80GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: Node change from %d to %d for Id %d",81(unsigned)i+1, driver->_node_id, node_id, battery_id);82driver->_node_id = node_id;83driver->init();84return driver;85}86}87}88// find empty uavcan driver89for (uint8_t i = 0; i < batt._num_instances; i++) {90if (batt.drivers[i] != nullptr &&91batt.allocated_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo &&92match_battery_id(i, battery_id)) {9394AP_BattMonitor_DroneCAN* batmon = (AP_BattMonitor_DroneCAN*)batt.drivers[i];95if(batmon->_ap_dronecan != nullptr || batmon->_node_id != 0) {96continue;97}98batmon->_ap_dronecan = ap_dronecan;99batmon->_node_id = node_id;100batmon->_instance = i;101batmon->init();102AP::can().log_text(AP_CANManager::LOG_INFO,103LOG_TAG,104"Registered BattMonitor Node %d on Bus %d\n",105node_id,106ap_dronecan->get_driver_index());107return batmon;108}109}110return nullptr;111}112113void AP_BattMonitor_DroneCAN::handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg)114{115update_interim_state(msg.voltage, msg.current, msg.temperature, msg.state_of_charge_pct, msg.state_of_health_pct);116117WITH_SEMAPHORE(_sem_battmon);118_remaining_capacity_wh = msg.remaining_capacity_wh;119_full_charge_capacity_wh = msg.full_charge_capacity_wh;120121// consume state of health122if (msg.state_of_health_pct != UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN) {123_interim_state.state_of_health_pct = msg.state_of_health_pct;124_interim_state.has_state_of_health_pct = true;125}126}127128void AP_BattMonitor_DroneCAN::update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc, uint8_t soh_pct)129{130WITH_SEMAPHORE(_sem_battmon);131132_interim_state.voltage = voltage;133_interim_state.current_amps = _curr_mult * current;134_soc = soc;135136if (!isnan(temperature_K) && temperature_K > 0) {137// Temperature reported from battery in kelvin and stored internally in Celsius.138_interim_state.temperature = KELVIN_TO_C(temperature_K);139_interim_state.temperature_time = AP_HAL::millis();140}141142const uint32_t tnow = AP_HAL::micros();143144if (!_has_battery_info_aux ||145!use_CAN_SoC()) {146const uint32_t dt_us = tnow - _interim_state.last_time_micros;147148// update total current drawn since startup149update_consumed(_interim_state, dt_us);150}151152// state of health153if (soh_pct != UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN) {154_interim_state.state_of_health_pct = soh_pct;155_interim_state.has_state_of_health_pct = true;156}157158// record time159_interim_state.last_time_micros = tnow;160_interim_state.healthy = true;161}162163void AP_BattMonitor_DroneCAN::handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg)164{165WITH_SEMAPHORE(_sem_battmon);166uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), msg.voltage_cell.len);167168_cycle_count = msg.cycle_count;169for (uint8_t i = 0; i < cell_count; i++) {170_interim_state.cell_voltages.cells[i] = msg.voltage_cell.data[i] * 1000;171}172_interim_state.is_powering_off = msg.is_powering_off;173if (!isnan(msg.nominal_voltage) && msg.nominal_voltage > 0) {174float remaining_capacity_ah = _remaining_capacity_wh / msg.nominal_voltage;175float full_charge_capacity_ah = _full_charge_capacity_wh / msg.nominal_voltage;176_interim_state.consumed_mah = (full_charge_capacity_ah - remaining_capacity_ah) * 1000;177_interim_state.consumed_wh = _full_charge_capacity_wh - _remaining_capacity_wh;178_interim_state.time_remaining = is_zero(_interim_state.current_amps) ? 0 : (remaining_capacity_ah / _interim_state.current_amps * 3600);179_interim_state.has_time_remaining = true;180}181182_has_cell_voltages = true;183_has_battery_info_aux = true;184}185186void AP_BattMonitor_DroneCAN::handle_mppt_stream(const mppt_Stream &msg)187{188const bool use_input_value = option_is_set(AP_BattMonitor_Params::Options::MPPT_Use_Input_Value);189const float voltage = use_input_value ? msg.input_voltage : msg.output_voltage;190const float current = use_input_value ? msg.input_current : msg.output_current;191192// use an invalid soc so we use the library calculated one193const uint8_t soc = 127;194195// convert C to Kelvin196const float temperature_K = isnan(msg.temperature) ? 0 : C_TO_KELVIN(msg.temperature);197198update_interim_state(voltage, current, temperature_K, soc, UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN);199200if (!_mppt.is_detected) {201// this is the first time the mppt message has been received202// so set powered up state203_mppt.is_detected = true;204205// Boot/Power-up event206if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Boot)) {207set_powered_state(true);208} else if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Boot)) {209set_powered_state(false);210}211}212213#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG214if (_mppt.fault_flags != msg.fault_flags) {215mppt_report_faults(_instance, msg.fault_flags);216}217#endif218_mppt.fault_flags = msg.fault_flags;219}220221void AP_BattMonitor_DroneCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg)222{223AP_BattMonitor_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id);224if (driver == nullptr) {225return;226}227driver->handle_battery_info(msg);228}229230void AP_BattMonitor_DroneCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg)231{232const auto &batt = AP::battery();233AP_BattMonitor_DroneCAN *driver = nullptr;234235/*236check for a backend with AllowSplitAuxInfo set, allowing InfoAux237from a different CAN node than the base battery information238*/239for (uint8_t i = 0; i < batt._num_instances; i++) {240const auto *drv = batt.drivers[i];241if (drv != nullptr &&242batt.allocated_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo &&243drv->option_is_set(AP_BattMonitor_Params::Options::AllowSplitAuxInfo) &&244batt.get_serial_number(i) == int32_t(msg.battery_id)) {245driver = (AP_BattMonitor_DroneCAN *)batt.drivers[i];246if (driver->_ap_dronecan == nullptr) {247/* we have not received the main battery information248yet. Discard InfoAux until we do so we can init the249backend with the right node ID250*/251return;252}253break;254}255}256if (driver == nullptr) {257driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id);258}259if (driver == nullptr) {260return;261}262driver->handle_battery_info_aux(msg);263}264265void AP_BattMonitor_DroneCAN::handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg)266{267AP_BattMonitor_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, transfer.source_node_id);268if (driver == nullptr) {269return;270}271driver->handle_mppt_stream(msg);272}273274// read - read the voltage and current275void AP_BattMonitor_DroneCAN::read()276{277uint32_t tnow = AP_HAL::micros();278279// timeout after 5 seconds280if ((tnow - _interim_state.last_time_micros) > AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS) {281_interim_state.healthy = false;282}283// Copy over relevant states over to main state284WITH_SEMAPHORE(_sem_battmon);285_state.temperature = _interim_state.temperature;286_state.temperature_time = _interim_state.temperature_time;287_state.voltage = _interim_state.voltage;288_state.current_amps = _interim_state.current_amps;289_state.consumed_mah = _interim_state.consumed_mah;290_state.consumed_wh = _interim_state.consumed_wh;291_state.last_time_micros = _interim_state.last_time_micros;292_state.healthy = _interim_state.healthy;293_state.time_remaining = _interim_state.time_remaining;294_state.has_time_remaining = _interim_state.has_time_remaining;295_state.is_powering_off = _interim_state.is_powering_off;296_state.state_of_health_pct = _interim_state.state_of_health_pct;297_state.has_state_of_health_pct = _interim_state.has_state_of_health_pct;298memcpy(_state.cell_voltages.cells, _interim_state.cell_voltages.cells, sizeof(_state.cell_voltages));299300_has_temperature = (AP_HAL::millis() - _state.temperature_time) <= AP_BATT_MONITOR_TIMEOUT;301302// check if MPPT should be powered on/off depending upon arming state303if (_mppt.is_detected) {304mppt_check_powered_state();305}306}307308// Return true if the DroneCAN state of charge should be used.309// Return false if state of charge should be calculated locally by counting mah.310bool AP_BattMonitor_DroneCAN::use_CAN_SoC() const311{312// a UAVCAN battery monitor may not be able to supply a state of charge. If it can't then313// the user can set the option to use current integration in the backend instead.314// SOC of 127 is used as an invalid SOC flag ie system configuration errors or SOC estimation unavailable315return !(option_is_set(AP_BattMonitor_Params::Options::Ignore_UAVCAN_SoC) ||316_mppt.is_detected ||317(_soc == 127));318}319320/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument321bool AP_BattMonitor_DroneCAN::capacity_remaining_pct(uint8_t &percentage) const322{323if (!use_CAN_SoC()) {324return AP_BattMonitor_Backend::capacity_remaining_pct(percentage);325}326327// the monitor must have current readings in order to estimate consumed_mah and be healthy328if (!has_current() || !_state.healthy) {329return false;330}331332percentage = _soc;333return true;334}335336// reset remaining percentage to given value337bool AP_BattMonitor_DroneCAN::reset_remaining(float percentage)338{339if (use_CAN_SoC()) {340// Cannot reset external state of charge341return false;342}343344WITH_SEMAPHORE(_sem_battmon);345346if (!AP_BattMonitor_Backend::reset_remaining(percentage)) {347// Base class reset failed348return false;349}350351// Reset interim state that is used internally, this is then copied back to the main state in the read() call352_interim_state.consumed_mah = _state.consumed_mah;353_interim_state.consumed_wh = _state.consumed_wh;354return true;355}356357/// get_cycle_count - return true if cycle count can be provided and fills in cycles argument358bool AP_BattMonitor_DroneCAN::get_cycle_count(uint16_t &cycles) const359{360if (_has_battery_info_aux) {361cycles = _cycle_count;362return true;363}364return false;365}366367// request MPPT board to power on/off depending upon vehicle arming state as specified by BATT_OPTIONS368void AP_BattMonitor_DroneCAN::mppt_check_powered_state()369{370if ((_mppt.powered_state_remote_ms != 0) && (AP_HAL::millis() - _mppt.powered_state_remote_ms >= 1000)) {371// there's already a set attempt that didnt' respond. Retry at 1Hz372set_powered_state(_mppt.powered_state);373}374375// check if vehicle armed state has changed376const bool vehicle_armed = hal.util->get_soft_armed();377if ((!_mppt.vehicle_armed_last && vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Arm)) {378// arm event379set_powered_state(true);380} else if ((_mppt.vehicle_armed_last && !vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Disarm)) {381// disarm event382set_powered_state(false);383}384_mppt.vehicle_armed_last = vehicle_armed;385}386387// request MPPT or BMS board to power on or off388// power_on should be true to power on the MPPT, false to power off389// force should be true to force sending the state change request to the MPPT390void AP_BattMonitor_DroneCAN::set_powered_state(bool power_on)391{392if (_ap_dronecan == nullptr || !_mppt.is_detected) {393return;394}395396_mppt.powered_state = power_on;397398GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: powering %s%s", (unsigned)_instance+1, _mppt.powered_state ? "ON" : "OFF",399(_mppt.powered_state_remote_ms == 0) ? "" : " Retry");400401mppt_OutputEnableRequest request;402request.enable = _mppt.powered_state;403request.disable = !request.enable;404405if (mppt_outputenable_client == nullptr) {406mppt_outputenable_client = NEW_NOTHROW Canard::Client<mppt_OutputEnableResponse>{_ap_dronecan->get_canard_iface(), mppt_outputenable_res_cb};407if (mppt_outputenable_client == nullptr) {408return;409}410}411mppt_outputenable_client->request(_node_id, request);412}413414// callback from outputEnable to verify it is enabled or disabled415void AP_BattMonitor_DroneCAN::handle_outputEnable_response(const CanardRxTransfer& transfer, const mppt_OutputEnableResponse& response)416{417if (transfer.source_node_id != _node_id) {418// this response is not from the node we are looking for419return;420}421422if (response.enabled == _mppt.powered_state) {423// we got back what we expected it to be. We set it on, it now says it on (or vice versa).424// Clear the timer so we don't re-request425_mppt.powered_state_remote_ms = 0;426}427}428429#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG430// report changes in MPPT faults431void AP_BattMonitor_DroneCAN::mppt_report_faults(const uint8_t instance, const uint8_t fault_flags)432{433// handle recovery434if (fault_flags == 0) {435GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: OK", (unsigned)instance+1);436return;437}438439// send battery faults via text messages440for (uint8_t fault_bit=0x01; fault_bit <= 0x08; fault_bit <<= 1) {441// this loop is to generate multiple messages if there are multiple concurrent faults, but also run once if there are no faults442if ((fault_bit & fault_flags) != 0) {443const MPPT_FaultFlags err = (MPPT_FaultFlags)fault_bit;444GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: %s", (unsigned)instance+1, mppt_fault_string(err));445}446}447}448449// returns string description of MPPT fault bit. Only handles single bit faults450const char* AP_BattMonitor_DroneCAN::mppt_fault_string(const MPPT_FaultFlags fault)451{452switch (fault) {453case MPPT_FaultFlags::OVER_VOLTAGE:454return "over voltage";455case MPPT_FaultFlags::UNDER_VOLTAGE:456return "under voltage";457case MPPT_FaultFlags::OVER_CURRENT:458return "over current";459case MPPT_FaultFlags::OVER_TEMPERATURE:460return "over temp";461}462return "unknown";463}464#endif465466// return mavlink fault bitmask (see MAV_BATTERY_FAULT enum)467uint32_t AP_BattMonitor_DroneCAN::get_mavlink_fault_bitmask() const468{469// return immediately if not mppt or no faults470if (!_mppt.is_detected || (_mppt.fault_flags == 0)) {471return 0;472}473474// convert mppt fault bitmask to mavlink fault bitmask475uint32_t mav_fault_bitmask = 0;476if ((_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_VOLTAGE) || (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::UNDER_VOLTAGE)) {477mav_fault_bitmask |= MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE;478}479if (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_CURRENT) {480mav_fault_bitmask |= MAV_BATTERY_FAULT_OVER_CURRENT;481}482if (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_TEMPERATURE) {483mav_fault_bitmask |= MAV_BATTERY_FAULT_OVER_TEMPERATURE;484}485return mav_fault_bitmask;486}487488#endif // AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED489490491