mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Motors: Refactor battery current interface
This commit is contained in:
parent
ee3511c1fa
commit
e3f1ef0c5e
@ -348,12 +348,11 @@ void AP_Motors6DOF::output_armed_stabilizing()
|
||||
const AP_BattMonitor &battery = AP::battery();
|
||||
|
||||
// Current limiting
|
||||
if (_batt_current_max <= 0.0f || !battery.has_current()) {
|
||||
float _batt_current;
|
||||
if (_batt_current_max <= 0.0f || !battery.current_amps(_batt_current)) {
|
||||
return;
|
||||
}
|
||||
|
||||
float _batt_current = battery.current_amps();
|
||||
|
||||
float _batt_current_delta = _batt_current - _batt_current_last;
|
||||
|
||||
float loop_interval = 1.0f/_loop_rate;
|
||||
|
@ -287,9 +287,11 @@ float AP_MotorsMulticopter::get_current_limit_max_throttle()
|
||||
{
|
||||
AP_BattMonitor &battery = AP::battery();
|
||||
|
||||
float _batt_current;
|
||||
|
||||
if (_batt_current_max <= 0 || // return maximum if current limiting is disabled
|
||||
!_flags.armed || // remove throttle limit if disarmed
|
||||
!battery.has_current(_batt_idx)) { // no current monitoring is available
|
||||
!battery.current_amps(_batt_current, _batt_idx)) { // no current monitoring is available
|
||||
_throttle_limit = 1.0f;
|
||||
return 1.0f;
|
||||
}
|
||||
@ -301,8 +303,6 @@ float AP_MotorsMulticopter::get_current_limit_max_throttle()
|
||||
return 1.0f;
|
||||
}
|
||||
|
||||
float _batt_current = battery.current_amps(_batt_idx);
|
||||
|
||||
// calculate the maximum current to prevent voltage sag below _batt_voltage_min
|
||||
float batt_current_max = MIN(_batt_current_max, _batt_current + (battery.voltage(_batt_idx) - _batt_voltage_min) / _batt_resistance);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user