AP_BattMonitor: support other INA2xx battery monitors

added parameters for I2C bus and address. Tested on INA231 and INA226

This allows any 2M flash board to use an INA2xx battery monitor
This commit is contained in:
Andrew Tridgell 2021-10-25 11:58:19 +11:00
parent 34ba3e4782
commit 75dfa6bae4
5 changed files with 75 additions and 28 deletions

View File

@ -14,7 +14,7 @@
#include "AP_BattMonitor_FuelLevel_PWM.h" #include "AP_BattMonitor_FuelLevel_PWM.h"
#include "AP_BattMonitor_Generator.h" #include "AP_BattMonitor_Generator.h"
#include "AP_BattMonitor_MPPT_PacketDigital.h" #include "AP_BattMonitor_MPPT_PacketDigital.h"
#include "AP_BattMonitor_INA231.h" #include "AP_BattMonitor_INA2xx.h"
#include "AP_BattMonitor_LTC2946.h" #include "AP_BattMonitor_LTC2946.h"
#include "AP_BattMonitor_Torqeedo.h" #include "AP_BattMonitor_Torqeedo.h"
@ -276,9 +276,9 @@ AP_BattMonitor::init()
drivers[instance] = new AP_BattMonitor_MPPT_PacketDigital(*this, state[instance], _params[instance]); drivers[instance] = new AP_BattMonitor_MPPT_PacketDigital(*this, state[instance], _params[instance]);
break; break;
#endif // HAL_MPPT_PACKETDIGITAL_CAN_ENABLE #endif // HAL_MPPT_PACKETDIGITAL_CAN_ENABLE
#if HAL_BATTMON_INA231_ENABLED #if HAL_BATTMON_INA2XX_ENABLED
case Type::INA231: case Type::INA2XX:
drivers[instance] = new AP_BattMonitor_INA231(*this, state[instance], _params[instance]); drivers[instance] = new AP_BattMonitor_INA2XX(*this, state[instance], _params[instance]);
break; break;
#endif #endif
#if HAL_BATTMON_LTC2946_ENABLED #if HAL_BATTMON_LTC2946_ENABLED

View File

@ -46,7 +46,7 @@ class AP_BattMonitor_SMBus_Rotoye;
class AP_BattMonitor_UAVCAN; class AP_BattMonitor_UAVCAN;
class AP_BattMonitor_Generator; class AP_BattMonitor_Generator;
class AP_BattMonitor_MPPT_PacketDigital; class AP_BattMonitor_MPPT_PacketDigital;
class AP_BattMonitor_INA231; class AP_BattMonitor_INA2XX;
class AP_BattMonitor_LTC2946; class AP_BattMonitor_LTC2946;
class AP_BattMonitor_Torqeedo; class AP_BattMonitor_Torqeedo;
@ -65,7 +65,7 @@ class AP_BattMonitor
friend class AP_BattMonitor_FuelLevel_PWM; friend class AP_BattMonitor_FuelLevel_PWM;
friend class AP_BattMonitor_Generator; friend class AP_BattMonitor_Generator;
friend class AP_BattMonitor_MPPT_PacketDigital; friend class AP_BattMonitor_MPPT_PacketDigital;
friend class AP_BattMonitor_INA231; friend class AP_BattMonitor_INA2XX;
friend class AP_BattMonitor_LTC2946; friend class AP_BattMonitor_LTC2946;
friend class AP_BattMonitor_Torqeedo; friend class AP_BattMonitor_Torqeedo;
@ -100,7 +100,7 @@ public:
GENERATOR_FUEL = 18, GENERATOR_FUEL = 18,
Rotoye = 19, Rotoye = 19,
MPPT_PacketDigital = 20, MPPT_PacketDigital = 20,
INA231 = 21, INA2XX = 21,
LTC2946 = 22, LTC2946 = 22,
Torqeedo = 23, Torqeedo = 23,
}; };

View File

