mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: fixed RealFlight RPM
This commit is contained in:
parent
60940593ee
commit
000c39ed27
@ -511,6 +511,7 @@ void FlightAxis::update(const struct sitl_input &input)
|
||||
battery_current = MAX(state.m_batteryCurrentDraw_AMPS, 0);
|
||||
rpm[0] = state.m_heliMainRotorRPM;
|
||||
rpm[1] = state.m_propRPM;
|
||||
motor_mask = 3;
|
||||
|
||||
/*
|
||||
the interlink interface supports 12 input channels
|
||||
|
Loading…
Reference in New Issue
Block a user