示例#1
0
// init_aux_switch_function - initialize aux functions
void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
{
    // init channel options
    switch(ch_option) {
    case RC_OVERRIDE_ENABLE:
    case AVOID_PROXIMITY:
        do_aux_function(ch_option, ch_flag);
        break;
    // the following functions to not need to be initialised:
    case RELAY:
    case RELAY2:
    case RELAY3:
    case RELAY4:
    case RELAY5:
    case RELAY6:
    case CAMERA_TRIGGER:
    case LOST_VEHICLE_SOUND:
    case DO_NOTHING:
    case CLEAR_WP:
    case COMPASS_LEARN:
    case LANDING_GEAR:
        break;
    case GRIPPER:
    case SPRAYER:
    case GPS_DISABLE:
        do_aux_function(ch_option, ch_flag);
        break;
    default:
        gcs().send_text(MAV_SEVERITY_WARNING, "Failed to initialise RC function (%u)", ch_option);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
        AP_HAL::panic("RC function (%u) initialisation not handled", ch_option);
#endif
        break;
    }
}
示例#2
0
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);
}
示例#3
0
// init_aux_switch_function - initialize aux functions
void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
{
    // init channel options
    switch(ch_option) {
    case SIMPLE_MODE:
    case RANGEFINDER:
    case FENCE:
    case SUPERSIMPLE_MODE:
    case ACRO_TRAINER:
    case PARACHUTE_ENABLE:
    case PARACHUTE_3POS:      // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
    case RETRACT_MOUNT:
    case MISSION_RESET:
    case ATTCON_FEEDFWD:
    case ATTCON_ACCEL_LIM:
    case MOTOR_ESTOP:
    case MOTOR_INTERLOCK:
    case AVOID_ADSB:
    case PRECISION_LOITER:
    case INVERTED:
    case WINCH_ENABLE:
        do_aux_function(ch_option, ch_flag);
        break;
    // the following functions do not need to be initialised:
    case FLIP:
    case RTL:
    case SAVE_TRIM:
    case SAVE_WP:
    case RESETTOARMEDYAW:
    case AUTO:
    case AUTOTUNE:
    case LAND:
    case BRAKE:
    case THROW:
    case SMART_RTL:
    case GUIDED:
    case PARACHUTE_RELEASE:
    case ARMDISARM:
    case WINCH_CONTROL:
    case USER_FUNC1:
    case USER_FUNC2:
    case USER_FUNC3:
    case ZIGZAG:
    case ZIGZAG_SaveWP:
        break;
    default:
        RC_Channel::init_aux_function(ch_option, ch_flag);
        break;
    }
}