Copter: removed unused servo3, servo4 from coax

This commit is contained in:
Randy Mackay 2014-02-06 23:41:13 +09:00
parent e6f4fb4828
commit 5d929351ca
3 changed files with 6 additions and 20 deletions

View File

@ -478,7 +478,7 @@ static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.rc_7);
#elif FRAME_CONFIG == SINGLE_FRAME // single constructor requires extra servos for flaps
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.single_servo_1, &g.single_servo_2, &g.single_servo_3, &g.single_servo_4);
#elif FRAME_CONFIG == COAX_FRAME // single constructor requires extra servos for flaps
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.single_servo_1, &g.single_servo_2, &g.single_servo_3, &g.single_servo_4);
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.single_servo_1, &g.single_servo_2);
#else
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4);
#endif

View File

@ -107,7 +107,7 @@ public:
k_param_gps_glitch, // 70
//
// 75: Singlecopter
// 75: Singlecopter, CoaxCopter
//
k_param_single_servo_1 = 75,
k_param_single_servo_2,
@ -379,8 +379,8 @@ public:
#endif
#if FRAME_CONFIG == COAX_FRAME
// Single
RC_Channel single_servo_1, single_servo_2, single_servo_3, single_servo_4; // servos for four flaps
// Coax copter flaps
RC_Channel single_servo_1, single_servo_2; // servos for two flaps
#endif
// RC channels
@ -449,8 +449,6 @@ 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),

View File

@ -515,12 +515,6 @@ const AP_Param::Info var_info[] PROGMEM = {
// @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),
#endif
// RC channel
@ -1124,15 +1118,9 @@ const AP_Param::Info var_info[] PROGMEM = {
// @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_MotorsSingle.cpp
GOBJECT(motors, "MOT_", AP_MotorsSingle),
// @Path: ../libraries/AP_Motors/AP_MotorsCoax.cpp
GOBJECT(motors, "MOT_", AP_MotorsCoax),
#else
// @Group: MOT_