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_INA239.cpp
Views: 1798
#include "AP_BattMonitor_config.h"12#if AP_BATTERY_INA239_ENABLED34#include <GCS_MAVLink/GCS.h>5#include <AP_HAL/utility/sparse-endian.h>67#include "AP_BattMonitor_INA239.h"89extern const AP_HAL::HAL& hal;1011/*12note that registers are clocked on SPI MSB first, with register13number in top 6 bits, LSB is read flag14*/15#define REG_CONFIG 0x0016#define REG_ADC_CONFIG 0x0117#define REG_SHUNT_CAL 0x0218#define REG_SHUNT_VOLTAGE 0x0419#define REG_BUS_VOLTAGE 0x0520#define REG_CURRENT 0x072122#define REG_ADC_CONFIG_RESET 0xFB68U2324#ifndef HAL_BATTMON_INA239_SHUNT_RESISTANCE25#define HAL_BATTMON_INA239_SHUNT_RESISTANCE 0.000226#endif2728#ifndef HAL_BATTMON_INA239_MAX_CURRENT29#define HAL_BATTMON_INA239_MAX_CURRENT 9030#endif3132const AP_Param::GroupInfo AP_BattMonitor_INA239::var_info[] = {3334// @Param: MAX_AMPS35// @DisplayName: Battery monitor max current36// @Description: This controls the maximum current the INA239 sensor will work with.37// @Range: 1 40038// @Units: A39// @User: Advanced40AP_GROUPINFO("MAX_AMPS", 27, AP_BattMonitor_INA239, max_amps, HAL_BATTMON_INA239_MAX_CURRENT),4142// @Param: SHUNT43// @DisplayName: Battery monitor shunt resistor44// @Description: This sets the shunt resistor used in the device45// @Range: 0.0001 0.0146// @Units: Ohm47// @User: Advanced48AP_GROUPINFO("SHUNT", 28, AP_BattMonitor_INA239, rShunt, HAL_BATTMON_INA239_SHUNT_RESISTANCE),4950// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS5152AP_GROUPEND53};5455AP_BattMonitor_INA239::AP_BattMonitor_INA239(AP_BattMonitor &mon,56AP_BattMonitor::BattMonitor_State &mon_state,57AP_BattMonitor_Params ¶ms)58: AP_BattMonitor_Backend(mon, mon_state, params)59{60AP_Param::setup_object_defaults(this, var_info);61_state.var_info = var_info;62}6364void AP_BattMonitor_INA239::init(void)65{66dev = hal.spi->get_device(AP_BATTERY_INA239_SPI_DEVICE);67if (!dev) {68GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "device fail");69return;70}71dev->set_read_flag(0x01);72// register now and configure in the timer callbacks73dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_INA239::timer, void));74}7576void AP_BattMonitor_INA239::configure(void)77{78WITH_SEMAPHORE(dev->get_semaphore());7980int16_t adc_config = 0;8182if (!read_word(REG_ADC_CONFIG, adc_config) ||83uint16_t(adc_config) != REG_ADC_CONFIG_RESET) {84return;85}8687voltage_LSB = 3.125e-3;88current_LSB = max_amps.get() / 0x8000;89const int16_t shunt_cal = 819.2 * 1e6 * current_LSB * rShunt.get();90int16_t shunt_cal2 = 0;9192if (!write_word(REG_SHUNT_CAL, shunt_cal) ||93!read_word(REG_SHUNT_CAL, shunt_cal2) ||94shunt_cal != shunt_cal2) {95return;96}9798configured = true;99}100101/// read the battery_voltage and current, should be called at 10hz102void AP_BattMonitor_INA239::read(void)103{104WITH_SEMAPHORE(accumulate.sem);105_state.healthy = accumulate.count > 0;106if (!_state.healthy) {107return;108}109110_state.voltage = accumulate.volt_sum / accumulate.count;111_state.current_amps = accumulate.current_sum / accumulate.count;112accumulate.volt_sum = 0;113accumulate.current_sum = 0;114accumulate.count = 0;115116const uint32_t tnow = AP_HAL::micros();117const uint32_t dt_us = tnow - _state.last_time_micros;118119// update total current drawn since startup120update_consumed(_state, dt_us);121122_state.last_time_micros = tnow;123}124125/*126read word from register127returns true if read was successful, false if failed128*/129bool AP_BattMonitor_INA239::read_word(const uint8_t reg, int16_t& data) const130{131// read the appropriate register from the device132if (!dev->read_registers(reg<<2, (uint8_t *)&data, sizeof(data))) {133return false;134}135136// convert byte order137data = int16_t(be16toh(uint16_t(data)));138139return true;140}141142/*143write word to a register, byte swapped144returns true if write was successful, false if failed145*/146bool AP_BattMonitor_INA239::write_word(const uint8_t reg, const uint16_t data) const147{148const uint8_t b[3] { uint8_t(reg<<2), uint8_t(data >> 8), uint8_t(data&0xff) };149return dev->transfer(b, sizeof(b), nullptr, 0);150}151152void AP_BattMonitor_INA239::timer(void)153{154// allow for power-on after boot155if (!configured) {156uint32_t now = AP_HAL::millis();157if (now - last_configure_ms > 200) {158// try contacting the device at 5Hz159last_configure_ms = now;160configure();161}162if (!configured) {163// waiting for the device to respond164return;165}166}167168int16_t bus_voltage, current;169170if (!read_word(REG_BUS_VOLTAGE, bus_voltage) ||171!read_word(REG_CURRENT, current)) {172failed_reads++;173if (failed_reads > 10) {174// device has disconnected, we need to reconfigure it175configured = false;176}177return;178}179failed_reads = 0;180181WITH_SEMAPHORE(accumulate.sem);182accumulate.volt_sum += bus_voltage * voltage_LSB;183accumulate.current_sum += current * current_LSB;184accumulate.count++;185}186187#endif // AP_BATTERY_INA239_ENABLED188189190