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_SMBus_SUI.cpp
Views: 1798
#include "AP_BattMonitor_config.h"12#if AP_BATTERY_SMBUS_SUI_ENABLED34#include <AP_HAL/AP_HAL.h>5#include <AP_Common/AP_Common.h>6#include <AP_Math/AP_Math.h>7#include "AP_BattMonitor.h"89#include "AP_BattMonitor_SMBus_SUI.h"1011extern const AP_HAL::HAL& hal;1213#define REG_CELL_VOLTAGE 0x2814#define REG_CURRENT 0x2a1516// maximum number of cells that we can read data for17#define SUI_MAX_CELL_READ 41819// Constructor20AP_BattMonitor_SMBus_SUI::AP_BattMonitor_SMBus_SUI(AP_BattMonitor &mon,21AP_BattMonitor::BattMonitor_State &mon_state,22AP_BattMonitor_Params ¶ms,23uint8_t _cell_count)24: AP_BattMonitor_SMBus(mon, mon_state, params, AP_BATTMONITOR_SMBUS_BUS_INTERNAL),25cell_count(_cell_count)26{27_pec_supported = false;28}2930void AP_BattMonitor_SMBus_SUI::init(void)31{32AP_BattMonitor_SMBus::init();33if (_dev) {34_dev->set_retries(2);35}36if (_dev && timer_handle) {37// run twice as fast for two phases38_dev->adjust_periodic_callback(timer_handle, 50000);39}40}4142void AP_BattMonitor_SMBus_SUI::timer()43{44uint32_t tnow = AP_HAL::micros();4546// we read in two phases as the device can stall if you read47// current too rapidly after voltages48phase_voltages = !phase_voltages;4950if (phase_voltages) {51read_cell_voltages();52update_health();53return;54}5556// read current57int32_t current_ma;58if (read_block_bare(REG_CURRENT, (uint8_t *)¤t_ma, sizeof(current_ma))) {59_state.current_amps = current_ma * -0.001;60_state.last_time_micros = tnow;61}6263read_full_charge_capacity();6465read_temp();66read_serial_number();67read_remaining_capacity();68update_health();69}7071// read_bare_block - returns true if successful72bool AP_BattMonitor_SMBus_SUI::read_block_bare(uint8_t reg, uint8_t* data, uint8_t len) const73{74// read bytes75if (!_dev->read_registers(reg, data, len)) {76return false;77}7879// return success80return true;81}8283void AP_BattMonitor_SMBus_SUI::read_cell_voltages()84{85// read cell voltages86uint16_t voltbuff[SUI_MAX_CELL_READ];8788if (!read_block(REG_CELL_VOLTAGE, (uint8_t *)voltbuff, sizeof(voltbuff))) {89return;90}91float pack_voltage_mv = 0.0f;9293for (uint8_t i = 0; i < MIN(SUI_MAX_CELL_READ, cell_count); i++) {94const uint16_t cell = voltbuff[i];95_state.cell_voltages.cells[i] = cell;96pack_voltage_mv += (float)cell;97}9899if (cell_count >= SUI_MAX_CELL_READ) {100// we can't read voltage of all cells. get overall pack voltage to work out101// an average for remaining cells102uint16_t total_mv;103if (read_word(BATTMONITOR_SMBUS_VOLTAGE, total_mv)) {104// if total voltage is below pack_voltage_mv then we will105// read zero volts for the extra cells.106total_mv = MAX(total_mv, pack_voltage_mv);107const uint16_t cell_mv = (total_mv - pack_voltage_mv) / (cell_count - SUI_MAX_CELL_READ);108for (uint8_t i = SUI_MAX_CELL_READ; i < cell_count; i++) {109_state.cell_voltages.cells[i] = cell_mv;110}111pack_voltage_mv = total_mv;112} else {113// we can't get total pack voltage. Use average of cells we have so far114const uint16_t cell_mv = pack_voltage_mv / SUI_MAX_CELL_READ;115for (uint8_t i = SUI_MAX_CELL_READ; i < cell_count; i++) {116_state.cell_voltages.cells[i] = cell_mv;117}118pack_voltage_mv += cell_mv * (cell_count - SUI_MAX_CELL_READ);119}120}121122_has_cell_voltages = true;123124// accumulate the pack voltage out of the total of the cells125_state.voltage = pack_voltage_mv * 0.001;126last_volt_read_us = AP_HAL::micros();127}128129/*130update healthy flag131*/132void AP_BattMonitor_SMBus_SUI::update_health()133{134uint32_t now = AP_HAL::micros();135_state.healthy = (now - last_volt_read_us < AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS) &&136(now - _state.last_time_micros < AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS);137}138139#endif // AP_BATTERY_SMBUS_SUI_ENABLED140141142