mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SITL: FlightAxis can support 8 channels
This commit is contained in:
parent
9081310ff1
commit
7cdab2a6c9
@ -301,12 +301,12 @@ void FlightAxis::update(const struct sitl_input &input)
|
||||
rpm2 = state.m_heliMainRotorRPM;
|
||||
|
||||
/*
|
||||
the interlink interface doesn't seem to support more than 6 channels
|
||||
the interlink interface supports 8 input channels
|
||||
*/
|
||||
for (uint8_t i=0; i<6; i++) {
|
||||
rcin_chan_count = 8;
|
||||
for (uint8_t i=0; i<rcin_chan_count; i++) {
|
||||
rcin[i] = state.rcin[i];
|
||||
}
|
||||
rcin_chan_count = 6;
|
||||
|
||||
update_position();
|
||||
time_now_us = (state.m_currentPhysicsTime_SEC - initial_time_s)*1.0e6;
|
||||
|
Loading…
Reference in New Issue
Block a user