From 5c94b61f49a3076c37c13115880b39a400713f51 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Jan 2016 08:22:51 +1100 Subject: [PATCH] Copter: support up to 14 input channels for all boards --- ArduCopter/Parameters.cpp | 4 ---- ArduCopter/Parameters.h | 8 -------- ArduCopter/switches.cpp | 6 ------ 3 files changed, 18 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 23befbf5f8..99c0504019 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -557,11 +557,9 @@ const AP_Param::Info Copter::var_info[] = { // @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp GGROUP(rc_8, "RC8_", RC_Channel_aux), -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN // @Group: RC9_ // @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp GGROUP(rc_9, "RC9_", RC_Channel_aux), -#endif // @Group: RC10_ // @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp @@ -570,7 +568,6 @@ const AP_Param::Info Copter::var_info[] = { // @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp GGROUP(rc_11, "RC11_", RC_Channel_aux), -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN // @Group: RC12_ // @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp GGROUP(rc_12, "RC12_", RC_Channel_aux), @@ -582,7 +579,6 @@ const AP_Param::Info Copter::var_info[] = { // @Group: RC14_ // @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp GGROUP(rc_14, "RC14_", RC_Channel_aux), -#endif // @Param: RC_SPEED // @DisplayName: ESC Update Speed diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index e381f9a10e..c647d4482b 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -472,16 +472,12 @@ public: RC_Channel_aux rc_6; RC_Channel_aux rc_7; RC_Channel_aux rc_8; -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN RC_Channel_aux rc_9; -#endif RC_Channel_aux rc_10; RC_Channel_aux rc_11; -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN RC_Channel_aux rc_12; RC_Channel_aux rc_13; RC_Channel_aux rc_14; -#endif AP_Int16 rc_speed; // speed of fast RC Channels in Hz @@ -550,16 +546,12 @@ public: rc_6 (CH_6), rc_7 (CH_7), rc_8 (CH_8), -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN rc_9 (CH_9), -#endif rc_10 (CH_10), rc_11 (CH_11), -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN rc_12 (CH_12), rc_13 (CH_13), rc_14 (CH_14), -#endif // PID controller initial P initial I initial D initial imax initial filt hz pid rate //--------------------------------------------------------------------------------------------------------------------------------- diff --git a/ArduCopter/switches.cpp b/ArduCopter/switches.cpp index e8297ddc72..152a756836 100644 --- a/ArduCopter/switches.cpp +++ b/ArduCopter/switches.cpp @@ -149,7 +149,6 @@ void Copter::read_aux_switches() do_aux_switch_function(g.ch8_option, aux_con.CH8_flag); } -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN // check if Ch9 switch has changed position switch_position = read_3pos_switch(g.rc_9.radio_in); if (aux_con.CH9_flag != switch_position) { @@ -159,7 +158,6 @@ void Copter::read_aux_switches() // invoke the appropriate function do_aux_switch_function(g.ch9_option, aux_con.CH9_flag); } -#endif // check if Ch10 switch has changed position switch_position = read_3pos_switch(g.rc_10.radio_in); @@ -204,10 +202,8 @@ void Copter::init_aux_switches() aux_con.CH11_flag = read_3pos_switch(g.rc_11.radio_in); // ch9, ch12 only supported on some boards -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN aux_con.CH9_flag = read_3pos_switch(g.rc_9.radio_in); aux_con.CH12_flag = read_3pos_switch(g.rc_12.radio_in); -#endif // initialise functions assigned to switches init_aux_switch_function(g.ch7_option, aux_con.CH7_flag); @@ -216,10 +212,8 @@ void Copter::init_aux_switches() init_aux_switch_function(g.ch11_option, aux_con.CH11_flag); // ch9, ch12 only supported on some boards -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN init_aux_switch_function(g.ch9_option, aux_con.CH9_flag); init_aux_switch_function(g.ch12_option, aux_con.CH12_flag); -#endif } // init_aux_switch_function - initialize aux functions