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/Rover/mode_auto.cpp
Views: 1798
#include "Rover.h"12#define AUTO_GUIDED_SEND_TARGET_MS 100034bool ModeAuto::_enter()5{6// fail to enter auto if no mission commands7if (mission.num_commands() <= 1) {8gcs().send_text(MAV_SEVERITY_NOTICE, "No Mission. Can't set AUTO.");9return false;10}1112// initialise waypoint navigation library13g2.wp_nav.init();1415// other initialisation16auto_triggered = false;1718// clear guided limits19rover.mode_guided.limit_clear();2021// initialise submode to stop or loiter22if (rover.is_boat()) {23if (!start_loiter()) {24start_stop();25}26} else {27start_stop();28}2930// set flag to start mission31waiting_to_start = true;3233return true;34}3536void ModeAuto::_exit()37{38// stop running the mission39if (mission.state() == AP_Mission::MISSION_RUNNING) {40mission.stop();41}42}4344void ModeAuto::update()45{46// check if mission exists (due to being cleared while disarmed in AUTO,47// if no mission, then stop...needs mode change out of AUTO, mission load,48// and change back to AUTO to run a mission at this point49if (!hal.util->get_soft_armed() && mission.num_commands() <= 1) {50start_stop();51}52// start or update mission53if (waiting_to_start) {54// don't start the mission until we have an origin55Location loc;56if (ahrs.get_origin(loc)) {57// start/resume the mission (based on MIS_RESTART parameter)58mission.start_or_resume();59waiting_to_start = false;6061// initialise mission change check62IGNORE_RETURN(mis_change_detector.check_for_mission_change());63}64} else {65// check for mission changes66if (mis_change_detector.check_for_mission_change()) {67// if mission is running restart the current command if it is a waypoint command68if ((mission.state() == AP_Mission::MISSION_RUNNING) && (_submode == SubMode::WP)) {69if (mission.restart_current_nav_cmd()) {70gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto mission changed, restarted command");71} else {72// failed to restart mission for some reason73gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto mission changed but failed to restart command");74}75}76}7778mission.update();79}8081switch (_submode) {82case SubMode::WP:83{84// boats loiter once the waypoint is reached85bool keep_navigating = true;86if (rover.is_boat() && g2.wp_nav.reached_destination() && !g2.wp_nav.is_fast_waypoint()) {87keep_navigating = !start_loiter();88}8990// update navigation controller91if (keep_navigating) {92navigate_to_waypoint();93}94break;95}9697case SubMode::HeadingAndSpeed:98{99if (!_reached_heading) {100// run steering and throttle controllers101calc_steering_to_heading(_desired_yaw_cd);102calc_throttle(calc_speed_nudge(_desired_speed, is_negative(_desired_speed)), true);103// check if we have reached within 5 degrees of target104_reached_heading = (fabsf(_desired_yaw_cd - ahrs.yaw_sensor) < 500);105} else {106// we have reached the destination so stay here107if (rover.is_boat()) {108if (!start_loiter()) {109stop_vehicle();110}111} else {112stop_vehicle();113}114}115break;116}117118case SubMode::RTL:119rover.mode_rtl.update();120break;121122case SubMode::Loiter:123rover.mode_loiter.update();124break;125126case SubMode::Guided:127{128// send location target to offboard navigation system129send_guided_position_target();130rover.mode_guided.update();131break;132}133134case SubMode::Stop:135stop_vehicle();136break;137138case SubMode::NavScriptTime:139rover.mode_guided.update();140break;141142case SubMode::Circle:143g2.mode_circle.update();144break;145}146}147148void ModeAuto::calc_throttle(float target_speed, bool avoidance_enabled)149{150// If not autostarting set the throttle to minimum151if (!check_trigger()) {152stop_vehicle();153return;154}155Mode::calc_throttle(target_speed, avoidance_enabled);156}157158// return heading (in degrees) to target destination (aka waypoint)159float ModeAuto::wp_bearing() const160{161switch (_submode) {162case SubMode::WP:163return g2.wp_nav.wp_bearing_cd() * 0.01f;164case SubMode::HeadingAndSpeed:165case SubMode::Stop:166return 0.0f;167case SubMode::RTL:168return rover.mode_rtl.wp_bearing();169case SubMode::Loiter:170return rover.mode_loiter.wp_bearing();171case SubMode::Guided:172case SubMode::NavScriptTime:173return rover.mode_guided.wp_bearing();174case SubMode::Circle:175return g2.mode_circle.wp_bearing();176}177178// this line should never be reached179return 0.0f;180}181182// return short-term target heading in degrees (i.e. target heading back to line between waypoints)183float ModeAuto::nav_bearing() const184{185switch (_submode) {186case SubMode::WP:187return g2.wp_nav.nav_bearing_cd() * 0.01f;188case SubMode::HeadingAndSpeed:189case SubMode::Stop:190return 0.0f;191case SubMode::RTL:192return rover.mode_rtl.nav_bearing();193case SubMode::Loiter:194return rover.mode_loiter.nav_bearing();195case SubMode::Guided:196case SubMode::NavScriptTime:197return rover.mode_guided.nav_bearing();198case SubMode::Circle:199return g2.mode_circle.nav_bearing();200}201202// this line should never be reached203return 0.0f;204}205206// return cross track error (i.e. vehicle's distance from the line between waypoints)207float ModeAuto::crosstrack_error() const208{209switch (_submode) {210case SubMode::WP:211return g2.wp_nav.crosstrack_error();212case SubMode::HeadingAndSpeed:213case SubMode::Stop:214return 0.0f;215case SubMode::RTL:216return rover.mode_rtl.crosstrack_error();217case SubMode::Loiter:218return rover.mode_loiter.crosstrack_error();219case SubMode::Guided:220case SubMode::NavScriptTime:221return rover.mode_guided.crosstrack_error();222case SubMode::Circle:223return g2.mode_circle.crosstrack_error();224}225226// this line should never be reached227return 0.0f;228}229230// return desired lateral acceleration231float ModeAuto::get_desired_lat_accel() const232{233switch (_submode) {234case SubMode::WP:235return g2.wp_nav.get_lat_accel();236case SubMode::HeadingAndSpeed:237case SubMode::Stop:238return 0.0f;239case SubMode::RTL:240return rover.mode_rtl.get_desired_lat_accel();241case SubMode::Loiter:242return rover.mode_loiter.get_desired_lat_accel();243case SubMode::Guided:244case SubMode::NavScriptTime:245return rover.mode_guided.get_desired_lat_accel();246case SubMode::Circle:247return g2.mode_circle.get_desired_lat_accel();248}249250// this line should never be reached251return 0.0f;252}253254// return distance (in meters) to destination255float ModeAuto::get_distance_to_destination() const256{257switch (_submode) {258case SubMode::WP:259return _distance_to_destination;260case SubMode::HeadingAndSpeed:261case SubMode::Stop:262// no valid distance so return zero263return 0.0f;264case SubMode::RTL:265return rover.mode_rtl.get_distance_to_destination();266case SubMode::Loiter:267return rover.mode_loiter.get_distance_to_destination();268case SubMode::Guided:269case SubMode::NavScriptTime:270return rover.mode_guided.get_distance_to_destination();271case SubMode::Circle:272return g2.mode_circle.get_distance_to_destination();273}274275// this line should never be reached276return 0.0f;277}278279// get desired location280bool ModeAuto::get_desired_location(Location& destination) const281{282switch (_submode) {283case SubMode::WP:284if (g2.wp_nav.is_destination_valid()) {285destination = g2.wp_nav.get_oa_destination();286return true;287}288return false;289case SubMode::HeadingAndSpeed:290case SubMode::Stop:291// no desired location for this submode292return false;293case SubMode::RTL:294return rover.mode_rtl.get_desired_location(destination);295case SubMode::Loiter:296return rover.mode_loiter.get_desired_location(destination);297case SubMode::Guided:298case SubMode::NavScriptTime:299return rover.mode_guided.get_desired_location(destination);300case SubMode::Circle:301return g2.mode_circle.get_desired_location(destination);302}303304// we should never reach here but just in case305return false;306}307308// set desired location to drive to309bool ModeAuto::set_desired_location(const Location &destination, Location next_destination)310{311// call parent312if (!Mode::set_desired_location(destination, next_destination)) {313return false;314}315316_submode = SubMode::WP;317318return true;319}320321// return true if vehicle has reached or even passed destination322bool ModeAuto::reached_destination() const323{324switch (_submode) {325case SubMode::WP:326return g2.wp_nav.reached_destination();327break;328case SubMode::HeadingAndSpeed:329case SubMode::Stop:330// always return true because this is the safer option to allow missions to continue331return true;332break;333case SubMode::RTL:334return rover.mode_rtl.reached_destination();335break;336case SubMode::Loiter:337return rover.mode_loiter.reached_destination();338break;339case SubMode::Guided:340case SubMode::NavScriptTime:341return rover.mode_guided.reached_destination();342case SubMode::Circle:343return g2.mode_circle.reached_destination();344}345346// we should never reach here but just in case, return true to allow missions to continue347return true;348}349350// set desired speed in m/s351bool ModeAuto::set_desired_speed(float speed)352{353switch (_submode) {354case SubMode::WP:355case SubMode::Stop:356return g2.wp_nav.set_speed_max(speed);357case SubMode::HeadingAndSpeed:358_desired_speed = speed;359return true;360case SubMode::RTL:361return rover.mode_rtl.set_desired_speed(speed);362case SubMode::Loiter:363return rover.mode_loiter.set_desired_speed(speed);364case SubMode::Guided:365case SubMode::NavScriptTime:366return rover.mode_guided.set_desired_speed(speed);367case SubMode::Circle:368return g2.mode_circle.set_desired_speed(speed);369}370return false;371}372373// start RTL (within auto)374void ModeAuto::start_RTL()375{376if (rover.mode_rtl.enter()) {377_submode = SubMode::RTL;378}379}380381// lua scripts use this to retrieve the contents of the active command382bool ModeAuto::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)383{384#if AP_SCRIPTING_ENABLED385if (_submode == SubMode::NavScriptTime) {386id = nav_scripting.id;387cmd = nav_scripting.command;388arg1 = nav_scripting.arg1;389arg2 = nav_scripting.arg2;390arg3 = nav_scripting.arg3;391arg4 = nav_scripting.arg4;392return true;393}394#endif395return false;396}397398// lua scripts use this to indicate when they have complete the command399void ModeAuto::nav_script_time_done(uint16_t id)400{401#if AP_SCRIPTING_ENABLED402if ((_submode == SubMode::NavScriptTime) && (id == nav_scripting.id)) {403nav_scripting.done = true;404}405#endif406}407408// check for triggering of start of auto mode409bool ModeAuto::check_trigger(void)410{411// check for user pressing the auto trigger to off412if (auto_triggered && g.auto_trigger_pin != -1 && rover.check_digital_pin(g.auto_trigger_pin) == 1) {413gcs().send_text(MAV_SEVERITY_WARNING, "AUTO triggered off");414auto_triggered = false;415return false;416}417418// if already triggered, then return true, so you don't419// need to hold the switch down420if (auto_triggered) {421return true;422}423424// return true if auto trigger and kickstart are disabled425if (g.auto_trigger_pin == -1 && is_zero(g.auto_kickstart)) {426// no trigger configured - let's go!427auto_triggered = true;428return true;429}430431// check if trigger pin has been pushed432if (g.auto_trigger_pin != -1 && rover.check_digital_pin(g.auto_trigger_pin) == 0) {433gcs().send_text(MAV_SEVERITY_WARNING, "Triggered AUTO with pin");434auto_triggered = true;435return true;436}437438// check if mission is started by giving vehicle a kick with acceleration > AUTO_KICKSTART439if (!is_zero(g.auto_kickstart)) {440const float xaccel = rover.ins.get_accel().x;441if (xaccel >= g.auto_kickstart) {442gcs().send_text(MAV_SEVERITY_WARNING, "Triggered AUTO xaccel=%.1f", static_cast<double>(xaccel));443auto_triggered = true;444return true;445}446}447448return false;449}450451bool ModeAuto::start_loiter()452{453if (rover.mode_loiter.enter()) {454_submode = SubMode::Loiter;455return true;456}457return false;458}459460// hand over control to external navigation controller in AUTO mode461void ModeAuto::start_guided(const Location& loc)462{463if (rover.mode_guided.enter()) {464_submode = SubMode::Guided;465466// initialise guided start time and position as reference for limit checking467rover.mode_guided.limit_init_time_and_location();468469// sanity check target location470if ((loc.lat != 0) || (loc.lng != 0)) {471guided_target.loc = loc;472guided_target.loc.sanitize(rover.current_loc);473guided_target.valid = true;474} else {475guided_target.valid = false;476}477}478}479480// start stopping vehicle as quickly as possible481void ModeAuto::start_stop()482{483_submode = SubMode::Stop;484}485486// send latest position target to offboard navigation system487void ModeAuto::send_guided_position_target()488{489if (!guided_target.valid) {490return;491}492493// send at maximum of 1hz494const uint32_t now_ms = AP_HAL::millis();495if ((guided_target.last_sent_ms == 0) || (now_ms - guided_target.last_sent_ms > AUTO_GUIDED_SEND_TARGET_MS)) {496guided_target.last_sent_ms = now_ms;497498// get system id and component id of offboard navigation system499uint8_t sysid;500uint8_t compid;501mavlink_channel_t chan;502if (GCS_MAVLINK::find_by_mavtype(MAV_TYPE_ONBOARD_CONTROLLER, sysid, compid, chan)) {503gcs().chan(chan-MAVLINK_COMM_0)->send_set_position_target_global_int(sysid, compid, guided_target.loc);504}505}506507}508509/********************************************************************************/510// Command Event Handlers511/********************************************************************************/512bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)513{514switch (cmd.id) {515case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint516return do_nav_wp(cmd, false);517518case MAV_CMD_NAV_RETURN_TO_LAUNCH:519do_RTL();520break;521522case MAV_CMD_NAV_LOITER_UNLIM: // Loiter indefinitely523case MAV_CMD_NAV_LOITER_TIME: // Loiter for specified time524return do_nav_wp(cmd, true);525526case MAV_CMD_NAV_LOITER_TURNS:527return do_circle(cmd);528529case MAV_CMD_NAV_GUIDED_ENABLE: // accept navigation commands from external nav computer530do_nav_guided_enable(cmd);531break;532533case MAV_CMD_NAV_SET_YAW_SPEED:534do_nav_set_yaw_speed(cmd);535break;536537case MAV_CMD_NAV_DELAY: // 93 Delay the next navigation command538do_nav_delay(cmd);539break;540541#if AP_SCRIPTING_ENABLED542case MAV_CMD_NAV_SCRIPT_TIME:543do_nav_script_time(cmd);544break;545#endif546547// Conditional commands548case MAV_CMD_CONDITION_DELAY:549do_wait_delay(cmd);550break;551552case MAV_CMD_CONDITION_DISTANCE:553do_within_distance(cmd);554break;555556// Do commands557case MAV_CMD_DO_CHANGE_SPEED:558do_change_speed(cmd);559break;560561case MAV_CMD_DO_SET_HOME:562do_set_home(cmd);563break;564565#if HAL_MOUNT_ENABLED566// Sets the region of interest (ROI) for a sensor set or the567// vehicle itself. This can then be used by the vehicles control568// system to control the vehicle attitude and the attitude of various569// devices such as cameras.570// |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|571case MAV_CMD_DO_SET_ROI:572if (cmd.content.location.alt == 0 && cmd.content.location.lat == 0 && cmd.content.location.lng == 0) {573// switch off the camera tracking if enabled574if (rover.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {575rover.camera_mount.set_mode_to_default();576}577} else {578// send the command to the camera mount579rover.camera_mount.set_roi_target(cmd.content.location);580}581break;582#endif583584case MAV_CMD_DO_SET_REVERSE:585do_set_reverse(cmd);586break;587588case MAV_CMD_DO_GUIDED_LIMITS:589do_guided_limits(cmd);590break;591592default:593// return false for unhandled commands594return false;595}596597// if we got this far we must have been successful598return true;599}600601// exit_mission - callback function called from ap-mission when the mission has completed602void ModeAuto::exit_mission()603{604// play a tone605AP_Notify::events.mission_complete = 1;606// send message607gcs().send_text(MAV_SEVERITY_NOTICE, "Mission Complete");608609switch ((DoneBehaviour)g2.mis_done_behave) {610case DoneBehaviour::HOLD:611// the default "start_stop" behaviour is used612break;613case DoneBehaviour::LOITER:614if (start_loiter()) {615return;616}617break;618case DoneBehaviour::ACRO:619if (rover.set_mode(rover.mode_acro, ModeReason::MISSION_END)) {620return;621}622break;623case DoneBehaviour::MANUAL:624if (rover.set_mode(rover.mode_manual, ModeReason::MISSION_END)) {625return;626}627break;628}629630start_stop();631}632633// verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run634// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode635bool ModeAuto::verify_command_callback(const AP_Mission::Mission_Command& cmd)636{637const bool cmd_complete = verify_command(cmd);638639// send message to GCS640if (cmd_complete) {641gcs().send_mission_item_reached_message(cmd.index);642}643644return cmd_complete;645}646647/*******************************************************************************648Verify command Handlers649650Each type of mission element has a "verify" operation. The verify651operation returns true when the mission element has completed and we652should move onto the next mission element.653Return true if we do not recognize the command so that we move on to the next command654*******************************************************************************/655656bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)657{658switch (cmd.id) {659case MAV_CMD_NAV_WAYPOINT:660return verify_nav_wp(cmd);661662case MAV_CMD_NAV_RETURN_TO_LAUNCH:663return verify_RTL();664665case MAV_CMD_NAV_LOITER_UNLIM:666return verify_loiter_unlimited(cmd);667668case MAV_CMD_NAV_LOITER_TURNS:669return verify_circle(cmd);670671case MAV_CMD_NAV_LOITER_TIME:672return verify_loiter_time(cmd);673674case MAV_CMD_NAV_GUIDED_ENABLE:675return verify_nav_guided_enable(cmd);676677case MAV_CMD_NAV_DELAY:678return verify_nav_delay(cmd);679680#if AP_SCRIPTING_ENABLED681case MAV_CMD_NAV_SCRIPT_TIME:682return verify_nav_script_time();683#endif684685case MAV_CMD_CONDITION_DELAY:686return verify_wait_delay();687688case MAV_CMD_CONDITION_DISTANCE:689return verify_within_distance();690691case MAV_CMD_NAV_SET_YAW_SPEED:692return verify_nav_set_yaw_speed();693694// do commands (always return true)695case MAV_CMD_DO_CHANGE_SPEED:696case MAV_CMD_DO_SET_HOME:697case MAV_CMD_DO_SET_CAM_TRIGG_DIST:698case MAV_CMD_DO_SET_ROI:699case MAV_CMD_DO_SET_REVERSE:700case MAV_CMD_DO_FENCE_ENABLE:701case MAV_CMD_DO_GUIDED_LIMITS:702return true;703704default:705// error message706gcs().send_text(MAV_SEVERITY_WARNING, "Skipping invalid cmd #%i", cmd.id);707// return true if we do not recognize the command so that we move on to the next command708return true;709}710}711712/********************************************************************************/713// Nav (Must) commands714/********************************************************************************/715716void ModeAuto::do_RTL(void)717{718// start rtl in auto mode719start_RTL();720}721722bool ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool always_stop_at_destination)723{724// retrieve and sanitize target location725Location cmdloc = cmd.content.location;726cmdloc.sanitize(rover.current_loc);727728// delayed stored in p1 in seconds729loiter_duration = ((int16_t) cmd.p1 < 0) ? 0 : cmd.p1;730loiter_start_time = 0;731if (loiter_duration > 0) {732always_stop_at_destination = true;733}734735// do not add next wp if there are no more navigation commands736AP_Mission::Mission_Command next_cmd;737if (always_stop_at_destination || !mission.get_next_nav_cmd(cmd.index+1, next_cmd)) {738// single destination739if (!set_desired_location(cmdloc)) {740return false;741}742} else {743// retrieve and sanitize next destination location744Location next_cmdloc = next_cmd.content.location;745next_cmdloc.sanitize(cmdloc);746if (!set_desired_location(cmdloc, next_cmdloc)) {747return false;748}749}750751// just starting so we haven't previously reached the waypoint752previously_reached_wp = false;753754return true;755}756757// do_nav_delay - Delay the next navigation command758void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd)759{760nav_delay_time_start_ms = millis();761762// boats loiter, cars and balancebots stop763if (rover.is_boat()) {764if (!start_loiter()) {765start_stop();766}767} else {768start_stop();769}770771if (cmd.content.nav_delay.seconds > 0) {772// relative delay773nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds774} else {775// absolute delay to utc time776#if AP_RTC_ENABLED777nav_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);778#else779nav_delay_time_max_ms = 0;780#endif781}782gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000));783}784785// start guided within auto to allow external navigation system to control vehicle786void ModeAuto::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd)787{788if (cmd.p1 > 0) {789start_guided(cmd.content.location);790}791}792793// do_set_yaw_speed - turn to a specified heading and achieve a given speed794void ModeAuto::do_nav_set_yaw_speed(const AP_Mission::Mission_Command& cmd)795{796float desired_heading_cd;797798// get final angle, 1 = Relative, 0 = Absolute799if (cmd.content.set_yaw_speed.relative_angle > 0) {800// relative angle801desired_heading_cd = wrap_180_cd(ahrs.yaw_sensor + cmd.content.set_yaw_speed.angle_deg * 100.0f);802} else {803// absolute angle804desired_heading_cd = cmd.content.set_yaw_speed.angle_deg * 100.0f;805}806807// set targets808const float speed_max = g2.wp_nav.get_default_speed();809_desired_speed = constrain_float(cmd.content.set_yaw_speed.speed, -speed_max, speed_max);810_desired_yaw_cd = desired_heading_cd;811_reached_heading = false;812_submode = SubMode::HeadingAndSpeed;813}814815/********************************************************************************/816// Verify Nav (Must) commands817/********************************************************************************/818bool ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd)819{820// exit immediately if we haven't reached the destination821if (!reached_destination()) {822return false;823}824825// Check if this is the first time we have noticed reaching the waypoint826if (!previously_reached_wp) {827previously_reached_wp = true;828829// check if we are loitering at this waypoint - the message sent to the GCS is different830if (loiter_duration > 0) {831// send message including loiter time832gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u. Loiter for %u seconds",833(unsigned int)cmd.index,834(unsigned int)loiter_duration);835// record the current time i.e. start timer836loiter_start_time = millis();837} else {838// send simpler message to GCS839gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u", (unsigned int)cmd.index);840}841}842843// Check if we have loitered long enough844if (loiter_duration == 0) {845return true;846} else {847return (((millis() - loiter_start_time) / 1000) >= loiter_duration);848}849}850851// verify_nav_delay - check if we have waited long enough852bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd)853{854if (millis() - nav_delay_time_start_ms > nav_delay_time_max_ms) {855nav_delay_time_max_ms = 0;856return true;857}858859return false;860}861862bool ModeAuto::verify_RTL() const863{864return reached_destination();865}866867bool ModeAuto::verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd)868{869verify_nav_wp(cmd);870return false;871}872873// verify_loiter_time - check if we have loitered long enough874bool ModeAuto::verify_loiter_time(const AP_Mission::Mission_Command& cmd)875{876const bool result = verify_nav_wp(cmd);877if (result) {878gcs().send_text(MAV_SEVERITY_WARNING, "Finished active loiter");879}880return result;881}882883// check if guided has completed884bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)885{886// if we failed to enter guided or this command disables guided887// return true so we move to next command888if (_submode != SubMode::Guided || cmd.p1 == 0) {889return true;890}891892// if a location target was set, return true once vehicle is close893if (guided_target.valid) {894if (rover.current_loc.get_distance(guided_target.loc) <= g2.wp_nav.get_radius()) {895return true;896}897}898899// guided command complete once a limit is breached900return rover.mode_guided.limit_breached();901}902903// verify_yaw - return true if we have reached the desired heading904bool ModeAuto::verify_nav_set_yaw_speed()905{906if (_submode == SubMode::HeadingAndSpeed) {907return _reached_heading;908}909// we should never reach here but just in case, return true to allow missions to continue910return true;911}912913bool ModeAuto::do_circle(const AP_Mission::Mission_Command& cmd)914{915// retrieve and sanitize target location916Location circle_center = cmd.content.location;917circle_center.sanitize(rover.current_loc);918919// calculate radius920uint16_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1921if (cmd.id == MAV_CMD_NAV_LOITER_TURNS &&922cmd.type_specific_bits & (1U << 0)) {923// special storage handling allows for larger radii924circle_radius_m *= 10;925}926927// initialise circle mode928if (g2.mode_circle.set_center(circle_center, circle_radius_m, cmd.content.location.loiter_ccw)) {929_submode = SubMode::Circle;930return true;931}932return false;933}934935bool ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd)936{937const float turns = cmd.get_loiter_turns();938// check if we have completed circling939return ((g2.mode_circle.get_angle_total_rad() / M_2PI) >= turns);940}941942/********************************************************************************/943// Condition (May) commands944/********************************************************************************/945946void ModeAuto::do_wait_delay(const AP_Mission::Mission_Command& cmd)947{948condition_start = millis();949condition_value = static_cast<int32_t>(cmd.content.delay.seconds * 1000); // convert seconds to milliseconds950}951952void ModeAuto::do_within_distance(const AP_Mission::Mission_Command& cmd)953{954condition_value = cmd.content.distance.meters;955}956957/********************************************************************************/958// Verify Condition (May) commands959/********************************************************************************/960961bool ModeAuto::verify_wait_delay()962{963if (static_cast<uint32_t>(millis() - condition_start) > static_cast<uint32_t>(condition_value)) {964condition_value = 0;965return true;966}967return false;968}969970bool ModeAuto::verify_within_distance()971{972if (get_distance_to_destination() < condition_value) {973condition_value = 0;974return true;975}976return false;977}978979980/********************************************************************************/981// Do (Now) commands982/********************************************************************************/983984void ModeAuto::do_change_speed(const AP_Mission::Mission_Command& cmd)985{986// set speed for active mode987if (set_desired_speed(cmd.content.speed.target_ms)) {988gcs().send_text(MAV_SEVERITY_INFO, "speed: %.1f m/s", static_cast<double>(cmd.content.speed.target_ms));989}990}991992void ModeAuto::do_set_home(const AP_Mission::Mission_Command& cmd)993{994if (cmd.p1 == 1 && rover.have_position) {995if (!rover.set_home_to_current_location(false)) {996// ignored...997}998} else {999if (!rover.set_home(cmd.content.location, false)) {1000// ignored...1001}1002}1003}10041005void ModeAuto::do_set_reverse(const AP_Mission::Mission_Command& cmd)1006{1007set_reversed(cmd.p1 == 1);1008}10091010// set timeout and position limits for guided within auto1011void ModeAuto::do_guided_limits(const AP_Mission::Mission_Command& cmd)1012{1013rover.mode_guided.limit_set(1014cmd.p1 * 1000, // convert seconds to ms1015cmd.content.guided_limits.horiz_max);1016}10171018#if AP_SCRIPTING_ENABLED1019// start accepting position, velocity and acceleration targets from lua scripts1020void ModeAuto::do_nav_script_time(const AP_Mission::Mission_Command& cmd)1021{1022// call regular guided flight mode initialisation1023if (rover.mode_guided.enter()) {1024_submode = SubMode::NavScriptTime;1025nav_scripting.done = false;1026nav_scripting.id++;1027nav_scripting.start_ms = millis();1028nav_scripting.command = cmd.content.nav_script_time.command;1029nav_scripting.timeout_s = cmd.content.nav_script_time.timeout_s;1030nav_scripting.arg1 = cmd.content.nav_script_time.arg1.get();1031nav_scripting.arg2 = cmd.content.nav_script_time.arg2.get();1032nav_scripting.arg3 = cmd.content.nav_script_time.arg3;1033nav_scripting.arg4 = cmd.content.nav_script_time.arg4;1034} else {1035// for safety we set nav_scripting to done to protect against the mission getting stuck1036nav_scripting.done = true;1037}1038}10391040// check if verify_nav_script_time command has completed1041bool ModeAuto::verify_nav_script_time()1042{1043// if done or timeout then return true1044if (nav_scripting.done ||1045((nav_scripting.timeout_s > 0) &&1046(AP_HAL::millis() - nav_scripting.start_ms) > (nav_scripting.timeout_s * 1000))) {1047return true;1048}1049return false;1050}1051#endif105210531054