void Plane::set_mode(enum FlightMode mode) { if(control_mode == mode) { // don't switch modes if we are already in the correct mode. return; } if(g.auto_trim > 0 && control_mode == MANUAL) trim_control_surfaces(); // perform any cleanup required for prev flight mode exit_mode(control_mode); // cancel inverted flight auto_state.inverted_flight = false; // don't cross-track when starting a mission auto_state.next_wp_no_crosstrack = true; // reset landing check auto_state.checked_for_autoland = false; // reset go around command auto_state.commanded_go_around = false; // not in pre-flare auto_state.land_pre_flare = false; // zero locked course steer_state.locked_course_err = 0; // reset crash detection crash_state.is_crashed = false; crash_state.impact_detected = false; // always reset this because we don't know who called set_mode. In evasion // behavior you should set this flag after set_mode so you know the evasion // logic is controlling the mode. This allows manual override of the mode // to exit evasion behavior automatically but if the mode is manually switched // then we won't resume AUTO after an evasion adsb_state.is_evading = false; // set mode previous_mode = control_mode; control_mode = mode; if (previous_mode == AUTOTUNE && control_mode != AUTOTUNE) { // restore last gains autotune_restore(); } // zero initial pitch and highest airspeed on mode change auto_state.highest_airspeed = 0; auto_state.initial_pitch_cd = ahrs.pitch_sensor; // disable taildrag takeoff on mode change auto_state.fbwa_tdrag_takeoff_mode = false; // start with previous WP at current location prev_WP_loc = current_loc; // new mode means new loiter loiter.start_time_ms = 0; // assume non-VTOL mode auto_state.vtol_mode = false; switch(control_mode) { case INITIALISING: auto_throttle_mode = true; break; case MANUAL: case STABILIZE: case TRAINING: case FLY_BY_WIRE_A: auto_throttle_mode = false; break; case AUTOTUNE: auto_throttle_mode = false; autotune_start(); break; case ACRO: auto_throttle_mode = false; acro_state.locked_roll = false; acro_state.locked_pitch = false; break; case CRUISE: auto_throttle_mode = true; cruise_state.locked_heading = false; cruise_state.lock_timer_ms = 0; set_target_altitude_current(); break; case FLY_BY_WIRE_B: auto_throttle_mode = true; set_target_altitude_current(); break; case CIRCLE: // the altitude to circle at is taken from the current altitude auto_throttle_mode = true; next_WP_loc.alt = current_loc.alt; break; case AUTO: auto_throttle_mode = true; auto_state.vtol_mode = false; next_WP_loc = prev_WP_loc = current_loc; // start or resume the mission, based on MIS_AUTORESET mission.start_or_resume(); break; case RTL: auto_throttle_mode = true; prev_WP_loc = current_loc; do_RTL(); break; case LOITER: auto_throttle_mode = true; do_loiter_at_location(); break; case GUIDED: auto_throttle_mode = true; guided_throttle_passthru = false; /* when entering guided mode we set the target as the current location. This matches the behaviour of the copter code */ guided_WP_loc = current_loc; set_guided_WP(); break; case QSTABILIZE: case QHOVER: case QLOITER: case QLAND: if (!quadplane.init_mode()) { control_mode = previous_mode; } else { auto_throttle_mode = false; auto_state.vtol_mode = true; } break; } // start with throttle suppressed in auto_throttle modes throttle_suppressed = auto_throttle_mode; if (should_log(MASK_LOG_MODE)) DataFlash.Log_Write_Mode(control_mode); // reset attitude integrators on mode change rollController.reset_I(); pitchController.reset_I(); yawController.reset_I(); steerController.reset_I(); }
void Plane::set_mode(enum FlightMode mode) { if(control_mode == mode) { // don't switch modes if we are already in the correct mode. return; } if(g.auto_trim > 0 && control_mode == MANUAL) trim_control_surfaces(); // perform any cleanup required for prev flight mode exit_mode(control_mode); // cancel inverted flight auto_state.inverted_flight = false; // don't cross-track when starting a mission auto_state.next_wp_no_crosstrack = true; // reset landing check auto_state.checked_for_autoland = false; // reset go around command auto_state.commanded_go_around = false; // zero locked course steer_state.locked_course_err = 0; // set mode previous_mode = control_mode; control_mode = mode; if (previous_mode == AUTOTUNE && control_mode != AUTOTUNE) { // restore last gains autotune_restore(); } // zero initial pitch and highest airspeed on mode change auto_state.highest_airspeed = 0; auto_state.initial_pitch_cd = ahrs.pitch_sensor; // disable taildrag takeoff on mode change auto_state.fbwa_tdrag_takeoff_mode = false; switch(control_mode) { case INITIALISING: auto_throttle_mode = true; break; case MANUAL: case STABILIZE: case TRAINING: case FLY_BY_WIRE_A: auto_throttle_mode = false; break; case AUTOTUNE: auto_throttle_mode = false; autotune_start(); break; case ACRO: auto_throttle_mode = false; acro_state.locked_roll = false; acro_state.locked_pitch = false; break; case CRUISE: auto_throttle_mode = true; cruise_state.locked_heading = false; cruise_state.lock_timer_ms = 0; set_target_altitude_current(); break; case FLY_BY_WIRE_B: auto_throttle_mode = true; set_target_altitude_current(); break; case CIRCLE: // the altitude to circle at is taken from the current altitude auto_throttle_mode = true; next_WP_loc.alt = current_loc.alt; break; case AUTO: auto_throttle_mode = true; next_WP_loc = prev_WP_loc = current_loc; // start or resume the mission, based on MIS_AUTORESET mission.start_or_resume(); break; case RTL: auto_throttle_mode = true; prev_WP_loc = current_loc; do_RTL(); break; case LOITER: auto_throttle_mode = true; do_loiter_at_location(); break; case GUIDED: auto_throttle_mode = true; guided_throttle_passthru = false; /* when entering guided mode we set the target as the current location. This matches the behaviour of the copter code */ guided_WP_loc = current_loc; set_guided_WP(); break; } // start with throttle suppressed in auto_throttle modes throttle_suppressed = auto_throttle_mode; if (should_log(MASK_LOG_MODE)) DataFlash.Log_Write_Mode(control_mode); // reset attitude integrators on mode change rollController.reset_I(); pitchController.reset_I(); yawController.reset_I(); steerController.reset_I(); }
void Plane::set_mode(enum FlightMode mode, mode_reason_t reason) { if(control_mode == mode) { // don't switch modes if we are already in the correct mode. return; } if(g.auto_trim > 0 && control_mode == MANUAL) trim_control_surfaces(); // perform any cleanup required for prev flight mode exit_mode(control_mode); // cancel inverted flight auto_state.inverted_flight = false; // don't cross-track when starting a mission auto_state.next_wp_no_crosstrack = true; // reset landing check auto_state.checked_for_autoland = false; // reset go around command auto_state.commanded_go_around = false; // not in pre-flare auto_state.land_pre_flare = false; // zero locked course steer_state.locked_course_err = 0; // reset crash detection crash_state.is_crashed = false; crash_state.impact_detected = false; // reset external attitude guidance guided_state.last_forced_rpy_ms.zero(); guided_state.last_forced_throttle_ms = 0; // set mode previous_mode = control_mode; control_mode = mode; previous_mode_reason = control_mode_reason; control_mode_reason = reason; #if FRSKY_TELEM_ENABLED == ENABLED frsky_telemetry.update_control_mode(control_mode); #endif if (previous_mode == AUTOTUNE && control_mode != AUTOTUNE) { // restore last gains autotune_restore(); } // zero initial pitch and highest airspeed on mode change auto_state.highest_airspeed = 0; auto_state.initial_pitch_cd = ahrs.pitch_sensor; // disable taildrag takeoff on mode change auto_state.fbwa_tdrag_takeoff_mode = false; // start with previous WP at current location prev_WP_loc = current_loc; // new mode means new loiter loiter.start_time_ms = 0; // assume non-VTOL mode auto_state.vtol_mode = false; auto_state.vtol_loiter = false; switch(control_mode) { case INITIALISING: auto_throttle_mode = true; auto_navigation_mode = false; break; case MANUAL: case STABILIZE: case TRAINING: case FLY_BY_WIRE_A: auto_throttle_mode = false; auto_navigation_mode = false; break; case AUTOTUNE: auto_throttle_mode = false; auto_navigation_mode = false; autotune_start(); break; case ACRO: auto_throttle_mode = false; auto_navigation_mode = false; acro_state.locked_roll = false; acro_state.locked_pitch = false; break; case CRUISE: auto_throttle_mode = true; auto_navigation_mode = false; cruise_state.locked_heading = false; cruise_state.lock_timer_ms = 0; set_target_altitude_current(); break; case FLY_BY_WIRE_B: auto_throttle_mode = true; auto_navigation_mode = false; set_target_altitude_current(); break; case CIRCLE: // the altitude to circle at is taken from the current altitude auto_throttle_mode = true; auto_navigation_mode = true; next_WP_loc.alt = current_loc.alt; break; case AUTO: auto_throttle_mode = true; auto_navigation_mode = true; if (quadplane.available() && quadplane.enable == 2) { auto_state.vtol_mode = true; } else { auto_state.vtol_mode = false; } next_WP_loc = prev_WP_loc = current_loc; // start or resume the mission, based on MIS_AUTORESET mission.start_or_resume(); break; case RTL: auto_throttle_mode = true; auto_navigation_mode = true; prev_WP_loc = current_loc; do_RTL(get_RTL_altitude()); break; case LOITER: auto_throttle_mode = true; auto_navigation_mode = true; do_loiter_at_location(); break; case AVOID_ADSB: case GUIDED: auto_throttle_mode = true; auto_navigation_mode = true; guided_throttle_passthru = false; /* when entering guided mode we set the target as the current location. This matches the behaviour of the copter code */ guided_WP_loc = current_loc; set_guided_WP(); break; case QSTABILIZE: case QHOVER: case QLOITER: case QLAND: case QRTL: auto_navigation_mode = false; if (!quadplane.init_mode()) { control_mode = previous_mode; } else { auto_throttle_mode = false; auto_state.vtol_mode = true; } break; } // start with throttle suppressed in auto_throttle modes throttle_suppressed = auto_throttle_mode; adsb.set_is_auto_mode(auto_navigation_mode); if (should_log(MASK_LOG_MODE)) DataFlash.Log_Write_Mode(control_mode); // reset attitude integrators on mode change rollController.reset_I(); pitchController.reset_I(); yawController.reset_I(); steerController.reset_I(); }