mirror of https://github.com/ArduPilot/ardupilot
Copter: AP_MotorsCoax now uses 4 servos
This commit is contained in:
parent
1174ad3e66
commit
a00a9601a4
|
@ -36,7 +36,7 @@ Copter::Copter(void) :
|
||||||
#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
|
#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
|
#else
|
||||||
motors(MAIN_LOOP_RATE),
|
motors(MAIN_LOOP_RATE),
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1024,6 +1024,12 @@ const AP_Param::Info Copter::var_info[] = {
|
||||||
// @Group: SS2_
|
// @Group: SS2_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||||
GGROUP(single_servo_2, "SS2_", RC_Channel),
|
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),
|
||||||
|
|
|
@ -465,7 +465,7 @@ public:
|
||||||
|
|
||||||
#if FRAME_CONFIG == COAX_FRAME
|
#if FRAME_CONFIG == COAX_FRAME
|
||||||
// Coax copter flaps
|
// 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
|
#endif
|
||||||
|
|
||||||
// RC channels
|
// RC channels
|
||||||
|
@ -541,6 +541,8 @@ public:
|
||||||
#if FRAME_CONFIG == COAX_FRAME
|
#if FRAME_CONFIG == COAX_FRAME
|
||||||
single_servo_1 (CH_1),
|
single_servo_1 (CH_1),
|
||||||
single_servo_2 (CH_2),
|
single_servo_2 (CH_2),
|
||||||
|
single_servo_3 (CH_3),
|
||||||
|
single_servo_4 (CH_4),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
rc_1 (CH_1),
|
rc_1 (CH_1),
|
||||||
|
|
Loading…
Reference in New Issue