From 9e9a048016c23d98f400355bdbf5aab63f8ebd64 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 Jun 2016 18:32:15 +1000 Subject: [PATCH] SITL: make heli RPM rpm1 in FlightAxis --- 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 bea968571c..60f92890aa 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -319,8 +319,8 @@ void FlightAxis::update(const struct sitl_input &input) battery_voltage = state.m_batteryVoltage_VOLTS; battery_current = state.m_batteryCurrentDraw_AMPS; - rpm1 = state.m_propRPM; - rpm2 = state.m_heliMainRotorRPM; + rpm1 = state.m_heliMainRotorRPM; + rpm2 = state.m_propRPM; /* the interlink interface supports 8 input channels