Mission Mode

Mission mode causes the vehicle to execute a predefined autonomous mission (flight plan) that has been uploaded to the flight controller. The mission is typically created and uploaded with a Ground Control Station (GCS) application like QGroundControl (QGC).

  • This mode requires 3d position information (e.g. GPS).
  • The vehicle must be armed before this mode can be engaged.
  • This mode is automatic - no user intervention is required to control the vehicle.
  • RC control switches can be used to change flight modes on any vehicle. RC stick movement will by default change the vehicle to Position mode when flying as a multicopter unless handling a critical battery failsafe (stick movement is ignored for fixed-wing flight).

Description

Missions are usually created in a ground control station (e.g. QGroundControl) and uploaded prior to launch. They may also be created by a developer API, and/or uploaded in flight.

Individual mission commands are handled in a way that is appropriate for each vehicle's flight characteristics (for example loiter is implemented as hover for copter and circle for fixed-wing). VTOL vehicles follow the behavior and parameters of fixed-wing when in FW mode, and of copter when in MC mode.

Missions are uploaded onto a SD card that needs to be inserted before booting up the autopilot.

At high level all vehicle types behave in the same way when MISSION mode is engaged:

  1. If a mission is stored and PX4 is flying it will execute the mission/flight plan from the current step.
  2. If a mission is stored and PX4 is landed:
    • On copters PX4 will execute the mission/flight plan. If the mission does not have a TAKEOFF command then PX4 will fly the vehicle to the minimum altitude before executing the remainder of the flight plan from the current step.
    • On fixed-wing vehicles PX4 will not automatically take off (the autopilot will detect the lack of movement and set the throttle to zero). The vehicle may start executing the mission if hand- or catapult- launched while in mission mode.
  3. If no mission is stored, or if PX4 has finished executing all mission commands:
    • If flying the vehicle will loiter.
    • If landed the vehicle will "wait".
  4. You can manually change the current mission command by selecting it in QGroundControl.

    If you have a Jump to item command in the mission, moving to another item will not reset the loop counter. One implication is that if you change the current mission command to 1 this will not "fully restart" the mission.

  5. The mission will only reset when the vehicle is disarmed or when a new mission is uploaded.

    To automatically disarm the vehicle after it lands, in QGroundControl go to Vehicle Setup > Safety, navigate to Land Mode Settings and check the box labeled Disarm after. Enter the time to wait after landing before disarming the vehicle.

Missions can be paused by activating HOLD mode. The mission will then continue from the current mission command when you reactivate the MISSION flight mode. While flying in mission mode, if you decide to discontinue the mission and switch to any other mode e.g. position mode, fly the vehicle elsewhere with RC, and then switch back to mission mode, the vehicle will continue the mission from its current position and will fly to the next mission waypoint not visited yet.

Ensure that the throttle stick is non-zero before switching to any RC mode (otherwise the vehicle will crash).We recommend you centre the control sticks before switching to any other mode.

For more information about mission planning, see:

QGroundControl Support

QGroundControl provides additional GCS-level mission handling support (in addition to that provided by the flight controller). For more information see:

Mission Parameters

Mission behaviour is affected by a number of parameters, most of which are documented in Parameter Reference > Mission. A very small subset are listed below.

Parameter Description
NAV_RCL_ACT RC loss failsafe mode (what the vehicle will do if it looses RC connection) - e.g. enter hold mode, return mode, terminate etc.
NAV_LOITER_RAD Fixed-wing loiter radius.
COM_RC_OVERRIDE If enabled for auto modes, stick movement gives control back to the pilot (switches to Position mode - except when vehicle is handling a critical battery failsafe). Enabled by default.

Supported Mission Commands

PX4 "accepts" the following MAVLink mission commands in Mission mode (note: caveats below list). Unless otherwise noted, the implementation is as defined in the MAVLink specification.

Note:

  • PX4 parses the above messages, but they are not necessary acted on. For example, some messages are vehicle-type specific.
  • PX4 generally does not support local frames for mission commands (e.g. MAV_FRAME_LOCAL_NED).
  • Not all messages/commands are exposed via QGroundControl.
  • The list may become out of date as messages are added. You can check the current set by inspecting the code. Support is MavlinkMissionManager::parse_mavlink_mission_item in /src/modules/mavlink/mavlink_mission.cpp (list generated in this git changelist).

    Please add an bug fix or PR if you find a missing/incorrect message.

Inter-Waypoint Trajectory

PX4 expects to follow a straight line from the previous waypoint to the current target (it does not plan any other kind of path between waypoints - if you need one you can simulate this by adding additional waypoints).

MC vehicles will change the speed when approaching or leaving a waypoint based on the jerk-limited tuning.

Vehicles switch to the next waypoint as soon as they enter the acceptance radius.

  • For MC this radius is defined by NAV_ACC_RAD
  • For FW the radius is defined by the "L1 distance".
    • The L1 distance is computed from two parameters: FW_L1_DAMPING and FW_L1_PERIOD, and the current ground speed.
    • By default, it's about 70 meters.
    • The equation is:
© PX4 Dev Team. License: CC BY 4.0            Updated: 2024-02-13 22:49:01

results matching ""

    No results matching ""