mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: Create new heli RSC RC Channel object.
This commit is contained in:
parent
cefa0c28a6
commit
990761a13b
@ -31,7 +31,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.rc_8, 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 == TRI_FRAME // tri constructor requires additional rc_7 argument to allow tail servo reversing
|
||||
motors(MAIN_LOOP_RATE),
|
||||
#elif FRAME_CONFIG == SINGLE_FRAME // single constructor requires extra servos for flaps
|
||||
|
@ -516,6 +516,9 @@ const AP_Param::Info Copter::var_info[] PROGMEM = {
|
||||
// @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),
|
||||
|
||||
// @Param: H_STAB_COL_MIN
|
||||
// @DisplayName: Heli Stabilize Throttle Collective Minimum
|
||||
|
@ -161,6 +161,7 @@ public:
|
||||
k_param_heli_yaw_ff, // remove
|
||||
k_param_heli_stab_col_min,
|
||||
k_param_heli_stab_col_max, // 88
|
||||
k_param_heli_servo_rsc, // 89 = full!
|
||||
|
||||
//
|
||||
// 90: misc2
|
||||
@ -437,6 +438,7 @@ public:
|
||||
#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
|
||||
AP_Int16 heli_stab_col_min; // min collective while pilot directly controls collective in stabilize mode
|
||||
AP_Int16 heli_stab_col_max; // min collective while pilot directly controls collective in stabilize mode
|
||||
#endif
|
||||
@ -515,6 +517,7 @@ public:
|
||||
heli_servo_2 (CH_2),
|
||||
heli_servo_3 (CH_3),
|
||||
heli_servo_4 (CH_4),
|
||||
heli_servo_rsc (CH_8),
|
||||
#endif
|
||||
#if FRAME_CONFIG == SINGLE_FRAME
|
||||
single_servo_1 (CH_1),
|
||||
|
Loading…
Reference in New Issue
Block a user