diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index ee67518675..e21883f190 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -36,7 +36,7 @@ Copter::Copter(void) : #elif FRAME_CONFIG == SINGLE_FRAME // single constructor requires extra servos for flaps motors(g.single_servo_1, g.single_servo_2, g.single_servo_3, g.single_servo_4, MAIN_LOOP_RATE), #elif FRAME_CONFIG == COAX_FRAME // single constructor requires extra servos for flaps - motors(g.single_servo_1, g.single_servo_2, MAIN_LOOP_RATE), + motors(g.single_servo_1, g.single_servo_2, g.single_servo_3, g.single_servo_4, MAIN_LOOP_RATE), #else motors(MAIN_LOOP_RATE), #endif diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index f5d914a866..3c6667d37f 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1024,6 +1024,12 @@ const AP_Param::Info Copter::var_info[] = { // @Group: SS2_ // @Path: ../libraries/RC_Channel/RC_Channel.cpp GGROUP(single_servo_2, "SS2_", RC_Channel), + // @Group: SS3_ + // @Path: ../libraries/RC_Channel/RC_Channel.cpp + GGROUP(single_servo_3, "SS3_", RC_Channel), + // @Group: SS4_ + // @Path: ../libraries/RC_Channel/RC_Channel.cpp + GGROUP(single_servo_4, "SS4_", RC_Channel), // @Group: MOT_ // @Path: ../libraries/AP_Motors/AP_MotorsCoax.cpp GOBJECT(motors, "MOT_", AP_MotorsCoax), diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 2d44b160b5..fa5df2a52a 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -465,7 +465,7 @@ public: #if FRAME_CONFIG == COAX_FRAME // Coax copter flaps - RC_Channel single_servo_1, single_servo_2; // servos for two flaps + RC_Channel single_servo_1, single_servo_2, single_servo_3, single_servo_4; // servos for four flaps #endif // RC channels @@ -541,6 +541,8 @@ public: #if FRAME_CONFIG == COAX_FRAME single_servo_1 (CH_1), single_servo_2 (CH_2), + single_servo_3 (CH_3), + single_servo_4 (CH_4), #endif rc_1 (CH_1),