mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
Copter: remove coax servo objects
servos moved to AP_MotorsCoax class
This commit is contained in:
parent
5dde87734c
commit
44180e44df
@ -35,8 +35,6 @@ Copter::Copter(void) :
|
|||||||
motors(MAIN_LOOP_RATE),
|
motors(MAIN_LOOP_RATE),
|
||||||
#elif FRAME_CONFIG == SINGLE_FRAME // single constructor requires extra servos for flaps
|
#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),
|
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, g.single_servo_3, g.single_servo_4, MAIN_LOOP_RATE),
|
|
||||||
#else
|
#else
|
||||||
motors(MAIN_LOOP_RATE),
|
motors(MAIN_LOOP_RATE),
|
||||||
#endif
|
#endif
|
||||||
|
@ -1018,18 +1018,6 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
GOBJECT(motors, "MOT_", AP_MotorsSingle),
|
GOBJECT(motors, "MOT_", AP_MotorsSingle),
|
||||||
|
|
||||||
#elif FRAME_CONFIG == COAX_FRAME
|
#elif FRAME_CONFIG == COAX_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_MotorsCoax.cpp
|
// @Path: ../libraries/AP_Motors/AP_MotorsCoax.cpp
|
||||||
GOBJECT(motors, "MOT_", AP_MotorsCoax),
|
GOBJECT(motors, "MOT_", AP_MotorsCoax),
|
||||||
|
@ -153,10 +153,10 @@ public:
|
|||||||
//
|
//
|
||||||
// 75: Singlecopter, CoaxCopter
|
// 75: Singlecopter, CoaxCopter
|
||||||
//
|
//
|
||||||
k_param_single_servo_1 = 75,
|
k_param_single_servo_1 = 75, // remove
|
||||||
k_param_single_servo_2,
|
k_param_single_servo_2, // remove
|
||||||
k_param_single_servo_3,
|
k_param_single_servo_3, // remove
|
||||||
k_param_single_servo_4, // 78
|
k_param_single_servo_4, // 78 - remove
|
||||||
|
|
||||||
//
|
//
|
||||||
// 80: Heli
|
// 80: Heli
|
||||||
@ -463,11 +463,6 @@ public:
|
|||||||
RC_Channel single_servo_1, single_servo_2, single_servo_3, single_servo_4; // servos for four flaps
|
RC_Channel single_servo_1, single_servo_2, single_servo_3, single_servo_4; // servos for four flaps
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if FRAME_CONFIG == COAX_FRAME
|
|
||||||
// Coax copter flaps
|
|
||||||
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;
|
||||||
RC_Channel rc_2;
|
RC_Channel rc_2;
|
||||||
@ -538,13 +533,6 @@ public:
|
|||||||
single_servo_4 (CH_4),
|
single_servo_4 (CH_4),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#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),
|
rc_1 (CH_1),
|
||||||
rc_2 (CH_2),
|
rc_2 (CH_2),
|
||||||
rc_3 (CH_3),
|
rc_3 (CH_3),
|
||||||
|
Loading…
Reference in New Issue
Block a user