Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp
9451 views
#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 0x075758// INA260 specific registers59#define REG_260_CONFIG 0x0060#define REG_260_CURRENT 0x0161#define REG_260_BUS_VOLTAGE 0x0262#define REG_260_POWER 0x0363#define REG_260_MASK 0x0664#define REG_260_ALERT 0x0765#define REG_260_MANUFACT_ID 0xfe66#define REG_260_DIE_ID 0xff6768#ifndef DEFAULT_BATTMON_INA2XX_MAX_AMPS69#define DEFAULT_BATTMON_INA2XX_MAX_AMPS 90.070#endif7172#ifndef DEFAULT_BATTMON_INA2XX_SHUNT73#define DEFAULT_BATTMON_INA2XX_SHUNT 0.000574#endif7576#ifndef HAL_BATTMON_INA2XX_BUS77#define HAL_BATTMON_INA2XX_BUS 078#endif79#ifndef HAL_BATTMON_INA2XX_ADDR80#define HAL_BATTMON_INA2XX_ADDR 081#endif8283// list of addresses to probe if I2C_ADDR is zero84const uint8_t AP_BattMonitor_INA2XX::i2c_probe_addresses[] { 0x41, 0x44, 0x45 };8586const AP_Param::GroupInfo AP_BattMonitor_INA2XX::var_info[] = {8788// @Param: I2C_BUS89// @DisplayName: Battery monitor I2C bus number90// @Description: Battery monitor I2C bus number91// @Range: 0 392// @User: Advanced93// @RebootRequired: True94AP_GROUPINFO("I2C_BUS", 25, AP_BattMonitor_INA2XX, i2c_bus, HAL_BATTMON_INA2XX_BUS),9596// @Param: I2C_ADDR97// @DisplayName: Battery monitor I2C address98// @Description: Battery monitor I2C address. If this is zero then probe list of supported addresses99// @Range: 0 127100// @User: Advanced101// @RebootRequired: True102AP_GROUPINFO("I2C_ADDR", 26, AP_BattMonitor_INA2XX, i2c_address, HAL_BATTMON_INA2XX_ADDR),103104// @Param: MAX_AMPS105// @DisplayName: Battery monitor max current106// @Description: This controls the maximum current the INS2XX sensor will work with.107// @Range: 1 400108// @Units: A109// @User: Advanced110AP_GROUPINFO("MAX_AMPS", 27, AP_BattMonitor_INA2XX, max_amps, DEFAULT_BATTMON_INA2XX_MAX_AMPS),111112// @Param: SHUNT113// @DisplayName: Battery monitor shunt resistor114// @Description: This sets the shunt resistor used in the device115// @Range: 0.0001 0.01116// @Units: Ohm117// @User: Advanced118AP_GROUPINFO("SHUNT", 28, AP_BattMonitor_INA2XX, rShunt, DEFAULT_BATTMON_INA2XX_SHUNT),119120// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS121122AP_GROUPEND123};124125AP_BattMonitor_INA2XX::AP_BattMonitor_INA2XX(AP_BattMonitor &mon,126AP_BattMonitor::BattMonitor_State &mon_state,127AP_BattMonitor_Params ¶ms)128: AP_BattMonitor_Backend(mon, mon_state, params)129{130AP_Param::setup_object_defaults(this, var_info);131_state.var_info = var_info;132}133134void AP_BattMonitor_INA2XX::init(void)135{136dev = hal.i2c_mgr->get_device_ptr(i2c_bus, i2c_address, 100000, false, 20);137if (!dev) {138return;139}140// register now and configure in the timer callbacks141dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_INA2XX::timer, void));142}143144bool AP_BattMonitor_INA2XX::configure(DevType dtype)145{146switch (dtype) {147case DevType::UNKNOWN:148return false;149150case DevType::INA226: {151// configure for MAX_AMPS152const uint16_t conf = (0x2<<9) | (0x5<<6) | (0x5<<3) | 0x7; // 2ms conv time, 16x sampling153current_LSB = max_amps / 32768.0;154voltage_LSB = 0.00125; // 1.25mV/bit155const uint16_t cal = uint16_t(0.00512 / (current_LSB * rShunt));156if (write_word(REG_226_CONFIG, REG_226_CONFIG_RESET) && // reset157write_word(REG_226_CONFIG, conf) &&158write_word(REG_226_CALIBRATION, cal)) {159dev_type = dtype;160return true;161}162break;163}164165case DevType::INA228: {166// configure for MAX_AMPS167voltage_LSB = 195.3125e-6; // 195.3125 uV/LSB168current_LSB = max_amps / (1U<<19);169const uint16_t shunt_cal = uint16_t(13107.2e6 * current_LSB * rShunt) & 0x7FFF;170if (write_word(REG_228_CONFIG, REG_228_CONFIG_RESET) && // reset171write_word(REG_228_CONFIG, 0) &&172write_word(REG_228_SHUNT_CAL, shunt_cal)) {173dev_type = dtype;174return true;175}176break;177}178179case DevType::INA238: {180// configure for MAX_AMPS181voltage_LSB = 3.125e-3; // 3.125mV/LSB182current_LSB = max_amps / (1U<<15);183const uint16_t shunt_cal = uint16_t(819.2e6 * current_LSB * rShunt) & 0x7FFF;184if (write_word(REG_238_CONFIG, REG_238_CONFIG_RESET) && // reset185write_word(REG_238_CONFIG, 0) &&186write_word(REG_238_SHUNT_CAL, shunt_cal)) {187dev_type = dtype;188return true;189}190break;191}192193case DevType::INA231: {194// no configuration needed195voltage_LSB = 1.25e-3;196current_LSB = max_amps / (1U<<15);197const uint16_t cal = 0.00512 / (current_LSB * rShunt);198if (write_word(REG_231_CALIBRATION, cal)) {199dev_type = dtype;200return true;201}202break;203}204205case DevType::INA260: {206// Reset device207if (!write_word(REG_260_CONFIG, 0x8000)) {208return false;209}210211// Set longest conversion time and no averaging212// This is 8.244ms for both voltage and current213// So both should have new readings after 16.488ms214// This is a new reading at 60Hz, we read at 40Hz215// Continuous voltage and current measurement216if (!write_word(REG_260_CONFIG, 0x01ff)) {217return false;218}219220// Configuration OK221// Set (not save) unused shunt and max amps parameters to reflect specs222// 2 milliohms internal shunt223rShunt.set_and_default(0.002);224225// Rated for 30 amps for 5 seconds226max_amps.set_and_default(30.0);227228// Set detected type229dev_type = dtype;230return true;231}232233}234return false;235}236237/// read the battery_voltage and current, should be called at 10hz238void AP_BattMonitor_INA2XX::read(void)239{240WITH_SEMAPHORE(accumulate.sem);241_state.healthy = accumulate.count > 0;242if (!_state.healthy) {243return;244}245246_state.voltage = accumulate.volt_sum / accumulate.count;247_state.current_amps = accumulate.current_sum / accumulate.count;248accumulate.volt_sum = 0;249accumulate.current_sum = 0;250accumulate.count = 0;251252const uint32_t tnow = AP_HAL::micros();253const uint32_t dt_us = tnow - _state.last_time_micros;254255// update total current drawn since startup256update_consumed(_state, dt_us);257258_state.last_time_micros = tnow;259}260261/*262read 16 bit word from register263returns true if read was successful, false if failed264*/265bool AP_BattMonitor_INA2XX::read_word16(const uint8_t reg, int16_t& data) const266{267// read the appropriate register from the device268if (!dev->read_registers(reg, (uint8_t *)&data, sizeof(data))) {269return false;270}271272// convert byte order273data = int16_t(be16toh(uint16_t(data)));274275return true;276}277278/*279read 24 bit signed value from register280returns true if read was successful, false if failed281*/282bool AP_BattMonitor_INA2XX::read_word24(const uint8_t reg, int32_t& data) const283{284// read the appropriate register from the device285uint8_t d[3];286if (!dev->read_registers(reg, d, sizeof(d))) {287return false;288}289// 24 bit 2s complement data. Shift into upper 24 bits of int32_t then divide by 256290// to cope with negative numbers properly291data = d[0]<<24 | d[1]<<16 | d[2] << 8;292data = data / 256;293294return true;295}296297/*298write word to a register, byte swapped299returns true if write was successful, false if failed300*/301bool AP_BattMonitor_INA2XX::write_word(const uint8_t reg, const uint16_t data) const302{303const uint8_t b[3] { reg, uint8_t(data >> 8), uint8_t(data&0xff) };304return dev->transfer(b, sizeof(b), nullptr, 0);305}306307/*308detect device type. This may happen well after power on if battery is309not plugged in yet310*/311bool AP_BattMonitor_INA2XX::detect_device(void)312{313uint32_t now = AP_HAL::millis();314if (now - last_detect_ms < 200) {315// don't flood the bus316return false;317}318last_detect_ms = now;319int16_t id;320321WITH_SEMAPHORE(dev->get_semaphore());322323if (i2c_address.get() == 0) {324// Cycle through probe address list325dev->set_address(i2c_probe_addresses[i2c_probe_next]);326i2c_probe_next = (i2c_probe_next+1) % sizeof(i2c_probe_addresses);327328} else {329// User provided address330dev->set_address(i2c_address.get());331}332333if (read_word16(REG_228_MANUFACT_ID, id) && id == 0x5449 &&334read_word16(REG_228_DEVICE_ID, id) && (id&0xFFF0) == 0x2280) {335has_temp = true;336return configure(DevType::INA228);337}338if (read_word16(REG_238_MANUFACT_ID, id) && id == 0x5449 &&339read_word16(REG_238_DEVICE_ID, id) && (id&0xFFF0) == 0x2380) {340has_temp = true;341return configure(DevType::INA238);342}343if (read_word16(REG_260_MANUFACT_ID, id) && id == 0x5449 &&344read_word16(REG_260_DIE_ID, id) && (id&0xFFF0) == 0x2270) {345return configure(DevType::INA260);346}347if (read_word16(REG_226_MANUFACT_ID, id) && id == 0x5449 &&348write_word(REG_226_CONFIG, REG_226_CONFIG_RESET) &&349write_word(REG_226_CONFIG, REG_226_CONFIG_DEFAULT) &&350read_word16(REG_226_CONFIG, id) &&351id == REG_226_CONFIG_DEFAULT) {352return configure(DevType::INA226);353}354if (read_word16(REG_231_CONFIG, id) && id == 0x4127) {355// no manufacturer ID for 231356return configure(DevType::INA231);357}358359return false;360}361362363void AP_BattMonitor_INA2XX::timer(void)364{365if (failed_reads > 10) {366// device has disconnected, we need to reconfigure it367dev_type = DevType::UNKNOWN;368}369370if (dev_type == DevType::UNKNOWN) {371if (!detect_device()) {372return;373}374375// Reset failed reads after successful detection376failed_reads = 0;377}378379float voltage = 0, current = 0;380381switch (dev_type) {382case DevType::UNKNOWN:383return;384385case DevType::INA226: {386int16_t bus_voltage16, current16;387if (!read_word16(REG_226_BUS_VOLTAGE, bus_voltage16) ||388!read_word16(REG_226_CURRENT, current16)) {389failed_reads++;390return;391}392voltage = bus_voltage16 * voltage_LSB;393current = current16 * current_LSB;394break;395}396397case DevType::INA228: {398int32_t bus_voltage24, current24;399int16_t temp16;400if (!read_word24(REG_228_VBUS, bus_voltage24) ||401!read_word24(REG_228_CURRENT, current24) ||402!read_word16(REG_228_DIETEMP, temp16)) {403failed_reads++;404return;405}406voltage = (bus_voltage24>>4) * voltage_LSB;407current = (current24>>4) * current_LSB;408temperature = temp16 * INA_228_TEMP_C_LSB;409break;410}411412case DevType::INA238: {413int16_t bus_voltage16, current16, temp16;414if (!read_word16(REG_238_VBUS, bus_voltage16) ||415!read_word16(REG_238_CURRENT, current16) ||416!read_word16(REG_238_DIETEMP, temp16)) {417failed_reads++;418return;419}420voltage = bus_voltage16 * voltage_LSB;421current = current16 * current_LSB;422temperature = (temp16&0xFFF0) * INA_238_TEMP_C_LSB;423break;424}425426case DevType::INA231: {427int16_t bus_voltage16, current16;428if (!read_word16(REG_231_SHUNT_VOLTAGE, bus_voltage16) ||429!read_word16(REG_231_CURRENT, current16)) {430failed_reads++;431return;432}433voltage = bus_voltage16 * voltage_LSB;434current = current16 * current_LSB;435break;436}437438case DevType::INA260: {439int16_t current16, bus_voltage16;440if (!read_word16(REG_260_BUS_VOLTAGE, bus_voltage16) ||441!read_word16(REG_260_CURRENT, current16)) {442failed_reads++;443return;444}445voltage = bus_voltage16 * 0.00125;446current = current16 * 0.00125;447break;448}449}450451failed_reads = 0;452453WITH_SEMAPHORE(accumulate.sem);454accumulate.volt_sum += voltage;455accumulate.current_sum += current;456accumulate.count++;457}458459/*460get last temperature461*/462bool AP_BattMonitor_INA2XX::get_temperature(float &temp) const463{464temp = temperature;465return has_temp;466}467468#endif // AP_BATTERY_INA2XX_ENABLED469470471