SITL: Calculate current in SIM_Plane.

This commit is contained in:
Samuel Tabor 2020-08-17 15:07:19 +01:00 committed by Peter Barker
parent 99e95666e8
commit c9362fbb70
1 changed files with 3 additions and 0 deletions

View File

@ -308,6 +308,9 @@ void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel
float thrust = throttle;
battery_voltage = sitl->batt_voltage - 0.7*throttle;
battery_current = 50.0f*throttle;
if (ice_engine) {
thrust = icengine.update(input);
}