mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
SITL: make heli RPM rpm1 in FlightAxis
This commit is contained in:
parent
f58d837026
commit
9e9a048016
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user