mirror of https://github.com/ArduPilot/ardupilot
Rover: support up to 14 input channels on all boards
This commit is contained in:
parent
5c94b61f49
commit
bd272390bc
|
@ -193,7 +193,6 @@ const AP_Param::Info Rover::var_info[] = {
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_8, "RC8_", RC_Channel_aux),
|
GGROUP(rc_8, "RC8_", RC_Channel_aux),
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
||||||
// @Group: RC9_
|
// @Group: RC9_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_9, "RC9_", RC_Channel_aux),
|
GGROUP(rc_9, "RC9_", RC_Channel_aux),
|
||||||
|
@ -217,7 +216,6 @@ const AP_Param::Info Rover::var_info[] = {
|
||||||
// @Group: RC14_
|
// @Group: RC14_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_14, "RC14_", RC_Channel_aux),
|
GGROUP(rc_14, "RC14_", RC_Channel_aux),
|
||||||
#endif
|
|
||||||
|
|
||||||
// @Param: THR_MIN
|
// @Param: THR_MIN
|
||||||
// @DisplayName: Minimum Throttle
|
// @DisplayName: Minimum Throttle
|
||||||
|
|
|
@ -249,14 +249,12 @@ public:
|
||||||
RC_Channel_aux rc_6;
|
RC_Channel_aux rc_6;
|
||||||
RC_Channel_aux rc_7;
|
RC_Channel_aux rc_7;
|
||||||
RC_Channel_aux rc_8;
|
RC_Channel_aux rc_8;
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
RC_Channel_aux rc_9;
|
||||||
RC_Channel_aux rc_9;
|
RC_Channel_aux rc_10;
|
||||||
RC_Channel_aux rc_10;
|
RC_Channel_aux rc_11;
|
||||||
RC_Channel_aux rc_11;
|
RC_Channel_aux rc_12;
|
||||||
RC_Channel_aux rc_12;
|
RC_Channel_aux rc_13;
|
||||||
RC_Channel_aux rc_13;
|
RC_Channel_aux rc_14;
|
||||||
RC_Channel_aux rc_14;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Throttle
|
// Throttle
|
||||||
//
|
//
|
||||||
|
@ -310,14 +308,12 @@ public:
|
||||||
rc_6(CH_6),
|
rc_6(CH_6),
|
||||||
rc_7(CH_7),
|
rc_7(CH_7),
|
||||||
rc_8(CH_8),
|
rc_8(CH_8),
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
||||||
rc_9(CH_9),
|
rc_9(CH_9),
|
||||||
rc_10(CH_10),
|
rc_10(CH_10),
|
||||||
rc_11(CH_11),
|
rc_11(CH_11),
|
||||||
rc_12(CH_12),
|
rc_12(CH_12),
|
||||||
rc_13(CH_13),
|
rc_13(CH_13),
|
||||||
rc_14(CH_14),
|
rc_14(CH_14),
|
||||||
#endif
|
|
||||||
|
|
||||||
// PID controller initial P initial I initial D initial imax
|
// PID controller initial P initial I initial D initial imax
|
||||||
//-----------------------------------------------------------------------------------
|
//-----------------------------------------------------------------------------------
|
||||||
|
|
Loading…
Reference in New Issue