void RC_Channel::read_aux() { const aux_func_t _option = (aux_func_t)option.get(); if (_option == DO_NOTHING) { // may wish to add special cases for other "AUXSW" things // here e.g. RCMAP_ROLL etc once they become options return; } const aux_switch_pos_t new_position = read_3pos_switch(); const aux_switch_pos_t old_position = old_switch_position(); if (new_position == old_position) { debounce.count = 0; return; } if (debounce.new_position != new_position) { debounce.new_position = new_position; debounce.count = 0; } // a value of 2 means we need 3 values in a row with the same // value to activate if (debounce.count++ < 2) { return; } // debounced; undertake the action: do_aux_function(_option, new_position); set_old_switch_position(new_position); }
void RC_Channel::init_aux() { aux_switch_pos_t position; if (!read_3pos_switch(position)) { position = aux_switch_pos_t::LOW; } init_aux_function((aux_func_t)option.get(), position); }
// init_aux_switches - invoke configured actions at start-up for aux function where it is safe to do so void Copter::init_aux_switches() { // set the CH7 ~ CH12 flags aux_con.CH7_flag = read_3pos_switch(g.rc_7.radio_in); aux_con.CH8_flag = read_3pos_switch(g.rc_8.radio_in); aux_con.CH10_flag = read_3pos_switch(g.rc_10.radio_in); 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); init_aux_switch_function(g.ch8_option, aux_con.CH8_flag); init_aux_switch_function(g.ch10_option, aux_con.CH10_flag); 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_switches - invoke configured actions at start-up for aux function where it is safe to do so void Copter::init_aux_switches() { // set the CH7 ~ CH12 flags aux_con.CH7_flag = read_3pos_switch(g.rc_7.get_radio_in()); aux_con.CH8_flag = read_3pos_switch(g.rc_8.get_radio_in()); aux_con.CH10_flag = read_3pos_switch(g.rc_10.get_radio_in()); aux_con.CH11_flag = read_3pos_switch(g.rc_11.get_radio_in()); // ch9, ch12 only supported on some boards aux_con.CH9_flag = read_3pos_switch(g.rc_9.get_radio_in()); aux_con.CH12_flag = read_3pos_switch(g.rc_12.get_radio_in()); // initialise functions assigned to switches init_aux_switch_function(g.ch7_option, aux_con.CH7_flag); init_aux_switch_function(g.ch8_option, aux_con.CH8_flag); init_aux_switch_function(g.ch10_option, aux_con.CH10_flag); init_aux_switch_function(g.ch11_option, aux_con.CH11_flag); // ch9, ch12 only supported on some boards init_aux_switch_function(g.ch9_option, aux_con.CH9_flag); init_aux_switch_function(g.ch12_option, aux_con.CH12_flag); }
// init_aux_switches - invoke configured actions at start-up for aux function where it is safe to do so void Copter::init_aux_switches() { // set the CH7 ~ CH12 flags aux_con.CH7_flag = read_3pos_switch(CH_7); aux_con.CH8_flag = read_3pos_switch(CH_8); aux_con.CH10_flag = read_3pos_switch(CH_10); aux_con.CH11_flag = read_3pos_switch(CH_11); // ch9, ch12 only supported on some boards aux_con.CH9_flag = read_3pos_switch(CH_9); aux_con.CH12_flag = read_3pos_switch(CH_12); // initialise functions assigned to switches init_aux_switch_function(g.ch7_option, aux_con.CH7_flag); init_aux_switch_function(g.ch8_option, aux_con.CH8_flag); init_aux_switch_function(g.ch10_option, aux_con.CH10_flag); init_aux_switch_function(g.ch11_option, aux_con.CH11_flag); // ch9, ch12 only supported on some boards init_aux_switch_function(g.ch9_option, aux_con.CH9_flag); init_aux_switch_function(g.ch12_option, aux_con.CH12_flag); }
void RC_Channel::init_aux() { const aux_switch_pos_t position = read_3pos_switch(); set_old_switch_position(position); init_aux_function((aux_func_t)option.get(), position); }
// read_aux_switches - checks aux switch positions and invokes configured actions void Copter::read_aux_switches() { uint8_t switch_position; // exit immediately during radio failsafe if (failsafe.radio || failsafe.radio_counter != 0) { return; } // check if ch7 switch has changed position switch_position = read_3pos_switch(g.rc_7.get_radio_in()); if (aux_con.CH7_flag != switch_position) { // set the CH7 flag aux_con.CH7_flag = switch_position; // invoke the appropriate function do_aux_switch_function(g.ch7_option, aux_con.CH7_flag); } // check if Ch8 switch has changed position switch_position = read_3pos_switch(g.rc_8.get_radio_in()); if (aux_con.CH8_flag != switch_position) { // set the CH8 flag aux_con.CH8_flag = switch_position; // invoke the appropriate function do_aux_switch_function(g.ch8_option, aux_con.CH8_flag); } // check if Ch9 switch has changed position switch_position = read_3pos_switch(g.rc_9.get_radio_in()); if (aux_con.CH9_flag != switch_position) { // set the CH9 flag aux_con.CH9_flag = switch_position; // invoke the appropriate function do_aux_switch_function(g.ch9_option, aux_con.CH9_flag); } // check if Ch10 switch has changed position switch_position = read_3pos_switch(g.rc_10.get_radio_in()); if (aux_con.CH10_flag != switch_position) { // set the CH10 flag aux_con.CH10_flag = switch_position; // invoke the appropriate function do_aux_switch_function(g.ch10_option, aux_con.CH10_flag); } // check if Ch11 switch has changed position switch_position = read_3pos_switch(g.rc_11.get_radio_in()); if (aux_con.CH11_flag != switch_position) { // set the CH11 flag aux_con.CH11_flag = switch_position; // invoke the appropriate function do_aux_switch_function(g.ch11_option, aux_con.CH11_flag); } #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN // check if Ch12 switch has changed position switch_position = read_3pos_switch(g.rc_12.get_radio_in()); if (aux_con.CH12_flag != switch_position) { // set the CH12 flag aux_con.CH12_flag = switch_position; // invoke the appropriate function do_aux_switch_function(g.ch12_option, aux_con.CH12_flag); } #endif }