AUTO mode without waypoint

Hello everyone,

I have got a log going to AUTO mode but we did not had any waypoint file. No mission was planned or stored in ardupilot. What does it suppose to do?

Off the top of my head, it does RTL. Can anyone confirm?

If there is no mission loaded, I believe it will just show a mode change error in the log, and it will not do anything.

// auto_init - initialise auto controller
bool Copter::auto_init(bool ignore_checks)
{
    if ((position_ok() && mission.num_commands() > 1) || ignore_checks) {
    [... do auto mission startup things....]
        return true;
    }else{
        return false;
    }
}

It returns a mode change error…

@Eosbandi That appears to come from ArduCopter, but this is the ArduPlane sub-forum, so I suspect you’d need to check that code instead?

Indeed… my bad.

Interestingly, in ArduPlane it does RTL…

exit_mission_callback is called when a mission is completed, and mission completed is set immediately when mode changes to AUTO but cannot fetch mission command…

void Plane::exit_mission_callback()
{
    if (control_mode == AUTO) {
        set_mode(RTL, MODE_REASON_MISSION_END);
        gcs_send_text_fmt(MAV_SEVERITY_INFO, "Mission complete, changing mode to RTL");
    }
}

Thanks for your replies @hunt0r and @Eosbandi. This query belongs to a flight failure blog generated by me. I was looking for the cause of failure of this flight.(Link: Data flash log is missing for certain duration). Unintentionally plane goes to AUTO mode and since no waypoint or flight plane was there, flight goes to RTL mode according to the codebase as @Eosbandi has already verified. But I did not see any mode change to RTL from AUTO in HEARTBEAT of MAVLINK messages ‘Custom_mode’ field of .tlog of the same discussion. Point here to go for .tlog file was that ardupilot failed to log data for around 7s duration, which is again a strange thing. So, my questions are -

  1. Is there a particular duration for checking for 1st waypoint? If it is so how much duration is it? What the plane will do during this period of time? This case is very rare I know. Because checking waypoint will not take couple of seconds, so mode change also will be quick. But in this flight case plane was in AUTO mode for about 5s.
  2. If mode change has happened it should have logged in Custom_mode message of Mavlink Heartbeat. But it did not logged. Why that happened? Is it a normal behaviour that Custom_mode will not capture RTL mode change from AUTO? If not, why it failed? Or why it will take more than 5s to log this mode change?

For your verification I have given plot for Custom_mode Mavlink Heartbeat message.

Figure marker : Black = Manual, Green = FBWA, Blue = AUTOTUNE, Yellow = AUTO, Red = Loiter

Plane does not reject mode change requests, it always does best-effort. So, flying in AUTO without a mission is treated the same as coming to the end of a mission - switch to RTL.

There’s a developer issue that we can use to track this type of thing.

Thanks @MagicRuB. According to you, plane will still show AUTO mode and it will continue to behave as in RTL mode, basically what arduplane does after completion of a mission - return to home point and continue RTL.

Thank you very much all of you.

It does not show AUTO mode, it switches to RTL mode.