mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_HAL_SITL: correct battery setup for rover
This commit is contained in:
parent
87d27957d9
commit
a5e5ee73eb
@ -481,7 +481,12 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
|
|||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// simulate simple battery setup
|
// simulate simple battery setup
|
||||||
float throttle = motors_on?(input.servos[2]-1000) / 1000.0f:0;
|
float throttle;
|
||||||
|
if (_vehicle == APMrover2) {
|
||||||
|
throttle = motors_on ? (input.servos[2] - 1500) / 500.0f : 0;
|
||||||
|
} else {
|
||||||
|
throttle = motors_on ? (input.servos[2] - 1000) / 1000.0f : 0;
|
||||||
|
}
|
||||||
// lose 0.7V at full throttle
|
// lose 0.7V at full throttle
|
||||||
voltage = _sitl->batt_voltage - 0.7f*fabsf(throttle);
|
voltage = _sitl->batt_voltage - 0.7f*fabsf(throttle);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user