From a549225e602f8c7a941d13525599a6ab9d2127c9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 22 Apr 2016 10:28:06 +1000 Subject: [PATCH] Plane: support Y6 frame class in quadplane --- ArduPlane/quadplane.cpp | 8 ++++++-- ArduPlane/quadplane.h | 1 + 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 0c37d477d7..e077a87702 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -220,7 +220,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: FRAME_CLASS // @DisplayName: Frame Class // @Description: Controls major frame class for multicopter component - // @Values: 0:Quad, 1:Hexa, 2:Octa, 3:OctaQuad + // @Values: 0:Quad, 1:Hexa, 2:Octa, 3:OctaQuad, 4:Y6 // @User: Standard AP_GROUPINFO("FRAME_CLASS", 30, QuadPlane, frame_class, 0), @@ -323,7 +323,11 @@ bool QuadPlane::setup(void) break; case FRAME_CLASS_OCTAQUAD: setup_default_channels(8); - motors = new AP_MotorsOctaQuad(plane.scheduler.get_loop_rate_hz()); + motors = new AP_MotorsOctaQuad(plane.scheduler.get_loop_rate_hz()); + break; + case FRAME_CLASS_Y6: + setup_default_channels(7); + motors = new AP_MotorsY6(plane.scheduler.get_loop_rate_hz()); break; default: hal.console->printf("Unknown frame class %u\n", (unsigned)frame_class.get()); diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 8ac3ee2d96..f0c8525e60 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -239,6 +239,7 @@ private: FRAME_CLASS_HEXA=1, FRAME_CLASS_OCTA=2, FRAME_CLASS_OCTAQUAD=3, + FRAME_CLASS_Y6=4, }; struct {