mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Motors6DOF: add missing float specifier
This commit is contained in:
parent
a75a5c5a0b
commit
9f054dd61d
@ -341,7 +341,7 @@ void AP_Motors6DOF::output_armed_stabilizing()
|
||||
float predicted_current_ratio = predicted_current/_batt_current_max;
|
||||
_batt_current_last = _batt_current;
|
||||
|
||||
if (predicted_current > _batt_current_max * 1.5) {
|
||||
if (predicted_current > _batt_current_max * 1.5f) {
|
||||
batt_current_ratio = 2.5f;
|
||||
} else if (_batt_current < _batt_current_max && predicted_current > _batt_current_max) {
|
||||
batt_current_ratio = predicted_current_ratio;
|
||||
|
Loading…
Reference in New Issue
Block a user