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_auto.cpp
Views: 1798
#include "mode.h"1#include "Plane.h"23bool ModeAuto::_enter()4{5#if HAL_QUADPLANE_ENABLED6// check if we should refuse auto mode due to a missing takeoff in7// guided_wait_takeoff state8if (plane.previous_mode == &plane.mode_guided &&9quadplane.guided_wait_takeoff_on_mode_enter) {10if (!plane.mission.starts_with_takeoff_cmd()) {11gcs().send_text(MAV_SEVERITY_ERROR,"Takeoff waypoint required");12quadplane.guided_wait_takeoff = true;13return false;14}15}1617if (plane.quadplane.available() && plane.quadplane.enable == 2) {18plane.auto_state.vtol_mode = true;19} else {20plane.auto_state.vtol_mode = false;21}22#else23plane.auto_state.vtol_mode = false;24#endif25plane.next_WP_loc = plane.prev_WP_loc = plane.current_loc;26// start or resume the mission, based on MIS_AUTORESET27plane.mission.start_or_resume();2829if (hal.util->was_watchdog_armed()) {30if (hal.util->persistent_data.waypoint_num != 0) {31gcs().send_text(MAV_SEVERITY_INFO, "Watchdog: resume WP %u", hal.util->persistent_data.waypoint_num);32plane.mission.set_current_cmd(hal.util->persistent_data.waypoint_num);33hal.util->persistent_data.waypoint_num = 0;34}35}3637#if HAL_SOARING_ENABLED38plane.g2.soaring_controller.init_cruising();39#endif4041return true;42}4344void ModeAuto::_exit()45{46if (plane.mission.state() == AP_Mission::MISSION_RUNNING) {47plane.mission.stop();4849bool restart = plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND;50#if HAL_QUADPLANE_ENABLED51if (plane.quadplane.is_vtol_land(plane.mission.get_current_nav_cmd().id)) {52restart = false;53}54#endif55if (restart) {56plane.landing.restart_landing_sequence();57}58}59plane.auto_state.started_flying_in_auto_ms = 0;60}6162void ModeAuto::update()63{64if (plane.mission.state() != AP_Mission::MISSION_RUNNING) {65// this could happen if AP_Landing::restart_landing_sequence() returns false which would only happen if:66// restart_landing_sequence() is called when not executing a NAV_LAND or there is no previous nav point67plane.set_mode(plane.mode_rtl, ModeReason::MISSION_END);68gcs().send_text(MAV_SEVERITY_INFO, "Aircraft in auto without a running mission");69return;70}7172uint16_t nav_cmd_id = plane.mission.get_current_nav_cmd().id;7374#if HAL_QUADPLANE_ENABLED75if (plane.quadplane.in_vtol_auto()) {76plane.quadplane.control_auto();77return;78}79#endif8081#if AP_PLANE_GLIDER_PULLUP_ENABLED82if (pullup.in_pullup()) {83return;84}85#endif8687if (nav_cmd_id == MAV_CMD_NAV_TAKEOFF ||88(nav_cmd_id == MAV_CMD_NAV_LAND && plane.flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING)) {89plane.takeoff_calc_roll();90plane.takeoff_calc_pitch();91plane.takeoff_calc_throttle();92} else if (nav_cmd_id == MAV_CMD_NAV_LAND) {93plane.calc_nav_roll();94plane.calc_nav_pitch();9596// allow landing to restrict the roll limits97plane.nav_roll_cd = plane.landing.constrain_roll(plane.nav_roll_cd, plane.g.level_roll_limit*100UL);9899if (plane.landing.is_throttle_suppressed()) {100// if landing is considered complete throttle is never allowed, regardless of landing type101SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);102} else {103plane.calc_throttle();104}105#if AP_SCRIPTING_ENABLED106} else if (nav_cmd_id == MAV_CMD_NAV_SCRIPT_TIME) {107// NAV_SCRIPTING has a desired roll and pitch rate and desired throttle108plane.nav_roll_cd = ahrs.roll_sensor;109plane.nav_pitch_cd = ahrs.pitch_sensor;110#endif111} else {112// we are doing normal AUTO flight, the special cases113// are for takeoff and landing114if (nav_cmd_id != MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT) {115plane.steer_state.hold_course_cd = -1;116}117plane.calc_nav_roll();118plane.calc_nav_pitch();119plane.calc_throttle();120}121}122123void ModeAuto::navigate()124{125if (AP::ahrs().home_is_set()) {126plane.mission.update();127}128}129130131bool ModeAuto::does_auto_navigation() const132{133#if AP_SCRIPTING_ENABLED134return (!plane.nav_scripting_active());135#endif136return true;137}138139bool ModeAuto::does_auto_throttle() const140{141#if AP_SCRIPTING_ENABLED142return (!plane.nav_scripting_active());143#endif144return true;145}146147// returns true if the vehicle can be armed in this mode148bool ModeAuto::_pre_arm_checks(size_t buflen, char *buffer) const149{150#if HAL_QUADPLANE_ENABLED151if (plane.quadplane.enabled()) {152if (plane.quadplane.option_is_set(QuadPlane::OPTION::ONLY_ARM_IN_QMODE_OR_AUTO) &&153!plane.quadplane.is_vtol_takeoff(plane.mission.get_current_nav_cmd().id)) {154hal.util->snprintf(buffer, buflen, "not in VTOL takeoff");155return false;156}157if (!plane.mission.starts_with_takeoff_cmd()) {158hal.util->snprintf(buffer, buflen, "missing takeoff waypoint");159return false;160}161}162#endif163// Note that this bypasses the base class checks164return true;165}166167bool ModeAuto::is_landing() const168{169return (plane.flight_stage == AP_FixedWing::FlightStage::LAND);170}171172void ModeAuto::run()173{174#if AP_PLANE_GLIDER_PULLUP_ENABLED175if (pullup.in_pullup()) {176pullup.stabilize_pullup();177return;178}179#endif180181if (plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_ALTITUDE_WAIT) {182183wiggle_servos();184185SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);186SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0);187SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0);188189SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle);190SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleLeft);191SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleRight);192193// Relax attitude control194reset_controllers();195196} else {197// Normal flight, run base class198Mode::run();199200}201}202203204