From 89a2a9288506e7b30a26614a5c24cbe673ddf963 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 1 May 2016 09:45:14 +1000 Subject: [PATCH] Plane: support better build time selection of multicopter frame type makes it possible to do "make sitl-tri" --- ArduPlane/quadplane.cpp | 4 +++- ArduPlane/quadplane.h | 18 ++++++++++++++---- 2 files changed, 17 insertions(+), 5 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 944e340415..906e5c2902 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -217,12 +217,14 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Increment: 1 AP_GROUPINFO("TRAN_PIT_MAX", 29, QuadPlane, transition_pitch_max, 3), +#if FRAME_CONFIG == MULTICOPTER_FRAME // @Param: FRAME_CLASS // @DisplayName: Frame Class // @Description: Controls major frame class for multicopter component // @Values: 0:Quad, 1:Hexa, 2:Octa, 3:OctaQuad, 4:Y6 // @User: Standard AP_GROUPINFO("FRAME_CLASS", 30, QuadPlane, frame_class, 0), +#endif // @Param: FRAME_TYPE // @DisplayName: Frame Type (+, X or V) @@ -318,7 +320,7 @@ bool QuadPlane::setup(void) goto failed; } -#ifdef AP_MOTORS_FORCE_CLASS +#if FRAME_CONFIG == TRI_FRAME RC_Channel_aux::set_aux_channel_default(RC_Channel_aux::k_motor1, CH_5); RC_Channel_aux::set_aux_channel_default(RC_Channel_aux::k_motor2, CH_6); RC_Channel_aux::set_aux_channel_default(RC_Channel_aux::k_motor4, CH_8); diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 15de9d4a1a..1d0bea0220 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -7,12 +7,20 @@ #include #include -// uncomment this to force a different motor class -// #define AP_MOTORS_FORCE_CLASS AP_MotorsTri +/* + frame types for quadplane build. Most case be set with + parameters. Those that can't are listed here and chosen with a build + time FRAME_CONFIG parameter + */ +#define MULTICOPTER_FRAME 1 +#define TRI_FRAME 2 +#ifndef FRAME_CONFIG +# define FRAME_CONFIG MULTICOPTER_FRAME +#endif -#ifdef AP_MOTORS_FORCE_CLASS -#define AP_MOTORS_CLASS AP_MOTORS_FORCE_CLASS +#if FRAME_CONFIG == TRI_FRAME +#define AP_MOTORS_CLASS AP_MotorsTri #else #define AP_MOTORS_CLASS AP_MotorsMulticopter #endif @@ -110,7 +118,9 @@ private: AC_PID pid_accel_z{0.3, 1, 0, 800, 10, 0.02}; AC_PI_2D pi_vel_xy{0.7, 0.35, 1000, 5, 0.02}; +#if FRAME_CONFIG == MULTICOPTER_FRAME AP_Int8 frame_class; +#endif AP_Int8 frame_type; AP_MOTORS_CLASS *motors;