mirror of https://github.com/ArduPilot/ardupilot
Copter: bug fix for duplicate single and coax params
This commit is contained in:
parent
4b3699f985
commit
91b78c0cbe
|
@ -493,30 +493,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
GSCALAR(heli_stab_col_max, "H_STAB_COL_MAX", HELI_STAB_COLLECTIVE_MAX_DEFAULT),
|
||||
#endif
|
||||
|
||||
#if 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),
|
||||
#endif
|
||||
|
||||
#if 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),
|
||||
#endif
|
||||
|
||||
// RC channel
|
||||
//-----------
|
||||
// @Group: RC1_
|
||||
|
|
Loading…
Reference in New Issue