Copter: remove tradheli swash, yaw and rsc servos
These are all created within the AP_MotorsSingle class now except for servo_rsc which was unused
This commit is contained in:
parent
c4b88aafef
commit
1f37f5a0e7
@ -30,7 +30,7 @@ Copter::Copter(void) :
|
||||
FUNCTOR_BIND_MEMBER(&Copter::exit_mission, void)),
|
||||
control_mode(STABILIZE),
|
||||
#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, MAIN_LOOP_RATE),
|
||||
#else
|
||||
motors(MAIN_LOOP_RATE),
|
||||
#endif
|
||||
|
@ -533,24 +533,6 @@ const AP_Param::Info Copter::var_info[] = {
|
||||
// @User: Advanced
|
||||
GSCALAR(fs_crash_check, "FS_CRASH_CHECK", 1),
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// @Group: HS1_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||
GGROUP(heli_servo_1, "HS1_", RC_Channel),
|
||||
// @Group: HS2_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||
GGROUP(heli_servo_2, "HS2_", RC_Channel),
|
||||
// @Group: HS3_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||
GGROUP(heli_servo_3, "HS3_", RC_Channel),
|
||||
// @Group: HS4_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||
GGROUP(heli_servo_4, "HS4_", RC_Channel),
|
||||
// @Group: H_RSC_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||
GGROUP(heli_servo_rsc, "H_RSC_", RC_Channel),
|
||||
#endif
|
||||
|
||||
// RC channel
|
||||
//-----------
|
||||
// @Group: RC1_
|
||||
|
@ -161,16 +161,16 @@ public:
|
||||
//
|
||||
// 80: Heli
|
||||
//
|
||||
k_param_heli_servo_1 = 80,
|
||||
k_param_heli_servo_2,
|
||||
k_param_heli_servo_3,
|
||||
k_param_heli_servo_4,
|
||||
k_param_heli_servo_1 = 80, // remove
|
||||
k_param_heli_servo_2, // remove
|
||||
k_param_heli_servo_3, // remove
|
||||
k_param_heli_servo_4, // remove
|
||||
k_param_heli_pitch_ff, // remove
|
||||
k_param_heli_roll_ff, // remove
|
||||
k_param_heli_yaw_ff, // remove
|
||||
k_param_heli_stab_col_min, // remove
|
||||
k_param_heli_stab_col_max, // remove
|
||||
k_param_heli_servo_rsc, // 89 = full!
|
||||
k_param_heli_servo_rsc, // 89 = full! - remove
|
||||
|
||||
//
|
||||
// 90: misc2
|
||||
@ -453,12 +453,6 @@ public:
|
||||
|
||||
AP_Int8 throw_motor_start;
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// Heli
|
||||
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
|
||||
#endif
|
||||
|
||||
// RC channels
|
||||
RC_Channel rc_1;
|
||||
RC_Channel rc_2;
|
||||
@ -515,14 +509,6 @@ public:
|
||||
// above.
|
||||
Parameters() :
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
heli_servo_1 (CH_1),
|
||||
heli_servo_2 (CH_2),
|
||||
heli_servo_3 (CH_3),
|
||||
heli_servo_4 (CH_4),
|
||||
heli_servo_rsc (CH_8),
|
||||
#endif
|
||||
|
||||
rc_1 (CH_1),
|
||||
rc_2 (CH_2),
|
||||
rc_3 (CH_3),
|
||||
|
Loading…
Reference in New Issue
Block a user