SITL: avoid negative current and voltage in flightaxis

RealFlight9 will sometimes give meaningless negative values
This commit is contained in:
Andrew Tridgell 2021-01-18 09:18:48 +11:00 committed by Peter Barker
parent 30eed3103b
commit 5def8a64ab

View File

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