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/commands_logic.cpp
Views: 1798
#include "Plane.h"12/********************************************************************************/3// Command Event Handlers4/********************************************************************************/5bool Plane::start_command(const AP_Mission::Mission_Command& cmd)6{7// default to non-VTOL loiter8auto_state.vtol_loiter = false;910#if AP_TERRAIN_AVAILABLE11plane.target_altitude.terrain_following_pending = false;12#endif1314// special handling for nav vs non-nav commands15if (AP_Mission::is_nav_cmd(cmd)) {16// set takeoff_complete to true so we don't add extra elevator17// except in a takeoff18auto_state.takeoff_complete = true;1920nav_controller->set_data_is_stale();2122// start non-idle23auto_state.idle_mode = false;2425// reset loiter start time. New command is a new loiter26loiter.start_time_ms = 0;2728AP_Mission::Mission_Command next_nav_cmd;29const uint16_t next_index = mission.get_current_nav_index() + 1;30const bool have_next_cmd = mission.get_next_nav_cmd(next_index, next_nav_cmd);31auto_state.wp_is_land_approach = have_next_cmd && (next_nav_cmd.id == MAV_CMD_NAV_LAND);32#if HAL_QUADPLANE_ENABLED33if (have_next_cmd && quadplane.is_vtol_land(next_nav_cmd.id)) {34auto_state.wp_is_land_approach = false;35}36#endif37}3839switch(cmd.id) {4041case MAV_CMD_NAV_TAKEOFF:42crash_state.is_crashed = false;43#if HAL_QUADPLANE_ENABLED44if (quadplane.is_vtol_takeoff(cmd.id)) {45return quadplane.do_vtol_takeoff(cmd);46}47#endif48do_takeoff(cmd);49break;5051case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint52do_nav_wp(cmd);53break;5455case MAV_CMD_NAV_LAND: // LAND to Waypoint56#if HAL_QUADPLANE_ENABLED57if (quadplane.is_vtol_land(cmd.id)) {58crash_state.is_crashed = false;59return quadplane.do_vtol_land(cmd);60}61#endif62do_land(cmd);63break;6465case MAV_CMD_NAV_LOITER_UNLIM: // Loiter indefinitely66do_loiter_unlimited(cmd);67break;6869case MAV_CMD_NAV_LOITER_TURNS: // Loiter N Times70do_loiter_turns(cmd);71break;7273case MAV_CMD_NAV_LOITER_TIME:74do_loiter_time(cmd);75break;7677case MAV_CMD_NAV_LOITER_TO_ALT:78do_loiter_to_alt(cmd);79break;8081case MAV_CMD_NAV_RETURN_TO_LAUNCH:82set_mode(mode_rtl, ModeReason::MISSION_CMD);83break;8485case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:86do_continue_and_change_alt(cmd);87break;8889case MAV_CMD_NAV_ALTITUDE_WAIT:90do_altitude_wait(cmd);91break;9293#if HAL_QUADPLANE_ENABLED94case MAV_CMD_NAV_VTOL_TAKEOFF:95crash_state.is_crashed = false;96return quadplane.do_vtol_takeoff(cmd);9798case MAV_CMD_NAV_VTOL_LAND:99case MAV_CMD_NAV_PAYLOAD_PLACE:100if (quadplane.landing_with_fixed_wing_spiral_approach()) {101// the user wants to approach the landing in a fixed wing flight mode102// the waypoint will be used as a loiter_to_alt103// after which point the plane will compute the optimal into the wind direction104// and fly in on that direction towards the landing waypoint105// it will then transition to VTOL and do a normal quadplane landing106do_landing_vtol_approach(cmd);107break;108} else {109return quadplane.do_vtol_land(cmd);110}111#endif112113// Conditional commands114115case MAV_CMD_CONDITION_DELAY:116do_wait_delay(cmd);117break;118119case MAV_CMD_CONDITION_DISTANCE:120do_within_distance(cmd);121break;122123// Do commands124125case MAV_CMD_DO_CHANGE_SPEED:126do_change_speed(cmd);127break;128129case MAV_CMD_DO_SET_HOME:130do_set_home(cmd);131break;132133case MAV_CMD_DO_INVERTED_FLIGHT:134if (cmd.p1 == 0 || cmd.p1 == 1) {135auto_state.inverted_flight = (bool)cmd.p1;136gcs().send_text(MAV_SEVERITY_INFO, "Set inverted %u", cmd.p1);137}138break;139140case MAV_CMD_DO_RETURN_PATH_START:141case MAV_CMD_DO_LAND_START:142break;143144case MAV_CMD_DO_AUTOTUNE_ENABLE:145autotune_enable(cmd.p1);146break;147148#if HAL_MOUNT_ENABLED149// Sets the region of interest (ROI) for a sensor set or the150// vehicle itself. This can then be used by the vehicles control151// system to control the vehicle attitude and the attitude of various152// devices such as cameras.153// |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|154case MAV_CMD_DO_SET_ROI:155if (cmd.content.location.alt == 0 && cmd.content.location.lat == 0 && cmd.content.location.lng == 0) {156// switch off the camera tracking if enabled157if (camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {158camera_mount.set_mode_to_default();159}160} else {161// set mount's target location162camera_mount.set_roi_target(cmd.content.location);163}164break;165166case MAV_CMD_DO_MOUNT_CONTROL: // 205167// point the camera to a specified angle168camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false);169break;170#endif171172#if HAL_QUADPLANE_ENABLED173case MAV_CMD_DO_VTOL_TRANSITION:174plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)cmd.content.do_vtol_transition.target_state);175break;176#endif177178#if AP_ICENGINE_ENABLED179case MAV_CMD_DO_ENGINE_CONTROL:180plane.g2.ice_control.engine_control(cmd.content.do_engine_control.start_control,181cmd.content.do_engine_control.cold_start,182cmd.content.do_engine_control.height_delay_cm*0.01f,183cmd.content.do_engine_control.allow_disarmed_start);184break;185#endif186187#if AP_SCRIPTING_ENABLED188case MAV_CMD_NAV_SCRIPT_TIME:189do_nav_script_time(cmd);190break;191#endif192193case MAV_CMD_NAV_DELAY:194mode_auto.do_nav_delay(cmd);195break;196197default:198// unable to use the command, allow the vehicle to try the next command199return false;200}201202return true;203}204205/*******************************************************************************206Verify command Handlers207208Each type of mission element has a "verify" operation. The verify209operation returns true when the mission element has completed and we210should move onto the next mission element.211Return true if we do not recognize the command so that we move on to the next command212*******************************************************************************/213214bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Returns true if command complete215{216switch(cmd.id) {217218case MAV_CMD_NAV_TAKEOFF:219#if HAL_QUADPLANE_ENABLED220if (quadplane.is_vtol_takeoff(cmd.id)) {221return quadplane.verify_vtol_takeoff(cmd);222}223#endif224return verify_takeoff();225226case MAV_CMD_NAV_WAYPOINT:227return verify_nav_wp(cmd);228229case MAV_CMD_NAV_LAND:230#if HAL_QUADPLANE_ENABLED231if (quadplane.is_vtol_land(cmd.id)) {232return quadplane.verify_vtol_land();233}234#endif235if (flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {236return landing.verify_abort_landing(prev_WP_loc, next_WP_loc, current_loc, auto_state.takeoff_altitude_rel_cm, throttle_suppressed);237238} else {239// use rangefinder to correct if possible240bool rangefinder_active = false;241float height = plane.get_landing_height(rangefinder_active);242243// for flare calculations we don't want to use the terrain244// correction as otherwise we will flare early on rising245// ground246height -= auto_state.terrain_correction;247return landing.verify_land(prev_WP_loc, next_WP_loc, current_loc,248height, auto_state.sink_rate, auto_state.wp_proportion, auto_state.last_flying_ms, arming.is_armed(), is_flying(),249rangefinder_active);250}251252case MAV_CMD_NAV_LOITER_UNLIM:253return verify_loiter_unlim(cmd);254255case MAV_CMD_NAV_LOITER_TURNS:256return verify_loiter_turns(cmd);257258case MAV_CMD_NAV_LOITER_TIME:259return verify_loiter_time();260261case MAV_CMD_NAV_LOITER_TO_ALT:262return verify_loiter_to_alt(cmd);263264case MAV_CMD_NAV_RETURN_TO_LAUNCH:265return verify_RTL();266267case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:268return verify_continue_and_change_alt();269270case MAV_CMD_NAV_ALTITUDE_WAIT:271return mode_auto.verify_altitude_wait(cmd);272273#if HAL_QUADPLANE_ENABLED274case MAV_CMD_NAV_VTOL_TAKEOFF:275return quadplane.verify_vtol_takeoff(cmd);276case MAV_CMD_NAV_VTOL_LAND:277case MAV_CMD_NAV_PAYLOAD_PLACE:278if (quadplane.landing_with_fixed_wing_spiral_approach() && !verify_landing_vtol_approach(cmd)) {279// verify_landing_vtol_approach will return true once we have completed the approach,280// in which case we fall over to normal vtol landing code281return false;282} else {283return quadplane.verify_vtol_land();284}285#endif // HAL_QUADPLANE_ENABLED286287// Conditional commands288289case MAV_CMD_CONDITION_DELAY:290return verify_wait_delay();291292case MAV_CMD_CONDITION_DISTANCE:293return verify_within_distance();294295#if AP_SCRIPTING_ENABLED296case MAV_CMD_NAV_SCRIPT_TIME:297return verify_nav_script_time(cmd);298#endif299300case MAV_CMD_NAV_DELAY:301return mode_auto.verify_nav_delay(cmd);302303// do commands (always return true)304case MAV_CMD_DO_CHANGE_SPEED:305case MAV_CMD_DO_SET_HOME:306case MAV_CMD_DO_INVERTED_FLIGHT:307case MAV_CMD_DO_RETURN_PATH_START:308case MAV_CMD_DO_LAND_START:309case MAV_CMD_DO_FENCE_ENABLE:310case MAV_CMD_DO_AUTOTUNE_ENABLE:311case MAV_CMD_DO_SET_CAM_TRIGG_DIST:312case MAV_CMD_DO_SET_ROI:313case MAV_CMD_DO_MOUNT_CONTROL:314case MAV_CMD_DO_VTOL_TRANSITION:315case MAV_CMD_DO_ENGINE_CONTROL:316return true;317318default:319// error message320gcs().send_text(MAV_SEVERITY_WARNING,"Skipping invalid cmd #%i",cmd.id);321// return true if we do not recognize the command so that we move on to the next command322return true;323}324}325326/********************************************************************************/327// Nav (Must) commands328/********************************************************************************/329330void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm)331{332auto_state.next_wp_crosstrack = false;333auto_state.crosstrack = false;334prev_WP_loc = current_loc;335next_WP_loc = calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm);336setup_terrain_target_alt(next_WP_loc);337set_target_altitude_location(next_WP_loc);338339if (aparm.loiter_radius < 0) {340loiter.direction = -1;341} else {342loiter.direction = 1;343}344345setup_glide_slope();346setup_turn_angle();347}348349Location Plane::calc_best_rally_or_home_location(const Location &_current_loc, float rtl_home_alt_amsl_cm) const350{351#if HAL_RALLY_ENABLED352return plane.rally.calc_best_rally_or_home_location(_current_loc, rtl_home_alt_amsl_cm);353#else354Location destination = plane.home;355destination.set_alt_cm(rtl_home_alt_amsl_cm, Location::AltFrame::ABSOLUTE);356return destination;357#endif358}359360/*361start a NAV_TAKEOFF command362*/363void Plane::do_takeoff(const AP_Mission::Mission_Command& cmd)364{365prev_WP_loc = current_loc;366set_next_WP(cmd.content.location);367// pitch in deg, airspeed m/s, throttle %, track WP 1 or 0368auto_state.takeoff_pitch_cd = (int16_t)cmd.p1 * 100;369if (auto_state.takeoff_pitch_cd <= 0) {370// if the mission doesn't specify a pitch use 4 degrees371auto_state.takeoff_pitch_cd = 400;372}373auto_state.takeoff_altitude_rel_cm = next_WP_loc.alt - home.alt;374next_WP_loc.lat = home.lat + 10;375next_WP_loc.lng = home.lng + 10;376auto_state.takeoff_speed_time_ms = 0;377auto_state.takeoff_complete = false; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction.378auto_state.height_below_takeoff_to_level_off_cm = 0;379// Flag also used to override "on the ground" throttle disable380381// zero locked course382steer_state.locked_course_err = 0;383steer_state.hold_course_cd = -1;384#if MODE_AUTOLAND_ENABLED385takeoff_state.initial_direction.initialized = false;386#endif387auto_state.baro_takeoff_alt = barometer.get_altitude();388}389390void Plane::do_nav_wp(const AP_Mission::Mission_Command& cmd)391{392set_next_WP(cmd.content.location);393}394395void Plane::do_land(const AP_Mission::Mission_Command& cmd)396{397set_next_WP(cmd.content.location);398399// configure abort altitude and pitch400// if NAV_LAND has an abort altitude then use it, else use last takeoff, else use 30m401if (cmd.p1 > 0) {402auto_state.takeoff_altitude_rel_cm = (int16_t)cmd.p1 * 100;403} else if (auto_state.takeoff_altitude_rel_cm <= 0) {404auto_state.takeoff_altitude_rel_cm = 3000;405}406407if (auto_state.takeoff_pitch_cd <= 0) {408// If no takeoff command has ever been used, default to a conservative 10deg409auto_state.takeoff_pitch_cd = 1000;410}411412#if AP_RANGEFINDER_ENABLED413// zero rangefinder state, start to accumulate good samples now414memset(&rangefinder_state, 0, sizeof(rangefinder_state));415#endif416417landing.do_land(cmd, relative_altitude);418419if (flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {420// if we were in an abort we need to explicitly move out of the abort state, as it's sticky421set_flight_stage(AP_FixedWing::FlightStage::LAND);422}423}424425#if HAL_QUADPLANE_ENABLED426void Plane::do_landing_vtol_approach(const AP_Mission::Mission_Command& cmd)427{428//set target alt429Location loc = cmd.content.location;430loc.sanitize(current_loc);431set_next_WP(loc);432433vtol_approach_s.approach_stage = VTOLApproach::Stage::LOITER_TO_ALT;434}435#endif436437void Plane::loiter_set_direction_wp(const AP_Mission::Mission_Command& cmd)438{439if (cmd.content.location.loiter_ccw) {440loiter.direction = -1;441} else {442loiter.direction = 1;443}444}445446void Plane::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)447{448Location cmdloc = cmd.content.location;449cmdloc.sanitize(current_loc);450set_next_WP(cmdloc);451loiter_set_direction_wp(cmd);452}453454void Plane::do_loiter_turns(const AP_Mission::Mission_Command& cmd)455{456Location cmdloc = cmd.content.location;457cmdloc.sanitize(current_loc);458set_next_WP(cmdloc);459loiter_set_direction_wp(cmd);460const float turns = cmd.get_loiter_turns();461462loiter.total_cd = (uint32_t)(turns * 36000UL);463condition_value = 1; // used to signify primary turns goal not yet met464}465466void Plane::do_loiter_time(const AP_Mission::Mission_Command& cmd)467{468Location cmdloc = cmd.content.location;469cmdloc.sanitize(current_loc);470set_next_WP(cmdloc);471loiter_set_direction_wp(cmd);472473// we set start_time_ms when we reach the waypoint474loiter.time_max_ms = cmd.p1 * (uint32_t)1000; // convert sec to ms475condition_value = 1; // used to signify primary time goal not yet met476}477478void Plane::do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd)479{480// select heading method. Either mission, gps bearing projection or yaw based481// If prev_WP_loc and next_WP_loc are different then an accurate wp based bearing can482// be computed. However, if we had just changed modes before this, such as an aborted landing483// via mode change, the prev and next wps are the same.484float bearing;485if (!prev_WP_loc.same_latlon_as(next_WP_loc)) {486// use waypoint based bearing, this is the usual case487steer_state.hold_course_cd = -1;488} else if (AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {489// use gps ground course based bearing hold490steer_state.hold_course_cd = -1;491bearing = AP::gps().ground_course();492next_WP_loc.offset_bearing(bearing, 1000); // push it out 1km493} else {494// use yaw based bearing hold495steer_state.hold_course_cd = wrap_360_cd(ahrs.yaw_sensor);496bearing = ahrs.yaw_sensor * 0.01f;497next_WP_loc.offset_bearing(bearing, 1000); // push it out 1km498}499500next_WP_loc.alt = cmd.content.location.alt + home.alt;501condition_value = cmd.p1;502reset_offset_altitude();503}504505void Plane::do_altitude_wait(const AP_Mission::Mission_Command& cmd)506{507// set all servos to trim until we reach altitude or descent speed508auto_state.idle_mode = true;509#if AP_PLANE_GLIDER_PULLUP_ENABLED510mode_auto.pullup.reset();511#endif512}513514void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd)515{516//set target alt517Location loc = cmd.content.location;518loc.sanitize(current_loc);519set_next_WP(loc);520loiter_set_direction_wp(cmd);521522// init to 0, set to 1 when altitude is reached523condition_value = 0;524}525526// do_nav_delay - Delay the next navigation command527void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd)528{529nav_delay.time_start_ms = millis();530531if (cmd.content.nav_delay.seconds > 0) {532// relative delay533nav_delay.time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds534} else {535// absolute delay to utc time536#if AP_RTC_ENABLED537nav_delay.time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0);538#else539nav_delay.time_max_ms = 0;540#endif541}542gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay.time_max_ms/1000));543}544545/********************************************************************************/546// Verify Nav (Must) commands547/********************************************************************************/548bool Plane::verify_takeoff()549{550bool trust_ahrs_yaw = AP::ahrs().initialised();551#if AP_AHRS_DCM_ENABLED552trust_ahrs_yaw |= ahrs.dcm_yaw_initialised();553#endif554if (trust_ahrs_yaw && steer_state.hold_course_cd == -1) {555const float min_gps_speed = GPS_GND_CRS_MIN_SPD;556if (auto_state.takeoff_speed_time_ms == 0 &&557gps.status() >= AP_GPS::GPS_OK_FIX_3D &&558gps.ground_speed() > min_gps_speed &&559hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {560auto_state.takeoff_speed_time_ms = millis();561#if MODE_AUTOLAND_ENABLED562plane.takeoff_state.initial_direction.heading = wrap_360(plane.gps.ground_course() + plane.mode_autoland.landing_dir_off);563takeoff_state.initial_direction.initialized = true;564gcs().send_text(MAV_SEVERITY_INFO, "Autoland direction= %u",int(takeoff_state.initial_direction.heading));565#endif566}567if (auto_state.takeoff_speed_time_ms != 0 &&568millis() - auto_state.takeoff_speed_time_ms >= 2000) {569// once we reach sufficient speed for good GPS course570// estimation we save our current GPS ground course571// corrected for summed yaw to set the take off572// course. This keeps wings level until we are ready to573// rotate, and also allows us to cope with arbitrary574// compass errors for auto takeoff575float takeoff_course = wrap_PI(radians(gps.ground_course())) - steer_state.locked_course_err;576takeoff_course = wrap_PI(takeoff_course);577steer_state.hold_course_cd = wrap_360_cd(degrees(takeoff_course)*100);578gcs().send_text(MAV_SEVERITY_INFO, "Holding course %d at %.1fm/s (%.1f)",579(int)steer_state.hold_course_cd,580(double)gps.ground_speed(),581(double)degrees(steer_state.locked_course_err));582}583}584585if (steer_state.hold_course_cd != -1) {586// call navigation controller for heading hold587nav_controller->update_heading_hold(steer_state.hold_course_cd);588} else {589nav_controller->update_level_flight();590}591592// check for optional takeoff timeout593if (plane.check_takeoff_timeout()) {594mission.reset();595}596597// see if we have reached takeoff altitude598int32_t relative_alt_cm = adjusted_relative_altitude_cm();599if (600relative_alt_cm > auto_state.takeoff_altitude_rel_cm || // altitude reached601plane.check_takeoff_timeout_level_off() // pitch level-off maneuver has timed out602) {603gcs().send_text(MAV_SEVERITY_INFO, "Takeoff complete at %.2fm",604(double)(relative_alt_cm*0.01f));605steer_state.hold_course_cd = -1;606auto_state.takeoff_complete = true;607next_WP_loc = prev_WP_loc = current_loc;608609#if AP_FENCE_ENABLED610plane.fence.auto_enable_fence_after_takeoff();611#endif612613// don't cross-track on completion of takeoff, as otherwise we614// can end up doing too sharp a turn615auto_state.next_wp_crosstrack = false;616return true;617} else {618return false;619}620}621622/*623update navigation for normal mission waypoints. Return true when the624waypoint is complete625*/626bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)627{628steer_state.hold_course_cd = -1;629630// depending on the pass by flag either go to waypoint in regular manner or631// fly past it for set distance along the line of waypoints632Location flex_next_WP_loc = next_WP_loc;633634uint8_t cmd_passby = HIGHBYTE(cmd.p1); // distance in meters to pass beyond the wp635uint8_t cmd_acceptance_distance = LOWBYTE(cmd.p1); // radius in meters to accept reaching the wp636637if (cmd_passby > 0) {638const float dist = prev_WP_loc.get_distance(flex_next_WP_loc);639const float bearing_deg = degrees(prev_WP_loc.get_bearing(flex_next_WP_loc));640641if (is_positive(dist)) {642flex_next_WP_loc.offset_bearing(bearing_deg, cmd_passby);643}644}645646if (auto_state.crosstrack) {647nav_controller->update_waypoint(prev_WP_loc, flex_next_WP_loc);648} else {649nav_controller->update_waypoint(current_loc, flex_next_WP_loc);650}651652// see if the user has specified a maximum distance to waypoint653// If override with p3 - then this is not used as it will overfly badly654if (g.waypoint_max_radius > 0 &&655auto_state.wp_distance > (uint16_t)g.waypoint_max_radius) {656if (current_loc.past_interval_finish_line(prev_WP_loc, flex_next_WP_loc)) {657// this is needed to ensure completion of the waypoint658if (cmd_passby == 0) {659prev_WP_loc = current_loc;660}661}662return false;663}664665float acceptance_distance_m = 0; // default to: if overflown - let it fly up to the point666if (cmd_acceptance_distance > 0) {667// allow user to override acceptance radius668acceptance_distance_m = cmd_acceptance_distance;669} else if (cmd_passby == 0) {670acceptance_distance_m = nav_controller->turn_distance(get_wp_radius(), auto_state.next_turn_angle);671}672const float wp_dist = current_loc.get_distance(flex_next_WP_loc);673if (wp_dist <= acceptance_distance_m) {674gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%i dist %um",675(unsigned)mission.get_current_nav_cmd().index,676(unsigned)current_loc.get_distance(flex_next_WP_loc));677return true;678}679680// have we flown past the waypoint?681if (current_loc.past_interval_finish_line(prev_WP_loc, flex_next_WP_loc)) {682gcs().send_text(MAV_SEVERITY_INFO, "Passed waypoint #%i dist %um",683(unsigned)mission.get_current_nav_cmd().index,684(unsigned)current_loc.get_distance(flex_next_WP_loc));685return true;686}687688return false;689}690691bool Plane::verify_loiter_unlim(const AP_Mission::Mission_Command &cmd)692{693// else use mission radius694update_loiter(cmd.p1);695return false;696}697698bool Plane::verify_loiter_time()699{700bool result = false;701// mission radius is always aparm.loiter_radius702update_loiter(0);703704if (loiter.start_time_ms == 0) {705if (reached_loiter_target() && loiter.sum_cd > 1) {706// we've reached the target, start the timer707loiter.start_time_ms = millis();708}709} else if (condition_value != 0) {710// primary goal, loiter time711if ((millis() - loiter.start_time_ms) > loiter.time_max_ms) {712// primary goal completed, initialize secondary heading goal713condition_value = 0;714result = verify_loiter_heading(true);715}716} else {717// secondary goal, loiter to heading718result = verify_loiter_heading(false);719}720721if (result) {722gcs().send_text(MAV_SEVERITY_INFO,"Loiter time complete");723auto_state.vtol_loiter = false;724}725return result;726}727728bool Plane::verify_loiter_turns(const AP_Mission::Mission_Command &cmd)729{730bool result = false;731uint16_t radius = HIGHBYTE(cmd.p1);732if (cmd.type_specific_bits & (1U<<0)) {733// special storage handling allows for larger radii734radius *= 10;735}736update_loiter(radius);737738// LOITER_TURNS makes no sense as VTOL739auto_state.vtol_loiter = false;740741if (condition_value != 0) {742// primary goal, loiter time743if (loiter.sum_cd > loiter.total_cd && loiter.sum_cd > 1) {744// primary goal completed, initialize secondary heading goal745condition_value = 0;746result = verify_loiter_heading(true);747}748} else {749// secondary goal, loiter to heading750result = verify_loiter_heading(false);751}752753if (result) {754gcs().send_text(MAV_SEVERITY_INFO,"Loiter orbits complete");755}756return result;757}758759/*760verify a LOITER_TO_ALT command. This involves checking we have761reached both the desired altitude and desired heading. The desired762altitude only needs to be reached once.763*/764bool Plane::verify_loiter_to_alt(const AP_Mission::Mission_Command &cmd)765{766bool result = false;767768update_loiter(cmd.p1);769770// condition_value == 0 means alt has never been reached771if (condition_value == 0) {772// primary goal, loiter to alt773if (labs(loiter.sum_cd) > 1 && (loiter.reached_target_alt || loiter.unable_to_acheive_target_alt)) {774// primary goal completed, initialize secondary heading goal775if (loiter.unable_to_acheive_target_alt) {776gcs().send_text(MAV_SEVERITY_INFO,"Loiter to alt was stuck at %d", int(current_loc.alt/100));777}778779condition_value = 1;780result = verify_loiter_heading(true);781}782} else {783// secondary goal, loiter to heading784result = verify_loiter_heading(false);785}786787if (result) {788gcs().send_text(MAV_SEVERITY_INFO,"Loiter to alt complete");789}790return result;791}792793bool Plane::verify_RTL()794{795if (g.rtl_radius < 0) {796loiter.direction = -1;797} else {798loiter.direction = 1;799}800update_loiter(abs(g.rtl_radius));801if (auto_state.wp_distance <= (uint32_t)MAX(get_wp_radius(),0) ||802reached_loiter_target()) {803gcs().send_text(MAV_SEVERITY_INFO,"Reached RTL location");804return true;805} else {806return false;807}808}809810bool Plane::verify_continue_and_change_alt()811{812// is waypoint info not available and heading hold is?813if (prev_WP_loc.same_latlon_as(next_WP_loc) &&814steer_state.hold_course_cd != -1) {815//keep flying the same course with fixed steering heading computed at start if cmd816nav_controller->update_heading_hold(steer_state.hold_course_cd);817}818else {819// Is the next_WP less than 200 m away?820if (current_loc.get_distance(next_WP_loc) < 200.0f) {821//push another 300 m down the line822int32_t next_wp_bearing_cd = prev_WP_loc.get_bearing_to(next_WP_loc);823next_WP_loc.offset_bearing(next_wp_bearing_cd * 0.01f, 300.0f);824}825826//keep flying the same course827nav_controller->update_waypoint(prev_WP_loc, next_WP_loc);828}829830//climbing?831if (condition_value == 1 && adjusted_altitude_cm() >= next_WP_loc.alt) {832return true;833}834//descending?835else if (condition_value == 2 &&836adjusted_altitude_cm() <= next_WP_loc.alt) {837return true;838}839//don't care if we're climbing or descending840else if (labs(adjusted_altitude_cm() - next_WP_loc.alt) <= 500) {841return true;842}843844return false;845}846847/*848see if we have reached altitude or descent speed849*/850bool ModeAuto::verify_altitude_wait(const AP_Mission::Mission_Command &cmd)851{852#if AP_PLANE_GLIDER_PULLUP_ENABLED853if (pullup.in_pullup()) {854return pullup.verify_pullup();855}856#endif857858/*859the target altitude in param1 is always AMSL860*/861const float alt_diff = plane.current_loc.alt*0.01 - cmd.content.altitude_wait.altitude;862bool completed = false;863if (alt_diff > 0) {864gcs().send_text(MAV_SEVERITY_INFO,"Reached altitude");865completed = true;866} else if (cmd.content.altitude_wait.descent_rate > 0 &&867plane.auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) {868gcs().send_text(MAV_SEVERITY_INFO, "Reached descent rate %.1f m/s", (double)plane.auto_state.sink_rate);869completed = true;870}871872if (completed) {873#if AP_PLANE_GLIDER_PULLUP_ENABLED874if (pullup.pullup_start()) {875// we are doing a pullup, ALTITUDE_WAIT not complete until pullup is done876return false;877}878#endif879return true;880}881882const float time_to_alt = alt_diff / MIN(plane.auto_state.sink_rate, -0.01);883884/*885if requested, wiggle servos886887we don't start a wiggle if we expect to release soon as we don't888want the servos to be off trim at the time of release889*/890if (cmd.content.altitude_wait.wiggle_time != 0 &&891(plane.auto_state.sink_rate > 0 || time_to_alt > cmd.content.altitude_wait.wiggle_time*5)) {892if (wiggle.stage == 0 &&893AP_HAL::millis() - wiggle.last_ms > cmd.content.altitude_wait.wiggle_time*1000) {894wiggle.stage = 1;895wiggle.last_ms = AP_HAL::millis();896// idle_wiggle_stage is updated in wiggle_servos()897}898}899900return false;901}902903// verify_nav_delay - check if we have waited long enough904bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd)905{906if (AP::arming().is_armed_and_safety_off()) {907// don't delay while armed, we need a nav controller running908return true;909}910if (millis() - nav_delay.time_start_ms > nav_delay.time_max_ms) {911nav_delay.time_max_ms = 0;912return true;913}914return false;915}916917/********************************************************************************/918// Condition (May) commands919/********************************************************************************/920921void Plane::do_wait_delay(const AP_Mission::Mission_Command& cmd)922{923condition_start = millis();924condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds925}926927void Plane::do_within_distance(const AP_Mission::Mission_Command& cmd)928{929condition_value = cmd.content.distance.meters;930}931932/********************************************************************************/933// Verify Condition (May) commands934/********************************************************************************/935936bool Plane::verify_wait_delay()937{938if ((unsigned)(millis() - condition_start) > (unsigned)condition_value) {939condition_value = 0;940return true;941}942return false;943}944945bool Plane::verify_within_distance()946{947if (auto_state.wp_distance < MAX(condition_value,0)) {948condition_value = 0;949return true;950}951return false;952}953954/********************************************************************************/955// Do (Now) commands956/********************************************************************************/957958void Plane::do_loiter_at_location()959{960if (aparm.loiter_radius < 0) {961loiter.direction = -1;962} else {963loiter.direction = 1;964}965next_WP_loc = current_loc;966}967968bool Plane::do_change_speed(const AP_Mission::Mission_Command& cmd)969{970return do_change_speed(971(uint8_t)cmd.content.speed.speed_type,972cmd.content.speed.target_ms,973cmd.content.speed.throttle_pct974);975}976977bool Plane::do_change_speed(uint8_t speedtype, float speed_target_ms, float throttle_pct)978{979switch (speedtype) {980case 0: // Airspeed981if (is_equal(speed_target_ms, -2.0f)) {982new_airspeed_cm = -1; // return to default airspeed983return true;984} else if ((speed_target_ms >= aparm.airspeed_min.get()) &&985(speed_target_ms <= aparm.airspeed_max.get())) {986new_airspeed_cm = speed_target_ms * 100; //new airspeed target for AUTO or GUIDED modes987gcs().send_text(MAV_SEVERITY_INFO, "Set airspeed %u m/s", (unsigned)speed_target_ms);988return true;989}990break;991case 1: // Ground speed992gcs().send_text(MAV_SEVERITY_INFO, "Set groundspeed %u", (unsigned)speed_target_ms);993aparm.min_groundspeed.set(speed_target_ms);994return true;995}996997if (throttle_pct > 0 && throttle_pct <= 100) {998gcs().send_text(MAV_SEVERITY_INFO, "Set throttle %u", (unsigned)throttle_pct);999aparm.throttle_cruise.set(throttle_pct);1000return true;1001}10021003return false;1004}10051006void Plane::do_set_home(const AP_Mission::Mission_Command& cmd)1007{1008if (cmd.p1 == 1 && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {1009if (!set_home_persistently(gps.location())) {1010// silently ignore error1011}1012} else {1013if (!AP::ahrs().set_home(cmd.content.location)) {1014// silently ignore failure1015}1016}1017}10181019// start_command_callback - callback function called from ap-mission when it begins a new mission command1020// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode1021bool Plane::start_command_callback(const AP_Mission::Mission_Command &cmd)1022{1023if (control_mode == &mode_auto) {1024return start_command(cmd);1025}1026return true;1027}10281029// verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run1030// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode1031bool Plane::verify_command_callback(const AP_Mission::Mission_Command& cmd)1032{1033if (control_mode == &mode_auto) {1034bool cmd_complete = verify_command(cmd);10351036// send message to GCS1037if (cmd_complete) {1038gcs().send_mission_item_reached_message(cmd.index);1039}10401041return cmd_complete;1042}1043return false;1044}10451046// exit_mission_callback - callback function called from ap-mission when the mission has completed1047// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode1048void Plane::exit_mission_callback()1049{1050if (control_mode == &mode_auto) {1051set_mode(mode_rtl, ModeReason::MISSION_END);1052gcs().send_text(MAV_SEVERITY_INFO, "Mission complete, changing mode to RTL");1053}1054}10551056#if HAL_QUADPLANE_ENABLED1057bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)1058{1059const float radius = is_zero(quadplane.fw_land_approach_radius)? aparm.loiter_radius : quadplane.fw_land_approach_radius;1060const int8_t direction = is_negative(radius) ? -1 : 1;1061const float abs_radius = fabsf(radius);10621063loiter.direction = direction;10641065switch (vtol_approach_s.approach_stage) {1066case VTOLApproach::Stage::RTL:1067{1068// fly home and loiter at RTL alt1069nav_controller->update_loiter(cmd.content.location, abs_radius, direction);1070if (plane.reached_loiter_target()) {1071// decend to Q RTL alt1072plane.do_RTL(plane.home.alt + plane.quadplane.qrtl_alt*100UL);1073plane.loiter_angle_reset();1074vtol_approach_s.approach_stage = VTOLApproach::Stage::LOITER_TO_ALT;1075}1076break;1077}1078case VTOLApproach::Stage::LOITER_TO_ALT:1079{1080nav_controller->update_loiter(cmd.content.location, abs_radius, direction);10811082if (labs(loiter.sum_cd) > 1 && (loiter.reached_target_alt || loiter.unable_to_acheive_target_alt)) {1083Vector3f wind = ahrs.wind_estimate();1084vtol_approach_s.approach_direction_deg = degrees(atan2f(-wind.y, -wind.x));1085gcs().send_text(MAV_SEVERITY_INFO, "Selected an approach path of %.1f", (double)vtol_approach_s.approach_direction_deg);1086vtol_approach_s.approach_stage = VTOLApproach::Stage::ENSURE_RADIUS;1087}1088break;1089}1090case VTOLApproach::Stage::ENSURE_RADIUS:1091{1092// validate that the vehicle is at least the expected distance away from the loiter point1093// require an angle total of at least 2 centidegrees, due to special casing of 1 centidegree1094if (((fabsF(cmd.content.location.get_distance(current_loc) - abs_radius) > 5.0f) &&1095(cmd.content.location.get_distance(current_loc) < abs_radius)) ||1096(labs(loiter.sum_cd) < 2)) {1097nav_controller->update_loiter(cmd.content.location, abs_radius, direction);1098break;1099}1100vtol_approach_s.approach_stage = VTOLApproach::Stage::WAIT_FOR_BREAKOUT;1101FALLTHROUGH;1102}1103case VTOLApproach::Stage::WAIT_FOR_BREAKOUT:1104{1105nav_controller->update_loiter(cmd.content.location, radius, direction);11061107const float breakout_direction_rad = radians(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90));11081109// breakout when within 5 degrees of the opposite direction1110if (fabsF(wrap_PI(ahrs.get_yaw() - breakout_direction_rad)) < radians(5.0f)) {1111gcs().send_text(MAV_SEVERITY_INFO, "Starting VTOL land approach path");1112vtol_approach_s.approach_stage = VTOLApproach::Stage::APPROACH_LINE;1113set_next_WP(cmd.content.location);1114// fallthrough1115} else {1116break;1117}1118FALLTHROUGH;1119}1120case VTOLApproach::Stage::APPROACH_LINE:1121{1122// project an apporach path1123Location start = cmd.content.location;1124Location end = cmd.content.location;11251126// project a 1km waypoint to either side of the landing location1127start.offset_bearing(vtol_approach_s.approach_direction_deg + 180, 1000);1128end.offset_bearing(vtol_approach_s.approach_direction_deg, 1000);11291130nav_controller->update_waypoint(start, end);11311132// check if we should move on to the next waypoint1133Location breakout_stopping_loc = cmd.content.location;1134breakout_stopping_loc.offset_bearing(vtol_approach_s.approach_direction_deg + 180, quadplane.stopping_distance());1135const bool past_finish_line = current_loc.past_interval_finish_line(start, breakout_stopping_loc);11361137Location breakout_loc = cmd.content.location;1138breakout_loc.offset_bearing(vtol_approach_s.approach_direction_deg + 180, abs_radius);1139const bool half_radius = current_loc.line_path_proportion(breakout_loc, cmd.content.location) > 0.5;1140bool lined_up = true;1141Vector3f vel_NED;1142if (ahrs.get_velocity_NED(vel_NED)) {1143const Vector2f target_vec = current_loc.get_distance_NE(cmd.content.location);1144const float angle_err = fabsf(wrap_180(degrees(vel_NED.xy().angle(target_vec))));1145lined_up = (angle_err < 30);1146}11471148if (past_finish_line && (lined_up || half_radius)) {1149vtol_approach_s.approach_stage = VTOLApproach::Stage::VTOL_LANDING;1150quadplane.do_vtol_land(cmd);1151// fallthrough1152} else {1153break;1154}1155FALLTHROUGH;1156}1157case VTOLApproach::Stage::VTOL_LANDING:1158// nothing to do here, we should be into the quadplane landing code1159return true;1160}11611162return false;1163}1164#endif // HAL_QUADPLANE_ENABLED11651166bool Plane::verify_loiter_heading(bool init)1167{1168#if HAL_QUADPLANE_ENABLED1169if (quadplane.in_vtol_auto()) {1170// skip heading verify if in VTOL auto1171return true;1172}1173#endif11741175//Get the lat/lon of next Nav waypoint after this one:1176AP_Mission::Mission_Command next_nav_cmd;1177if (! mission.get_next_nav_cmd(mission.get_current_nav_index() + 1,1178next_nav_cmd)) {1179//no next waypoint to shoot for -- go ahead and break out of loiter1180return true;1181}11821183if (init) {1184loiter.sum_cd = 0;1185}11861187return plane.mode_loiter.isHeadingLinedUp(next_WP_loc, next_nav_cmd.content.location);1188}11891190float Plane::get_wp_radius() const1191{1192#if HAL_QUADPLANE_ENABLED1193if (plane.quadplane.in_vtol_mode()) {1194return plane.quadplane.wp_nav->get_wp_radius_cm() * 0.01;1195}1196#endif1197return g.waypoint_radius;1198}11991200#if AP_SCRIPTING_ENABLED1201/*1202support for scripted navigation, with verify operation for completion1203*/1204void Plane::do_nav_script_time(const AP_Mission::Mission_Command& cmd)1205{1206nav_scripting.enabled = true;1207nav_scripting.id++;1208nav_scripting.start_ms = AP_HAL::millis();1209nav_scripting.current_ms = nav_scripting.start_ms;12101211// start with current roll rate, pitch rate and throttle1212nav_scripting.roll_rate_dps = plane.rollController.get_pid_info().target;1213nav_scripting.pitch_rate_dps = plane.pitchController.get_pid_info().target;1214nav_scripting.yaw_rate_dps = degrees(ahrs.get_gyro().z);1215nav_scripting.throttle_pct = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);1216}12171218/*1219wait for scripting to say that the mission item is complete1220*/1221bool Plane::verify_nav_script_time(const AP_Mission::Mission_Command& cmd)1222{1223if (cmd.content.nav_script_time.timeout_s > 0) {1224const uint32_t now = AP_HAL::millis();1225if (now - nav_scripting.start_ms > cmd.content.nav_script_time.timeout_s*1000U) {1226gcs().send_text(MAV_SEVERITY_INFO, "NavScriptTime timed out");1227nav_scripting.enabled = false;1228nav_scripting.rudder_offset_pct = 0;1229nav_scripting.run_yaw_rate_controller = true;1230}1231}1232return !nav_scripting.enabled;1233}12341235// check if we are in a NAV_SCRIPT_* command1236bool Plane::nav_scripting_active(void)1237{1238if (nav_scripting.enabled && AP_HAL::millis() - nav_scripting.current_ms > 1000) {1239// set_target_throttle_rate_rpy has not been called from script in last 1000ms1240nav_scripting.enabled = false;1241nav_scripting.current_ms = 0;1242nav_scripting.rudder_offset_pct = 0;1243nav_scripting.run_yaw_rate_controller = true;1244gcs().send_text(MAV_SEVERITY_INFO, "NavScript time out");1245}1246if (control_mode == &mode_auto &&1247mission.get_current_nav_cmd().id != MAV_CMD_NAV_SCRIPT_TIME) {1248nav_scripting.enabled = false;1249}1250return nav_scripting.enabled;1251}12521253// support for NAV_SCRIPTING mission command1254bool Plane::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)1255{1256if (!nav_scripting_active()) {1257// not in NAV_SCRIPT_TIME1258return false;1259}1260const auto &c = mission.get_current_nav_cmd().content.nav_script_time;1261id = nav_scripting.id;1262cmd = c.command;1263arg1 = c.arg1.get();1264arg2 = c.arg2.get();1265arg3 = c.arg3;1266arg4 = c.arg4;1267return true;1268}12691270// called when script has completed the command1271void Plane::nav_script_time_done(uint16_t id)1272{1273if (id == nav_scripting.id) {1274nav_scripting.enabled = false;1275}1276}12771278// support for NAV_SCRIPTING mission command and aerobatics in other allowed modes1279void Plane::set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps)1280{1281nav_scripting.roll_rate_dps = constrain_float(roll_rate_dps, -g.acro_roll_rate, g.acro_roll_rate);1282nav_scripting.pitch_rate_dps = constrain_float(pitch_rate_dps, -g.acro_pitch_rate, g.acro_pitch_rate);1283nav_scripting.yaw_rate_dps = constrain_float(yaw_rate_dps, -g.acro_yaw_rate, g.acro_yaw_rate);1284nav_scripting.throttle_pct = constrain_float(throttle_pct, aparm.throttle_min, aparm.throttle_max);1285nav_scripting.current_ms = AP_HAL::millis();1286}12871288// support for rudder offset override in aerobatic scripting1289void Plane::set_rudder_offset(float rudder_pct, bool run_yaw_rate_controller)1290{1291nav_scripting.rudder_offset_pct = rudder_pct;1292nav_scripting.run_yaw_rate_controller = run_yaw_rate_controller;1293}12941295// enable NAV_SCRIPTING takeover in modes other than AUTO using script time mission commands1296bool Plane::nav_scripting_enable(uint8_t mode)1297{1298uint8_t current_control_mode = control_mode->mode_number();1299if (current_control_mode == mode) {1300switch (current_control_mode) {1301case Mode::Number::CIRCLE:1302case Mode::Number::STABILIZE:1303case Mode::Number::ACRO:1304case Mode::Number::FLY_BY_WIRE_A:1305case Mode::Number::FLY_BY_WIRE_B:1306case Mode::Number::CRUISE:1307case Mode::Number::LOITER:1308nav_scripting.enabled = true;1309nav_scripting.current_ms = AP_HAL::millis();1310break;1311default:1312nav_scripting.enabled = false;1313}1314} else {1315nav_scripting.enabled = false;1316}1317return nav_scripting.enabled;1318}1319#endif // AP_SCRIPTING_ENABLED13201321/*1322return true if this is a LAND command1323note that we consider a PAYLOAD_PLACE to be a land command as it1324follows the landing logic for quadplanes1325*/1326bool Plane::is_land_command(uint16_t command) const1327{1328return1329command == MAV_CMD_NAV_VTOL_LAND ||1330command == MAV_CMD_NAV_LAND ||1331command == MAV_CMD_NAV_PAYLOAD_PLACE;1332}13331334/*1335return true if in a specific AUTO mission command1336*/1337bool Plane::in_auto_mission_id(uint16_t command) const1338{1339return control_mode == &mode_auto && mission.get_current_nav_id() == command;1340}1341134213431344