Browse Source

SITL: avoid negative current and voltage in flightaxis

RealFlight9 will sometimes give meaningless negative values
c415-sdk
Andrew Tridgell 4 years ago committed by Peter Barker
parent
commit
5def8a64ab
  1. 4
      libraries/SITL/SIM_FlightAxis.cpp

4
libraries/SITL/SIM_FlightAxis.cpp

@ -466,8 +466,8 @@ void FlightAxis::update(const struct sitl_input &input)
airspeed3d.z); airspeed3d.z);
#endif #endif
battery_voltage = state.m_batteryVoltage_VOLTS; battery_voltage = MAX(state.m_batteryVoltage_VOLTS, 0);
battery_current = state.m_batteryCurrentDraw_AMPS; battery_current = MAX(state.m_batteryCurrentDraw_AMPS, 0);
rpm[0] = state.m_heliMainRotorRPM; rpm[0] = state.m_heliMainRotorRPM;
rpm[1] = state.m_propRPM; rpm[1] = state.m_propRPM;

Loading…
Cancel
Save