Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp
Views: 1798
#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: .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 && driver->_node_id == node_id && match_battery_id(i, battery_id)) {77return driver;78}79}80// find empty uavcan driver81for (uint8_t i = 0; i < batt._num_instances; i++) {82if (batt.drivers[i] != nullptr &&83batt.allocated_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo &&84match_battery_id(i, battery_id)) {8586AP_BattMonitor_DroneCAN* batmon = (AP_BattMonitor_DroneCAN*)batt.drivers[i];87if(batmon->_ap_dronecan != nullptr || batmon->_node_id != 0) {88continue;89}90batmon->_ap_dronecan = ap_dronecan;91batmon->_node_id = node_id;92batmon->_instance = i;93batmon->init();94AP::can().log_text(AP_CANManager::LOG_INFO,95LOG_TAG,96"Registered BattMonitor Node %d on Bus %d\n",97node_id,98ap_dronecan->get_driver_index());99return batmon;100}101}102return nullptr;103}104105void AP_BattMonitor_DroneCAN::handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg)106{107update_interim_state(msg.voltage, msg.current, msg.temperature, msg.state_of_charge_pct, msg.state_of_health_pct);108109WITH_SEMAPHORE(_sem_battmon);110_remaining_capacity_wh = msg.remaining_capacity_wh;111_full_charge_capacity_wh = msg.full_charge_capacity_wh;112113// consume state of health114if (msg.state_of_health_pct != UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN) {115_interim_state.state_of_health_pct = msg.state_of_health_pct;116_interim_state.has_state_of_health_pct = true;117}118}119120void AP_BattMonitor_DroneCAN::update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc, uint8_t soh_pct)121{122WITH_SEMAPHORE(_sem_battmon);123124_interim_state.voltage = voltage;125_interim_state.current_amps = _curr_mult * current;126_soc = soc;127128if (!isnan(temperature_K) && temperature_K > 0) {129// Temperature reported from battery in kelvin and stored internally in Celsius.130_interim_state.temperature = KELVIN_TO_C(temperature_K);131_interim_state.temperature_time = AP_HAL::millis();132}133134const uint32_t tnow = AP_HAL::micros();135136if (!_has_battery_info_aux ||137!use_CAN_SoC()) {138const uint32_t dt_us = tnow - _interim_state.last_time_micros;139140// update total current drawn since startup141update_consumed(_interim_state, dt_us);142}143144// state of health145if (soh_pct != UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN) {146_interim_state.state_of_health_pct = soh_pct;147_interim_state.has_state_of_health_pct = true;148}149150// record time151_interim_state.last_time_micros = tnow;152_interim_state.healthy = true;153}154155void AP_BattMonitor_DroneCAN::handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg)156{157WITH_SEMAPHORE(_sem_battmon);158uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), msg.voltage_cell.len);159160_cycle_count = msg.cycle_count;161for (uint8_t i = 0; i < cell_count; i++) {162_interim_state.cell_voltages.cells[i] = msg.voltage_cell.data[i] * 1000;163}164_interim_state.is_powering_off = msg.is_powering_off;165if (!isnan(msg.nominal_voltage) && msg.nominal_voltage > 0) {166float remaining_capacity_ah = _remaining_capacity_wh / msg.nominal_voltage;167float full_charge_capacity_ah = _full_charge_capacity_wh / msg.nominal_voltage;168_interim_state.consumed_mah = (full_charge_capacity_ah - remaining_capacity_ah) * 1000;169_interim_state.consumed_wh = _full_charge_capacity_wh - _remaining_capacity_wh;170_interim_state.time_remaining = is_zero(_interim_state.current_amps) ? 0 : (remaining_capacity_ah / _interim_state.current_amps * 3600);171_interim_state.has_time_remaining = true;172}173174_has_cell_voltages = true;175_has_battery_info_aux = true;176}177178void AP_BattMonitor_DroneCAN::handle_mppt_stream(const mppt_Stream &msg)179{180const bool use_input_value = option_is_set(AP_BattMonitor_Params::Options::MPPT_Use_Input_Value);181const float voltage = use_input_value ? msg.input_voltage : msg.output_voltage;182const float current = use_input_value ? msg.input_current : msg.output_current;183184// use an invalid soc so we use the library calculated one185const uint8_t soc = 127;186187// convert C to Kelvin188const float temperature_K = isnan(msg.temperature) ? 0 : C_TO_KELVIN(msg.temperature);189190update_interim_state(voltage, current, temperature_K, soc, UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN);191192if (!_mppt.is_detected) {193// this is the first time the mppt message has been received194// so set powered up state195_mppt.is_detected = true;196197// Boot/Power-up event198if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Boot)) {199mppt_set_powered_state(true);200} else if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Boot)) {201mppt_set_powered_state(false);202}203}204205#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG206if (_mppt.fault_flags != msg.fault_flags) {207mppt_report_faults(_instance, msg.fault_flags);208}209#endif210_mppt.fault_flags = msg.fault_flags;211}212213void AP_BattMonitor_DroneCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg)214{215AP_BattMonitor_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id);216if (driver == nullptr) {217return;218}219driver->handle_battery_info(msg);220}221222void AP_BattMonitor_DroneCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg)223{224const auto &batt = AP::battery();225AP_BattMonitor_DroneCAN *driver = nullptr;226227/*228check for a backend with AllowSplitAuxInfo set, allowing InfoAux229from a different CAN node than the base battery information230*/231for (uint8_t i = 0; i < batt._num_instances; i++) {232const auto *drv = batt.drivers[i];233if (drv != nullptr &&234batt.allocated_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo &&235drv->option_is_set(AP_BattMonitor_Params::Options::AllowSplitAuxInfo) &&236batt.get_serial_number(i) == int32_t(msg.battery_id)) {237driver = (AP_BattMonitor_DroneCAN *)batt.drivers[i];238if (driver->_ap_dronecan == nullptr) {239/* we have not received the main battery information240yet. Discard InfoAux until we do so we can init the241backend with the right node ID242*/243return;244}245break;246}247}248if (driver == nullptr) {249driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id);250}251if (driver == nullptr) {252return;253}254driver->handle_battery_info_aux(msg);255}256257void AP_BattMonitor_DroneCAN::handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg)258{259AP_BattMonitor_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, transfer.source_node_id);260if (driver == nullptr) {261return;262}263driver->handle_mppt_stream(msg);264}265266// read - read the voltage and current267void AP_BattMonitor_DroneCAN::read()268{269uint32_t tnow = AP_HAL::micros();270271// timeout after 5 seconds272if ((tnow - _interim_state.last_time_micros) > AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS) {273_interim_state.healthy = false;274}275// Copy over relevant states over to main state276WITH_SEMAPHORE(_sem_battmon);277_state.temperature = _interim_state.temperature;278_state.temperature_time = _interim_state.temperature_time;279_state.voltage = _interim_state.voltage;280_state.current_amps = _interim_state.current_amps;281_state.consumed_mah = _interim_state.consumed_mah;282_state.consumed_wh = _interim_state.consumed_wh;283_state.last_time_micros = _interim_state.last_time_micros;284_state.healthy = _interim_state.healthy;285_state.time_remaining = _interim_state.time_remaining;286_state.has_time_remaining = _interim_state.has_time_remaining;287_state.is_powering_off = _interim_state.is_powering_off;288_state.state_of_health_pct = _interim_state.state_of_health_pct;289_state.has_state_of_health_pct = _interim_state.has_state_of_health_pct;290memcpy(_state.cell_voltages.cells, _interim_state.cell_voltages.cells, sizeof(_state.cell_voltages));291292_has_temperature = (AP_HAL::millis() - _state.temperature_time) <= AP_BATT_MONITOR_TIMEOUT;293294// check if MPPT should be powered on/off depending upon arming state295if (_mppt.is_detected) {296mppt_check_powered_state();297}298}299300// Return true if the DroneCAN state of charge should be used.301// Return false if state of charge should be calculated locally by counting mah.302bool AP_BattMonitor_DroneCAN::use_CAN_SoC() const303{304// a UAVCAN battery monitor may not be able to supply a state of charge. If it can't then305// the user can set the option to use current integration in the backend instead.306// SOC of 127 is used as an invalid SOC flag ie system configuration errors or SOC estimation unavailable307return !(option_is_set(AP_BattMonitor_Params::Options::Ignore_UAVCAN_SoC) ||308_mppt.is_detected ||309(_soc == 127));310}311312/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument313bool AP_BattMonitor_DroneCAN::capacity_remaining_pct(uint8_t &percentage) const314{315if (!use_CAN_SoC()) {316return AP_BattMonitor_Backend::capacity_remaining_pct(percentage);317}318319// the monitor must have current readings in order to estimate consumed_mah and be healthy320if (!has_current() || !_state.healthy) {321return false;322}323324percentage = _soc;325return true;326}327328// reset remaining percentage to given value329bool AP_BattMonitor_DroneCAN::reset_remaining(float percentage)330{331if (use_CAN_SoC()) {332// Cannot reset external state of charge333return false;334}335336WITH_SEMAPHORE(_sem_battmon);337338if (!AP_BattMonitor_Backend::reset_remaining(percentage)) {339// Base class reset failed340return false;341}342343// Reset interim state that is used internally, this is then copied back to the main state in the read() call344_interim_state.consumed_mah = _state.consumed_mah;345_interim_state.consumed_wh = _state.consumed_wh;346return true;347}348349/// get_cycle_count - return true if cycle count can be provided and fills in cycles argument350bool AP_BattMonitor_DroneCAN::get_cycle_count(uint16_t &cycles) const351{352if (_has_battery_info_aux) {353cycles = _cycle_count;354return true;355}356return false;357}358359// request MPPT board to power on/off depending upon vehicle arming state as specified by BATT_OPTIONS360void AP_BattMonitor_DroneCAN::mppt_check_powered_state()361{362if ((_mppt.powered_state_remote_ms != 0) && (AP_HAL::millis() - _mppt.powered_state_remote_ms >= 1000)) {363// there's already a set attempt that didnt' respond. Retry at 1Hz364mppt_set_powered_state(_mppt.powered_state);365}366367// check if vehicle armed state has changed368const bool vehicle_armed = hal.util->get_soft_armed();369if ((!_mppt.vehicle_armed_last && vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Arm)) {370// arm event371mppt_set_powered_state(true);372} else if ((_mppt.vehicle_armed_last && !vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Disarm)) {373// disarm event374mppt_set_powered_state(false);375}376_mppt.vehicle_armed_last = vehicle_armed;377}378379// request MPPT board to power on or off380// power_on should be true to power on the MPPT, false to power off381// force should be true to force sending the state change request to the MPPT382void AP_BattMonitor_DroneCAN::mppt_set_powered_state(bool power_on)383{384if (_ap_dronecan == nullptr || !_mppt.is_detected) {385return;386}387388_mppt.powered_state = power_on;389390GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: powering %s%s", (unsigned)_instance+1, _mppt.powered_state ? "ON" : "OFF",391(_mppt.powered_state_remote_ms == 0) ? "" : " Retry");392393mppt_OutputEnableRequest request;394request.enable = _mppt.powered_state;395request.disable = !request.enable;396397if (mppt_outputenable_client == nullptr) {398mppt_outputenable_client = NEW_NOTHROW Canard::Client<mppt_OutputEnableResponse>{_ap_dronecan->get_canard_iface(), mppt_outputenable_res_cb};399if (mppt_outputenable_client == nullptr) {400return;401}402}403mppt_outputenable_client->request(_node_id, request);404}405406// callback from outputEnable to verify it is enabled or disabled407void AP_BattMonitor_DroneCAN::handle_outputEnable_response(const CanardRxTransfer& transfer, const mppt_OutputEnableResponse& response)408{409if (transfer.source_node_id != _node_id) {410// this response is not from the node we are looking for411return;412}413414if (response.enabled == _mppt.powered_state) {415// we got back what we expected it to be. We set it on, it now says it on (or vice versa).416// Clear the timer so we don't re-request417_mppt.powered_state_remote_ms = 0;418}419}420421#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG422// report changes in MPPT faults423void AP_BattMonitor_DroneCAN::mppt_report_faults(const uint8_t instance, const uint8_t fault_flags)424{425// handle recovery426if (fault_flags == 0) {427GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: OK", (unsigned)instance+1);428return;429}430431// send battery faults via text messages432for (uint8_t fault_bit=0x01; fault_bit <= 0x08; fault_bit <<= 1) {433// this loop is to generate multiple messages if there are multiple concurrent faults, but also run once if there are no faults434if ((fault_bit & fault_flags) != 0) {435const MPPT_FaultFlags err = (MPPT_FaultFlags)fault_bit;436GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: %s", (unsigned)instance+1, mppt_fault_string(err));437}438}439}440441// returns string description of MPPT fault bit. Only handles single bit faults442const char* AP_BattMonitor_DroneCAN::mppt_fault_string(const MPPT_FaultFlags fault)443{444switch (fault) {445case MPPT_FaultFlags::OVER_VOLTAGE:446return "over voltage";447case MPPT_FaultFlags::UNDER_VOLTAGE:448return "under voltage";449case MPPT_FaultFlags::OVER_CURRENT:450return "over current";451case MPPT_FaultFlags::OVER_TEMPERATURE:452return "over temp";453}454return "unknown";455}456#endif457458// return mavlink fault bitmask (see MAV_BATTERY_FAULT enum)459uint32_t AP_BattMonitor_DroneCAN::get_mavlink_fault_bitmask() const460{461// return immediately if not mppt or no faults462if (!_mppt.is_detected || (_mppt.fault_flags == 0)) {463return 0;464}465466// convert mppt fault bitmask to mavlink fault bitmask467uint32_t mav_fault_bitmask = 0;468if ((_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_VOLTAGE) || (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::UNDER_VOLTAGE)) {469mav_fault_bitmask |= MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE;470}471if (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_CURRENT) {472mav_fault_bitmask |= MAV_BATTERY_FAULT_OVER_CURRENT;473}474if (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_TEMPERATURE) {475mav_fault_bitmask |= MAV_BATTERY_FAULT_OVER_TEMPERATURE;476}477return mav_fault_bitmask;478}479480#endif // AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED481482483