// 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); }