@ -1,8 +1,8 @@
#include "AP_BattMonitor_INA231.h" #include "AP_BattMonitor_INA2xx.h"
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
#include <AP_HAL/utility/sparse-endian.h> #include <AP_HAL/utility/sparse-endian.h>
#if HAL_BATTMON_INA231_ENABLED #if HAL_BATTMON_INA2XX_ENABLED
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -18,9 +18,46 @@ extern const AP_HAL::HAL& hal;
// this should become a parameter in future // this should become a parameter in future
#define MAX_AMPS 90.0 #define MAX_AMPS 90.0
void AP_BattMonitor_INA231::init(void) #ifndef HAL_BATTMON_INA2XX_BUS
#define HAL_BATTMON_INA2XX_BUS 0
#endif
#ifndef HAL_BATTMON_INA2XX_ADDR
#define HAL_BATTMON_INA2XX_ADDR 0
#endif
const AP_Param::GroupInfo AP_BattMonitor_INA2XX::var_info[] = {
// @Param: I2C_BUS
// @DisplayName: Battery monitor I2C bus number
// @Description: Battery monitor I2C bus number
// @Range: 0 3
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("I2C_BUS", 25, AP_BattMonitor_INA2XX, i2c_bus, HAL_BATTMON_INA2XX_BUS),
// @Param: I2C_ADDR
// @DisplayName: Battery monitor I2C address
// @Description: Battery monitor I2C address
// @Range: 0 127
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("I2C_ADDR", 26, AP_BattMonitor_INA2XX, i2c_address, HAL_BATTMON_INA2XX_ADDR),
AP_GROUPEND
};
AP_BattMonitor_INA2XX::AP_BattMonitor_INA2XX(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params)
: AP_BattMonitor_Backend(mon, mon_state, params)
{ {
dev = hal.i2c_mgr->get_device(HAL_BATTMON_INA231_BUS, HAL_BATTMON_INA231_ADDR, 100000, false, 20); AP_Param::setup_object_defaults(this, var_info);
_state.var_info = var_info;
}
void AP_BattMonitor_INA2XX::init(void)
{
dev = hal.i2c_mgr->get_device(i2c_bus, i2c_address, 100000, false, 20);
if (!dev) { if (!dev) {
return; return;
} }
@ -31,7 +68,7 @@ void AP_BattMonitor_INA231::init(void)
!write_word(REG_CONFIG, REG_CONFIG_DEFAULT) || !write_word(REG_CONFIG, REG_CONFIG_DEFAULT) ||
!read_word(REG_CONFIG, config) || !read_word(REG_CONFIG, config) ||
config != REG_CONFIG_DEFAULT) { config != REG_CONFIG_DEFAULT) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "INA231: Failed to find device 0x%04x", unsigned(config)); GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "INA2XX: Failed to find device 0x%04x", unsigned(config));
return; return;
} }
@ -44,20 +81,20 @@ void AP_BattMonitor_INA231::init(void)
if (!write_word(REG_CONFIG, REG_CONFIG_RESET) || // reset if (!write_word(REG_CONFIG, REG_CONFIG_RESET) || // reset
!write_word(REG_CONFIG, conf) || !write_word(REG_CONFIG, conf) ||
!write_word(REG_CALIBRATION, cal)) { !write_word(REG_CALIBRATION, cal)) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "INA231: Failed to configure device"); GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "INA2XX: Failed to configure device");
return; return;
} }
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "INA231: found monitor on bus %u", HAL_BATTMON_INA231_BUS); GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "INA2XX: found monitor on I2C:%u:%02x", unsigned(i2c_bus), unsigned(i2c_address));
if (dev) { if (dev) {
dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_INA231::timer, void)); dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_INA2XX::timer, void));
} }
} }
/// read the battery_voltage and current, should be called at 10hz /// read the battery_voltage and current, should be called at 10hz
void AP_BattMonitor_INA231::read(void) void AP_BattMonitor_INA2XX::read(void)
{ {
WITH_SEMAPHORE(accumulate.sem); WITH_SEMAPHORE(accumulate.sem);
_state.healthy = accumulate.count > 0; _state.healthy = accumulate.count > 0;
@ -88,7 +125,7 @@ void AP_BattMonitor_INA231::read(void)
read word from register read word from register
returns true if read was successful, false if failed returns true if read was successful, false if failed
*/ */
bool AP_BattMonitor_INA231::read_word(const uint8_t reg, int16_t& data) const bool AP_BattMonitor_INA2XX::read_word(const uint8_t reg, int16_t& data) const
{ {
// read the appropriate register from the device // read the appropriate register from the device
if (!dev->read_registers(reg, (uint8_t *)&data, sizeof(data))) { if (!dev->read_registers(reg, (uint8_t *)&data, sizeof(data))) {
@ -105,13 +142,13 @@ bool AP_BattMonitor_INA231::read_word(const uint8_t reg, int16_t& data) const
write word to a register, byte swapped write word to a register, byte swapped
returns true if write was successful, false if failed returns true if write was successful, false if failed
*/ */
bool AP_BattMonitor_INA231::write_word(const uint8_t reg, const uint16_t data) const bool AP_BattMonitor_INA2XX::write_word(const uint8_t reg, const uint16_t data) const
{ {
const uint8_t b[3] { reg, uint8_t(data >> 8), uint8_t(data&0xff) }; const uint8_t b[3] { reg, uint8_t(data >> 8), uint8_t(data&0xff) };
return dev->transfer(b, sizeof(b), nullptr, 0); return dev->transfer(b, sizeof(b), nullptr, 0);
} }
void AP_BattMonitor_INA231::timer(void) void AP_BattMonitor_INA2XX::timer(void)
{ {
int16_t bus_voltage, current; int16_t bus_voltage, current;
if (!read_word(REG_BUS_VOLTAGE, bus_voltage) || if (!read_word(REG_BUS_VOLTAGE, bus_voltage) ||
@ -124,4 +161,4 @@ void AP_BattMonitor_INA231::timer(void)
accumulate.count++; accumulate.count++;
} }
#endif // HAL_BATTMON_INA231_ENABLED #endif // HAL_BATTMON_INA2XX_ENABLED

View File

@ -3,17 +3,22 @@
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_HAL/I2CDevice.h> #include <AP_HAL/I2CDevice.h>
#include "AP_BattMonitor_Backend.h" #include "AP_BattMonitor_Backend.h"
#include <AP_Param/AP_Param.h>
#include <utility> #include <utility>
#define HAL_BATTMON_INA231_ENABLED defined(HAL_BATTMON_INA231_BUS) && defined(HAL_BATTMON_INA231_ADDR) #ifndef HAL_BATTMON_INA2XX_ENABLED
#define HAL_BATTMON_INA2XX_ENABLED (BOARD_FLASH_SIZE > 1024)
#endif
#if HAL_BATTMON_INA231_ENABLED #if HAL_BATTMON_INA2XX_ENABLED
class AP_BattMonitor_INA231 : public AP_BattMonitor_Backend class AP_BattMonitor_INA2XX : public AP_BattMonitor_Backend
{ {
public: public:
// inherit constructor /// Constructor
using AP_BattMonitor_Backend::AP_BattMonitor_Backend; AP_BattMonitor_INA2XX(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params);
bool has_cell_voltages() const override { return false; } bool has_cell_voltages() const override { return false; }
bool has_temperature() const override { return false; } bool has_temperature() const override { return false; }
@ -24,6 +29,8 @@ public:
virtual void init(void) override; virtual void init(void) override;
virtual void read() override; virtual void read() override;
static const struct AP_Param::GroupInfo var_info[];
private: private:
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev; AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
@ -31,6 +38,9 @@ private:
bool write_word(const uint8_t reg, const uint16_t data) const; bool write_word(const uint8_t reg, const uint16_t data) const;
void timer(void); void timer(void);
AP_Int8 i2c_bus;
AP_Int8 i2c_address;
struct { struct {
uint16_t count; uint16_t count;
float volt_sum; float volt_sum;
@ -41,4 +51,4 @@ private:
float voltage_LSB; float voltage_LSB;
}; };
#endif // HAL_BATTMON_INA231_ENABLED #endif // HAL_BATTMON_INA2XX_ENABLED

View File

@ -13,7 +13,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
// @Param: MONITOR // @Param: MONITOR
// @DisplayName: Battery monitoring // @DisplayName: Battery monitoring
// @Description: Controls enabling monitoring of the battery's voltage and current // @Description: Controls enabling monitoring of the battery's voltage and current
// @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Generic,8:UAVCAN-BatteryInfo,9:ESC,10:SumOfFollowing,11:FuelFlow,12:FuelLevelPWM,13:SMBUS-SUI3,14:SMBUS-SUI6,15:NeoDesign,16:SMBus-Maxell,17:Generator-Elec,18:Generator-Fuel,19:Rotoye,20:MPPT,21:INA231,22:LTC2946,23:Torqeedo // @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Generic,8:UAVCAN-BatteryInfo,9:ESC,10:SumOfFollowing,11:FuelFlow,12:FuelLevelPWM,13:SMBUS-SUI3,14:SMBUS-SUI6,15:NeoDesign,16:SMBus-Maxell,17:Generator-Elec,18:Generator-Fuel,19:Rotoye,20:MPPT,21:INA2XX,22:LTC2946,23:Torqeedo
// @User: Standard // @User: Standard
// @RebootRequired: True // @RebootRequired: True
AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, int8_t(AP_BattMonitor::Type::NONE), AP_PARAM_FLAG_ENABLE), AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, int8_t(AP_BattMonitor::Type::NONE), AP_PARAM_FLAG_ENABLE),