mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_SITL: handle negative throttle
- negative throttle was causing negative voltage offsets
This commit is contained in:
parent
b55294920b
commit
f695f37ca3
@ -405,10 +405,10 @@ void SITL_State::_simulator_servos(Aircraft::sitl_input &input)
|
||||
// simulate simple battery setup
|
||||
float throttle = _sitl->motors_on?(input.servos[2]-1000) / 1000.0f:0;
|
||||
// lose 0.7V at full throttle
|
||||
voltage = _sitl->batt_voltage - 0.7f*throttle;
|
||||
voltage = _sitl->batt_voltage - 0.7f*fabsf(throttle);
|
||||
|
||||
// assume 50A at full throttle
|
||||
_current = 50.0f * throttle;
|
||||
_current = 50.0f * fabsf(throttle);
|
||||
} else {
|
||||
// FDM provides voltage and current
|
||||
voltage = _sitl->state.battery_voltage;
|
||||
|
Loading…
Reference in New Issue
Block a user