Browse Source

SITL: Calculate current in SIM_Plane.

zr-v5.1
Samuel Tabor 5 years ago committed by Peter Barker
parent
commit
c9362fbb70
  1. 3
      libraries/SITL/SIM_Plane.cpp

3
libraries/SITL/SIM_Plane.cpp

@ -308,6 +308,9 @@ void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel @@ -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);
}

Loading…
Cancel
Save