Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduPlane/mode.cpp
Views: 1798
#include "Plane.h"12Mode::Mode() :3unused_integer{17},4#if HAL_QUADPLANE_ENABLED5pos_control(plane.quadplane.pos_control),6attitude_control(plane.quadplane.attitude_control),7loiter_nav(plane.quadplane.loiter_nav),8quadplane(plane.quadplane),9poscontrol(plane.quadplane.poscontrol),10#endif11ahrs(plane.ahrs)12{13}1415void Mode::exit()16{17// call sub-classes exit18_exit();19// stop autotuning if not AUTOTUNE mode20if (plane.control_mode != &plane.mode_autotune){21plane.autotune_restore();22}2324}2526bool Mode::enter()27{28#if AP_SCRIPTING_ENABLED29// reset nav_scripting.enabled30plane.nav_scripting.enabled = false;31#endif3233// cancel inverted flight34plane.auto_state.inverted_flight = false;3536// cancel waiting for rudder neutral37plane.takeoff_state.waiting_for_rudder_neutral = false;3839// don't cross-track when starting a mission40plane.auto_state.next_wp_crosstrack = false;4142// reset landing check43plane.auto_state.checked_for_autoland = false;4445// zero locked course46plane.steer_state.locked_course_err = 0;47plane.steer_state.locked_course = false;4849// reset crash detection50plane.crash_state.is_crashed = false;51plane.crash_state.impact_detected = false;5253// reset external attitude guidance54plane.guided_state.last_forced_rpy_ms.zero();55plane.guided_state.last_forced_throttle_ms = 0;5657#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED58plane.guided_state.target_heading = -4; // radians here are in range -3.14 to 3.14, so a default value needs to be outside that range59plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;60plane.guided_state.target_airspeed_cm = -1; // same as above, although an airspeed of -1 is rare on plane.61plane.guided_state.target_alt_time_ms = 0;62plane.guided_state.target_location.set_alt_cm(-1, Location::AltFrame::ABSOLUTE);63#endif6465#if AP_CAMERA_ENABLED66plane.camera.set_is_auto_mode(this == &plane.mode_auto);67#endif6869// zero initial pitch and highest airspeed on mode change70plane.auto_state.highest_airspeed = 0;71plane.auto_state.initial_pitch_cd = ahrs.pitch_sensor;7273// disable taildrag takeoff on mode change74plane.auto_state.fbwa_tdrag_takeoff_mode = false;7576// start with previous WP at current location77plane.prev_WP_loc = plane.current_loc;7879// new mode means new loiter80plane.loiter.start_time_ms = 0;8182// record time of mode change83plane.last_mode_change_ms = AP_HAL::millis();8485// set VTOL auto state86plane.auto_state.vtol_mode = is_vtol_mode();87plane.auto_state.vtol_loiter = false;8889// initialize speed variable used in AUTO and GUIDED for DO_CHANGE_SPEED commands90plane.new_airspeed_cm = -1;9192// clear postponed long failsafe if mode change (from GCS) occurs before recall of long failsafe93plane.long_failsafe_pending = false;9495#if HAL_QUADPLANE_ENABLED96quadplane.mode_enter();97#endif9899#if AP_TERRAIN_AVAILABLE100plane.target_altitude.terrain_following_pending = false;101#endif102103// disable auto mode servo idle during altitude wait command104plane.auto_state.idle_mode = false;105106bool enter_result = _enter();107108if (enter_result) {109// -------------------110// these must be done AFTER _enter() because they use the results to set more flags111112// start with throttle suppressed in auto_throttle modes113plane.throttle_suppressed = does_auto_throttle();114#if HAL_ADSB_ENABLED115plane.adsb.set_is_auto_mode(does_auto_navigation());116#endif117118// set the nav controller stale AFTER _enter() so that we can check if we're currently in a loiter during the mode change119plane.nav_controller->set_data_is_stale();120121// reset steering integrator on mode change122plane.steerController.reset_I();123124// update RC failsafe, as mode change may have necessitated changing the failsafe throttle125plane.control_failsafe();126127#if AP_FENCE_ENABLED128// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover129// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)130// but it should be harmless to disable the fence temporarily in these situations as well131plane.fence.manual_recovery_start();132#endif133//reset mission if in landing sequence, disarmed, not flying, and have changed to a non-autothrottle mode to clear prearm134if (plane.mission.get_in_landing_sequence_flag() &&135!plane.is_flying() && !plane.arming.is_armed_and_safety_off() &&136!plane.control_mode->does_auto_navigation()) {137GCS_SEND_TEXT(MAV_SEVERITY_INFO, "In landing sequence: mission reset");138plane.mission.reset();139}140141// Make sure the flight stage is correct for the new mode142plane.update_flight_stage();143144// reset landing state145plane.landing.reset();146147148#if HAL_QUADPLANE_ENABLED149if (quadplane.enabled()) {150float aspeed;151bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed);152quadplane.assisted_flight = quadplane.assist.should_assist(aspeed, have_airspeed);153}154#endif155}156157return enter_result;158}159160bool Mode::is_vtol_man_throttle() const161{162#if HAL_QUADPLANE_ENABLED163if (plane.quadplane.tailsitter.is_in_fw_flight() &&164plane.quadplane.assisted_flight) {165// We are a tailsitter that has fully transitioned to Q-assisted forward flight.166// In this case the forward throttle directly drives the vertical throttle so167// set vertical throttle state to match the forward throttle state. Confusingly the booleans are inverted,168// forward throttle uses 'does_auto_throttle' whereas vertical uses 'is_vtol_man_throttle'.169return !does_auto_throttle();170}171#endif172return false;173}174175void Mode::update_target_altitude()176{177Location target_location;178179if (plane.landing.is_flaring()) {180// during a landing flare, use TECS_LAND_SINK as a target sink181// rate, and ignores the target altitude182plane.set_target_altitude_location(plane.next_WP_loc);183} else if (plane.landing.is_on_approach()) {184plane.landing.setup_landing_glide_slope(plane.prev_WP_loc, plane.next_WP_loc, plane.current_loc, plane.target_altitude.offset_cm);185#if AP_RANGEFINDER_ENABLED186plane.landing.adjust_landing_slope_for_rangefinder_bump(plane.rangefinder_state, plane.prev_WP_loc, plane.next_WP_loc, plane.current_loc, plane.auto_state.wp_distance, plane.target_altitude.offset_cm);187#endif188} else if (plane.landing.get_target_altitude_location(target_location)) {189plane.set_target_altitude_location(target_location);190#if HAL_SOARING_ENABLED191} else if (plane.g2.soaring_controller.is_active() && plane.g2.soaring_controller.get_throttle_suppressed()) {192// Reset target alt to current alt, to prevent large altitude errors when gliding.193plane.set_target_altitude_location(plane.current_loc);194plane.reset_offset_altitude();195#endif196} else if (plane.reached_loiter_target()) {197// once we reach a loiter target then lock to the final198// altitude target199plane.set_target_altitude_location(plane.next_WP_loc);200} else if (plane.target_altitude.offset_cm != 0 &&201!plane.current_loc.past_interval_finish_line(plane.prev_WP_loc, plane.next_WP_loc)) {202// control climb/descent rate203plane.set_target_altitude_proportion(plane.next_WP_loc, 1.0f-plane.auto_state.wp_proportion);204205// stay within the range of the start and end locations in altitude206plane.constrain_target_altitude_location(plane.next_WP_loc, plane.prev_WP_loc);207} else {208plane.set_target_altitude_location(plane.next_WP_loc);209}210}211212// returns true if the vehicle can be armed in this mode213bool Mode::pre_arm_checks(size_t buflen, char *buffer) const214{215if (!_pre_arm_checks(buflen, buffer)) {216if (strlen(buffer) == 0) {217// If no message is provided add a generic one218hal.util->snprintf(buffer, buflen, "mode not armable");219}220return false;221}222223return true;224}225226// Auto and Guided do not call this to bypass the q-mode check.227bool Mode::_pre_arm_checks(size_t buflen, char *buffer) const228{229#if HAL_QUADPLANE_ENABLED230if (plane.quadplane.enabled() && !is_vtol_mode() &&231plane.quadplane.option_is_set(QuadPlane::OPTION::ONLY_ARM_IN_QMODE_OR_AUTO)) {232hal.util->snprintf(buffer, buflen, "not Q mode");233return false;234}235#endif236return true;237}238239void Mode::run()240{241// Direct stick mixing functionality has been removed, so as not to remove all stick mixing from the user completely242// the old direct option is now used to enable fbw mixing, this is easier than doing a param conversion.243if ((plane.g.stick_mixing == StickMixing::FBW) || (plane.g.stick_mixing == StickMixing::DIRECT_REMOVED)) {244plane.stabilize_stick_mixing_fbw();245}246plane.stabilize_roll();247plane.stabilize_pitch();248plane.stabilize_yaw();249}250251// Reset rate and steering controllers252void Mode::reset_controllers()253{254// reset integrators255plane.rollController.reset_I();256plane.pitchController.reset_I();257plane.yawController.reset_I();258259// reset steering controls260plane.steer_state.locked_course = false;261plane.steer_state.locked_course_err = 0;262263// reset TECS264plane.TECS_controller.reset();265}266267bool Mode::is_taking_off() const268{269return (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF);270}271272// Helper to output to both k_rudder and k_steering servo functions273void Mode::output_rudder_and_steering(float val)274{275SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, val);276SRV_Channels::set_output_scaled(SRV_Channel::k_steering, val);277}278279// Output pilot throttle, this is used in stabilized modes without auto throttle control280// Direct mapping if THR_PASS_STAB is set281// Otherwise apply curve for trim correction if configured282void Mode::output_pilot_throttle()283{284if (plane.g.throttle_passthru_stabilize) {285// THR_PASS_STAB set, direct mapping286SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.get_throttle_input(true));287return;288}289290// get throttle, but adjust center to output TRIM_THROTTLE if flight option set291SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.get_adjusted_throttle_input(true));292}293294// true if throttle min/max limits should be applied295bool Mode::use_throttle_limits() const296{297#if AP_SCRIPTING_ENABLED298if (plane.nav_scripting_active()) {299return false;300}301#endif302303if (this == &plane.mode_stabilize ||304this == &plane.mode_training ||305this == &plane.mode_acro ||306this == &plane.mode_fbwa ||307this == &plane.mode_autotune) {308// a manual throttle mode309return !plane.g.throttle_passthru_stabilize;310}311312if (is_guided_mode() && plane.guided_throttle_passthru) {313// manual pass through of throttle while in GUIDED314return false;315}316317#if HAL_QUADPLANE_ENABLED318if (quadplane.in_vtol_mode()) {319return quadplane.allow_forward_throttle_in_vtol_mode();320}321#endif322323return true;324}325326// true if voltage correction should be applied to throttle327bool Mode::use_battery_compensation() const328{329#if AP_SCRIPTING_ENABLED330if (plane.nav_scripting_active()) {331return false;332}333#endif334335if (this == &plane.mode_stabilize ||336this == &plane.mode_training ||337this == &plane.mode_acro ||338this == &plane.mode_fbwa ||339this == &plane.mode_autotune) {340// a manual throttle mode341return false;342}343344if (is_guided_mode() && plane.guided_throttle_passthru) {345// manual pass through of throttle while in GUIDED346return false;347}348349#if HAL_QUADPLANE_ENABLED350if (quadplane.in_vtol_mode()) {351return false;352}353#endif354355return true;356}357358359