mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: added MAX_AMPS and SHUNT parameters for INA239
allows for a wider range of current
This commit is contained in:
parent
8a06ee4cf6
commit
a444004a8a
|
@ -30,11 +30,34 @@ extern const AP_HAL::HAL& hal;
|
||||||
#define HAL_BATTMON_INA239_MAX_CURRENT 90
|
#define HAL_BATTMON_INA239_MAX_CURRENT 90
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
const AP_Param::GroupInfo AP_BattMonitor_INA239::var_info[] = {
|
||||||
|
|
||||||
|
// @Param: MAX_AMPS
|
||||||
|
// @DisplayName: Battery monitor max current
|
||||||
|
// @Description: This controls the maximum current the INA239 sensor will work with.
|
||||||
|
// @Range: 1 400
|
||||||
|
// @Units: A
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("MAX_AMPS", 27, AP_BattMonitor_INA239, max_amps, HAL_BATTMON_INA239_MAX_CURRENT),
|
||||||
|
|
||||||
|
// @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_INA239, rShunt, HAL_BATTMON_INA239_SHUNT_RESISTANCE),
|
||||||
|
|
||||||
|
AP_GROUPEND
|
||||||
|
};
|
||||||
|
|
||||||
AP_BattMonitor_INA239::AP_BattMonitor_INA239(AP_BattMonitor &mon,
|
AP_BattMonitor_INA239::AP_BattMonitor_INA239(AP_BattMonitor &mon,
|
||||||
AP_BattMonitor::BattMonitor_State &mon_state,
|
AP_BattMonitor::BattMonitor_State &mon_state,
|
||||||
AP_BattMonitor_Params ¶ms)
|
AP_BattMonitor_Params ¶ms)
|
||||||
: AP_BattMonitor_Backend(mon, mon_state, params)
|
: AP_BattMonitor_Backend(mon, mon_state, params)
|
||||||
{
|
{
|
||||||
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
_state.var_info = var_info;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_BattMonitor_INA239::init(void)
|
void AP_BattMonitor_INA239::init(void)
|
||||||
|
@ -61,8 +84,8 @@ void AP_BattMonitor_INA239::configure(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
voltage_LSB = 3.125e-3;
|
voltage_LSB = 3.125e-3;
|
||||||
current_LSB = float(HAL_BATTMON_INA239_MAX_CURRENT) / 0x8000;
|
current_LSB = max_amps.get() / 0x8000;
|
||||||
const int16_t shunt_cal = 819.2 * 1e6 * current_LSB * HAL_BATTMON_INA239_SHUNT_RESISTANCE;
|
const int16_t shunt_cal = 819.2 * 1e6 * current_LSB * rShunt.get();
|
||||||
int16_t shunt_cal2 = 0;
|
int16_t shunt_cal2 = 0;
|
||||||
|
|
||||||
if (!write_word(REG_SHUNT_CAL, shunt_cal) ||
|
if (!write_word(REG_SHUNT_CAL, shunt_cal) ||
|
||||||
|
|
|
@ -23,6 +23,8 @@ public:
|
||||||
void init(void) override;
|
void init(void) override;
|
||||||
void read() override;
|
void read() override;
|
||||||
|
|
||||||
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
AP_HAL::OwnPtr<AP_HAL::Device> dev;
|
AP_HAL::OwnPtr<AP_HAL::Device> dev;
|
||||||
|
|
||||||
|
@ -44,6 +46,9 @@ protected:
|
||||||
} accumulate;
|
} accumulate;
|
||||||
float current_LSB;
|
float current_LSB;
|
||||||
float voltage_LSB;
|
float voltage_LSB;
|
||||||
|
|
||||||
|
AP_Float max_amps;
|
||||||
|
AP_Float rShunt;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_BATTERY_INA239_ENABLED
|
#endif // AP_BATTERY_INA239_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue