mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: added SHUNT parameter to INS2xx driver
some vendors want different shunt resistors
This commit is contained in:
parent
429e7d2fc9
commit
5d7e7c0477
|
@ -46,6 +46,10 @@ extern const AP_HAL::HAL& hal;
|
|||
#define DEFAULT_BATTMON_INA2XX_MAX_AMPS 90.0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_BATTMON_INA2XX_SHUNT
|
||||
#define DEFAULT_BATTMON_INA2XX_SHUNT 0.0005
|
||||
#endif
|
||||
|
||||
#ifndef HAL_BATTMON_INA2XX_BUS
|
||||
#define HAL_BATTMON_INA2XX_BUS 0
|
||||
#endif
|
||||
|
@ -80,9 +84,16 @@ const AP_Param::GroupInfo AP_BattMonitor_INA2XX::var_info[] = {
|
|||
// @Range: 1 400
|
||||
// @Units: A
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("MAX_AMPS", 27, AP_BattMonitor_INA2XX, max_amps, DEFAULT_BATTMON_INA2XX_MAX_AMPS),
|
||||
|
||||
|
||||
// @Param: SHUNT
|
||||
// @DisplayName: Battery monitor shunt resistor
|
||||
// @Description: This sets the shunt resistor used in the device
|
||||
// @Range: 0.0001 0.01
|
||||
// @Units: Ohm
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SHUNT", 28, AP_BattMonitor_INA2XX, rShunt, DEFAULT_BATTMON_INA2XX_SHUNT),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -114,7 +125,6 @@ bool AP_BattMonitor_INA2XX::configure(DevType dtype)
|
|||
case DevType::INA226: {
|
||||
// configure for MAX_AMPS
|
||||
const uint16_t conf = (0x2<<9) | (0x5<<6) | (0x5<<3) | 0x7; // 2ms conv time, 16x sampling
|
||||
const float rShunt = 0.0005;
|
||||
current_LSB = max_amps / 32768.0;
|
||||
voltage_LSB = 0.00125; // 1.25mV/bit
|
||||
const uint16_t cal = uint16_t(0.00512 / (current_LSB * rShunt));
|
||||
|
@ -130,7 +140,6 @@ bool AP_BattMonitor_INA2XX::configure(DevType dtype)
|
|||
case DevType::INA228: {
|
||||
// configure for MAX_AMPS
|
||||
voltage_LSB = 195.3125e-6; // 195.3125 uV/LSB
|
||||
const float rShunt = 0.0005;
|
||||
current_LSB = max_amps / (1<<19);
|
||||
const uint16_t shunt_cal = uint16_t(13107.2e6 * current_LSB * rShunt) & 0x7FFF;
|
||||
if (write_word(REG_228_CONFIG, REG_228_CONFIG_RESET) && // reset
|
||||
|
@ -145,7 +154,6 @@ bool AP_BattMonitor_INA2XX::configure(DevType dtype)
|
|||
case DevType::INA238: {
|
||||
// configure for MAX_AMPS
|
||||
voltage_LSB = 3.125e-3; // 3.125mV/LSB
|
||||
const float rShunt = 0.0005;
|
||||
current_LSB = max_amps / (1<<15);
|
||||
const uint16_t shunt_cal = uint16_t(819.2e6 * current_LSB * rShunt) & 0x7FFF;
|
||||
if (write_word(REG_238_CONFIG, REG_238_CONFIG_RESET) && // reset
|
||||
|
|
|
@ -53,7 +53,7 @@ private:
|
|||
AP_Int8 i2c_bus;
|
||||
AP_Int8 i2c_address;
|
||||
AP_Float max_amps;
|
||||
bool callback_registered;
|
||||
AP_Float rShunt;
|
||||
uint32_t failed_reads;
|
||||
|
||||
struct {
|
||||
|
|
Loading…
Reference in New Issue