mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: Create check_if_auxsw_mode_used() to check for function usage
This commit is contained in:
parent
97cd3614eb
commit
1afeb05398
@ -4,7 +4,7 @@
|
||||
static void landinggear_update(){
|
||||
|
||||
// If landing gear control is active, run update function.
|
||||
if (g.ch7_option == AUXSW_LANDING_GEAR || g.ch8_option == AUXSW_LANDING_GEAR ){
|
||||
if (check_if_auxsw_mode_used(AUXSW_LANDING_GEAR)){
|
||||
|
||||
// last status (deployed or retracted) used to check for changes
|
||||
static bool last_deploy_status;
|
||||
|
@ -36,9 +36,9 @@ static void read_control_switch()
|
||||
}
|
||||
}
|
||||
|
||||
if(g.ch7_option != AUXSW_SIMPLE_MODE && g.ch8_option != AUXSW_SIMPLE_MODE && g.ch7_option != AUXSW_SUPERSIMPLE_MODE && g.ch8_option != AUXSW_SUPERSIMPLE_MODE) {
|
||||
// set Simple mode using stored paramters from Mission planner
|
||||
// rather than by the control switch
|
||||
if(!check_if_auxsw_mode_used(AUXSW_SIMPLE_MODE) && !check_if_auxsw_mode_used(AUXSW_SUPERSIMPLE_MODE)) {
|
||||
// if none of the Aux Switches are set to Simple or Super Simple Mode then
|
||||
// set Simple Mode using stored parameters from EEPROM
|
||||
if (BIT_IS_SET(g.super_simple, switch_position)) {
|
||||
set_simple_mode(2);
|
||||
}else{
|
||||
@ -58,6 +58,14 @@ static void read_control_switch()
|
||||
control_switch_state.last_switch_position = switch_position;
|
||||
}
|
||||
|
||||
// check_if_auxsw_mode_used - Check to see if any of the Aux Switches are set to a given mode.
|
||||
static bool check_if_auxsw_mode_used(uint8_t auxsw_mode_check){
|
||||
bool ret = g.ch7_option == auxsw_mode_check || g.ch8_option == auxsw_mode_check || g.ch9_option == auxsw_mode_check
|
||||
|| g.ch10_option == auxsw_mode_check || g.ch11_option == auxsw_mode_check || g.ch12_option == auxsw_mode_check;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static void reset_control_switch()
|
||||
{
|
||||
control_switch_state.last_switch_position = control_switch_state.debounced_switch_position = -1;
|
||||
|
Loading…
Reference in New Issue
Block a user