Plane: support octaquad planes

This commit is contained in:
Andrew Tridgell 2016-03-13 10:04:25 +11:00
parent 2a6e64e358
commit d644474817
1 changed files with 4 additions and 0 deletions

View File

@ -399,6 +399,10 @@ bool QuadPlane::setup(void)
setup_default_channels(8);
motors = new AP_MotorsOcta(plane.ins.get_sample_rate());
break;
case FRAME_CLASS_OCTAQUAD:
setup_default_channels(8);
motors = new AP_MotorsOctaQuad(plane.ins.get_sample_rate());
break;
default:
hal.console->printf("Unknown frame class %u\n", (unsigned)frame_class.get());
goto failed;