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_INA2xx.cpp
Views: 1798
#include "AP_BattMonitor_config.h"12#if AP_BATTERY_INA2XX_ENABLED34/*5supports INA226, INA228 and INA238 I2C battery monitors6*/78#include <AP_HAL/utility/sparse-endian.h>910#include "AP_BattMonitor_INA2xx.h"1112extern const AP_HAL::HAL& hal;131415// INA226 specific registers16#define REG_226_CONFIG 0x0017#define REG_226_CONFIG_DEFAULT 0x412718#define REG_226_CONFIG_RESET 0x800019#define REG_226_BUS_VOLTAGE 0x0220#define REG_226_CURRENT 0x0421#define REG_226_CALIBRATION 0x0522#define REG_226_MANUFACT_ID 0xfe2324// INA228 specific registers25#define REG_228_CONFIG 0x0026#define REG_228_CONFIG_RESET 0x800027#define REG_228_ADC_CONFIG 0x0128#define REG_228_SHUNT_CAL 0x0229#define REG_228_VBUS 0x0530#define REG_228_CURRENT 0x0731#define REG_228_MANUFACT_ID 0x3e32#define REG_228_DEVICE_ID 0x3f33#define REG_228_DIETEMP 0x0634#define INA_228_TEMP_C_LSB 7.8125e-33536// INA237/INA238 specific registers37#define REG_238_CONFIG 0x0038#define REG_238_CONFIG_RESET 0x800039#define REG_238_ADC_CONFIG 0x0140#define REG_238_SHUNT_CAL 0x0241#define REG_238_VBUS 0x0542#define REG_238_CURRENT 0x0743#define REG_238_MANUFACT_ID 0x3e44#define REG_238_DEVICE_ID 0x3f45#define REG_238_DIETEMP 0x0646#define INA_238_TEMP_C_LSB 7.8125e-3 // need to mask bottom 4 bits4748// INA231 specific registers49#define REG_231_CONFIG 0x0050#define REG_231_SHUNT_VOLTAGE 0x0151#define REG_231_BUS_VOLTAGE 0x0252#define REG_231_POWER 0x0353#define REG_231_CURRENT 0x0454#define REG_231_CALIBRATION 0x0555#define REG_231_MASK 0x0656#define REG_231_ALERT 0x07575859#ifndef DEFAULT_BATTMON_INA2XX_MAX_AMPS60#define DEFAULT_BATTMON_INA2XX_MAX_AMPS 90.061#endif6263#ifndef DEFAULT_BATTMON_INA2XX_SHUNT64#define DEFAULT_BATTMON_INA2XX_SHUNT 0.000565#endif6667#ifndef HAL_BATTMON_INA2XX_BUS68#define HAL_BATTMON_INA2XX_BUS 069#endif70#ifndef HAL_BATTMON_INA2XX_ADDR71#define HAL_BATTMON_INA2XX_ADDR 072#endif7374// list of addresses to probe if I2C_ADDR is zero75const uint8_t AP_BattMonitor_INA2XX::i2c_probe_addresses[] { 0x41, 0x44, 0x45 };7677const AP_Param::GroupInfo AP_BattMonitor_INA2XX::var_info[] = {7879// @Param: I2C_BUS80// @DisplayName: Battery monitor I2C bus number81// @Description: Battery monitor I2C bus number82// @Range: 0 383// @User: Advanced84// @RebootRequired: True85AP_GROUPINFO("I2C_BUS", 25, AP_BattMonitor_INA2XX, i2c_bus, HAL_BATTMON_INA2XX_BUS),8687// @Param: I2C_ADDR88// @DisplayName: Battery monitor I2C address89// @Description: Battery monitor I2C address. If this is zero then probe list of supported addresses90// @Range: 0 12791// @User: Advanced92// @RebootRequired: True93AP_GROUPINFO("I2C_ADDR", 26, AP_BattMonitor_INA2XX, i2c_address, HAL_BATTMON_INA2XX_ADDR),9495// @Param: MAX_AMPS96// @DisplayName: Battery monitor max current97// @Description: This controls the maximum current the INS2XX sensor will work with.98// @Range: 1 40099// @Units: A100// @User: Advanced101AP_GROUPINFO("MAX_AMPS", 27, AP_BattMonitor_INA2XX, max_amps, DEFAULT_BATTMON_INA2XX_MAX_AMPS),102103// @Param: SHUNT104// @DisplayName: Battery monitor shunt resistor105// @Description: This sets the shunt resistor used in the device106// @Range: 0.0001 0.01107// @Units: Ohm108// @User: Advanced109AP_GROUPINFO("SHUNT", 28, AP_BattMonitor_INA2XX, rShunt, DEFAULT_BATTMON_INA2XX_SHUNT),110111// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS112113AP_GROUPEND114};115116AP_BattMonitor_INA2XX::AP_BattMonitor_INA2XX(AP_BattMonitor &mon,117AP_BattMonitor::BattMonitor_State &mon_state,118AP_BattMonitor_Params ¶ms)119: AP_BattMonitor_Backend(mon, mon_state, params)120{121AP_Param::setup_object_defaults(this, var_info);122_state.var_info = var_info;123}124125void AP_BattMonitor_INA2XX::init(void)126{127dev = hal.i2c_mgr->get_device(i2c_bus, i2c_address, 100000, false, 20);128if (!dev) {129return;130}131// register now and configure in the timer callbacks132dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_INA2XX::timer, void));133}134135bool AP_BattMonitor_INA2XX::configure(DevType dtype)136{137switch (dtype) {138case DevType::UNKNOWN:139return false;140141case DevType::INA226: {142// configure for MAX_AMPS143const uint16_t conf = (0x2<<9) | (0x5<<6) | (0x5<<3) | 0x7; // 2ms conv time, 16x sampling144current_LSB = max_amps / 32768.0;145voltage_LSB = 0.00125; // 1.25mV/bit146const uint16_t cal = uint16_t(0.00512 / (current_LSB * rShunt));147if (write_word(REG_226_CONFIG, REG_226_CONFIG_RESET) && // reset148write_word(REG_226_CONFIG, conf) &&149write_word(REG_226_CALIBRATION, cal)) {150dev_type = dtype;151return true;152}153break;154}155156case DevType::INA228: {157// configure for MAX_AMPS158voltage_LSB = 195.3125e-6; // 195.3125 uV/LSB159current_LSB = max_amps / (1U<<19);160const uint16_t shunt_cal = uint16_t(13107.2e6 * current_LSB * rShunt) & 0x7FFF;161if (write_word(REG_228_CONFIG, REG_228_CONFIG_RESET) && // reset162write_word(REG_228_CONFIG, 0) &&163write_word(REG_228_SHUNT_CAL, shunt_cal)) {164dev_type = dtype;165return true;166}167break;168}169170case DevType::INA238: {171// configure for MAX_AMPS172voltage_LSB = 3.125e-3; // 3.125mV/LSB173current_LSB = max_amps / (1U<<15);174const uint16_t shunt_cal = uint16_t(819.2e6 * current_LSB * rShunt) & 0x7FFF;175if (write_word(REG_238_CONFIG, REG_238_CONFIG_RESET) && // reset176write_word(REG_238_CONFIG, 0) &&177write_word(REG_238_SHUNT_CAL, shunt_cal)) {178dev_type = dtype;179return true;180}181break;182}183184case DevType::INA231: {185// no configuration needed186voltage_LSB = 1.25e-3;187current_LSB = max_amps / (1U<<15);188const uint16_t cal = 0.00512 / (current_LSB * rShunt);189if (write_word(REG_231_CALIBRATION, cal)) {190return true;191}192}193194}195return false;196}197198/// read the battery_voltage and current, should be called at 10hz199void AP_BattMonitor_INA2XX::read(void)200{201WITH_SEMAPHORE(accumulate.sem);202_state.healthy = accumulate.count > 0;203if (!_state.healthy) {204return;205}206207_state.voltage = accumulate.volt_sum / accumulate.count;208_state.current_amps = accumulate.current_sum / accumulate.count;209accumulate.volt_sum = 0;210accumulate.current_sum = 0;211accumulate.count = 0;212213const uint32_t tnow = AP_HAL::micros();214const uint32_t dt_us = tnow - _state.last_time_micros;215216// update total current drawn since startup217update_consumed(_state, dt_us);218219_state.last_time_micros = tnow;220}221222/*223read 16 bit word from register224returns true if read was successful, false if failed225*/226bool AP_BattMonitor_INA2XX::read_word16(const uint8_t reg, int16_t& data) const227{228// read the appropriate register from the device229if (!dev->read_registers(reg, (uint8_t *)&data, sizeof(data))) {230return false;231}232233// convert byte order234data = int16_t(be16toh(uint16_t(data)));235236return true;237}238239/*240read 24 bit signed value from register241returns true if read was successful, false if failed242*/243bool AP_BattMonitor_INA2XX::read_word24(const uint8_t reg, int32_t& data) const244{245// read the appropriate register from the device246uint8_t d[3];247if (!dev->read_registers(reg, d, sizeof(d))) {248return false;249}250// 24 bit 2s complement data. Shift into upper 24 bits of int32_t then divide by 256251// to cope with negative numbers properly252data = d[0]<<24 | d[1]<<16 | d[2] << 8;253data = data / 256;254255return true;256}257258/*259write word to a register, byte swapped260returns true if write was successful, false if failed261*/262bool AP_BattMonitor_INA2XX::write_word(const uint8_t reg, const uint16_t data) const263{264const uint8_t b[3] { reg, uint8_t(data >> 8), uint8_t(data&0xff) };265return dev->transfer(b, sizeof(b), nullptr, 0);266}267268/*269detect device type. This may happen well after power on if battery is270not plugged in yet271*/272bool AP_BattMonitor_INA2XX::detect_device(void)273{274uint32_t now = AP_HAL::millis();275if (now - last_detect_ms < 200) {276// don't flood the bus277return false;278}279last_detect_ms = now;280int16_t id;281282WITH_SEMAPHORE(dev->get_semaphore());283284if (i2c_address.get() == 0) {285dev->set_address(i2c_probe_addresses[i2c_probe_next]);286i2c_probe_next = (i2c_probe_next+1) % sizeof(i2c_probe_addresses);287}288289if (read_word16(REG_228_MANUFACT_ID, id) && id == 0x5449 &&290read_word16(REG_228_DEVICE_ID, id) && (id&0xFFF0) == 0x2280) {291has_temp = true;292return configure(DevType::INA228);293}294if (read_word16(REG_238_MANUFACT_ID, id) && id == 0x5449 &&295read_word16(REG_238_DEVICE_ID, id) && (id&0xFFF0) == 0x2380) {296has_temp = true;297return configure(DevType::INA238);298}299if (read_word16(REG_226_MANUFACT_ID, id) && id == 0x5449 &&300write_word(REG_226_CONFIG, REG_226_CONFIG_RESET) &&301write_word(REG_226_CONFIG, REG_226_CONFIG_DEFAULT) &&302read_word16(REG_226_CONFIG, id) &&303id == REG_226_CONFIG_DEFAULT) {304return configure(DevType::INA226);305}306if (read_word16(REG_231_CONFIG, id) && id == 0x4127) {307// no manufacturer ID for 231308return configure(DevType::INA231);309}310311return false;312}313314315void AP_BattMonitor_INA2XX::timer(void)316{317if (dev_type == DevType::UNKNOWN) {318if (!detect_device()) {319return;320}321}322323float voltage = 0, current = 0;324325switch (dev_type) {326case DevType::UNKNOWN:327return;328329case DevType::INA226: {330int16_t bus_voltage16, current16;331if (!read_word16(REG_226_BUS_VOLTAGE, bus_voltage16) ||332!read_word16(REG_226_CURRENT, current16)) {333failed_reads++;334if (failed_reads > 10) {335// device has disconnected, we need to reconfigure it336dev_type = DevType::UNKNOWN;337}338return;339}340voltage = bus_voltage16 * voltage_LSB;341current = current16 * current_LSB;342break;343}344345case DevType::INA228: {346int32_t bus_voltage24, current24;347int16_t temp16;348if (!read_word24(REG_228_VBUS, bus_voltage24) ||349!read_word24(REG_228_CURRENT, current24) ||350!read_word16(REG_228_DIETEMP, temp16)) {351failed_reads++;352if (failed_reads > 10) {353// device has disconnected, we need to reconfigure it354dev_type = DevType::UNKNOWN;355}356return;357}358voltage = (bus_voltage24>>4) * voltage_LSB;359current = (current24>>4) * current_LSB;360temperature = temp16 * INA_228_TEMP_C_LSB;361break;362}363364case DevType::INA238: {365int16_t bus_voltage16, current16, temp16;366if (!read_word16(REG_238_VBUS, bus_voltage16) ||367!read_word16(REG_238_CURRENT, current16) ||368!read_word16(REG_238_DIETEMP, temp16)) {369failed_reads++;370if (failed_reads > 10) {371// device has disconnected, we need to reconfigure it372dev_type = DevType::UNKNOWN;373}374return;375}376voltage = bus_voltage16 * voltage_LSB;377current = current16 * current_LSB;378temperature = (temp16&0xFFF0) * INA_238_TEMP_C_LSB;379break;380}381382case DevType::INA231: {383int16_t bus_voltage16, current16;384if (!read_word16(REG_231_SHUNT_VOLTAGE, bus_voltage16) ||385!read_word16(REG_231_CURRENT, current16)) {386failed_reads++;387if (failed_reads > 10) {388// device has disconnected, we need to reconfigure it389dev_type = DevType::UNKNOWN;390}391return;392}393voltage = bus_voltage16 * voltage_LSB;394current = current16 * current_LSB;395break;396}397}398399failed_reads = 0;400401WITH_SEMAPHORE(accumulate.sem);402accumulate.volt_sum += voltage;403accumulate.current_sum += current;404accumulate.count++;405}406407/*408get last temperature409*/410bool AP_BattMonitor_INA2XX::get_temperature(float &temp) const411{412temp = temperature;413return has_temp;414}415416#endif // AP_BATTERY_INA2XX_ENABLED417418419