Copter: remove single frame's servo objects

This commit is contained in:
Leonard Hall 2016-01-21 10:50:22 +09:00 committed by Randy Mackay
parent 8d0a6765f1
commit 6c40d6f774
3 changed files with 0 additions and 24 deletions

View File

@ -31,8 +31,6 @@ Copter::Copter(void) :
control_mode(STABILIZE), control_mode(STABILIZE),
#if FRAME_CONFIG == HELI_FRAME // helicopter constructor requires more arguments #if FRAME_CONFIG == HELI_FRAME // helicopter constructor requires more arguments
motors(g.rc_7, g.heli_servo_rsc, g.heli_servo_1, g.heli_servo_2, g.heli_servo_3, g.heli_servo_4, MAIN_LOOP_RATE), motors(g.rc_7, g.heli_servo_rsc, g.heli_servo_1, g.heli_servo_2, g.heli_servo_3, g.heli_servo_4, MAIN_LOOP_RATE),
#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),
#else #else
motors(MAIN_LOOP_RATE), motors(MAIN_LOOP_RATE),
#endif #endif

View File

@ -1001,18 +1001,6 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECT(motors, "H_", AP_MotorsHeli_Single), GOBJECT(motors, "H_", AP_MotorsHeli_Single),
#elif FRAME_CONFIG == SINGLE_FRAME #elif FRAME_CONFIG == SINGLE_FRAME
// @Group: SS1_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(single_servo_1, "SS1_", RC_Channel),
// @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_ // @Group: MOT_
// @Path: ../libraries/AP_Motors/AP_MotorsSingle.cpp // @Path: ../libraries/AP_Motors/AP_MotorsSingle.cpp
GOBJECT(motors, "MOT_", AP_MotorsSingle), GOBJECT(motors, "MOT_", AP_MotorsSingle),

View File

@ -458,10 +458,6 @@ public:
RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail
RC_Channel heli_servo_rsc; // servo for rotor speed control output RC_Channel heli_servo_rsc; // servo for rotor speed control output
#endif #endif
#if FRAME_CONFIG == SINGLE_FRAME
// Single
RC_Channel single_servo_1, single_servo_2, single_servo_3, single_servo_4; // servos for four flaps
#endif
// RC channels // RC channels
RC_Channel rc_1; RC_Channel rc_1;
@ -526,12 +522,6 @@ public:
heli_servo_4 (CH_4), heli_servo_4 (CH_4),
heli_servo_rsc (CH_8), heli_servo_rsc (CH_8),
#endif #endif
#if FRAME_CONFIG == SINGLE_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), rc_1 (CH_1),
rc_2 (CH_2), rc_2 (CH_2),