From 5def8a64ab1e4535e6fb68c3bbc8cc9a65408426 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 18 Jan 2021 09:18:48 +1100 Subject: [PATCH] SITL: avoid negative current and voltage in flightaxis RealFlight9 will sometimes give meaningless negative values --- libraries/SITL/SIM_FlightAxis.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index 0e3dbb2d4e..10ecfbb49b 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -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;