ArduPlane: add support for deca frame in QuadPlane::setup

The deca frame is properly supported for Copter and as the quadplane vtol setup calls upon the copter frames, it should also be supported for arduplane vtol for anyone who wants to work 10 vertical motors.
This commit is contained in:
Ido Buchman 2024-08-21 19:16:19 +10:00 committed by Peter Hall
parent 32cee974e4
commit e037b0b985
1 changed files with 3 additions and 0 deletions

View File

@ -695,6 +695,9 @@ bool QuadPlane::setup(void)
case AP_Motors::MOTOR_FRAME_Y6:
setup_default_channels(7);
break;
case AP_Motors::MOTOR_FRAME_DECA:
setup_default_channels(10);
break;
case AP_Motors::MOTOR_FRAME_TRI:
SRV_Channels::set_default_function(CH_5, SRV_Channel::k_motor1);
SRV_Channels::set_default_function(CH_6, SRV_Channel::k_motor2);