# Flight Tasks

Flight Tasks are used within Flight Modes to provide specific movement behaviours: e.g. follow me, or flight smoothing.

# Overview

A flight task is a class in the flight task framework derived from the base class FlightTask (opens new window). Its goal is to generate setpoints for the controller from arbitrary input data, where each task implements the desired vehicle behavior for a specific mode. Programmers typically override the activate() and update() virtual methods by calling the base task's minimal implementation and extending with the implementation of the desired behavior. The activate() method is called when switching to the task and allows to initialize its state and take over gently from the passed over setpoints the previous task was just applying.

update() is called on every loop iteration during the execution and contains the core behavior implementation producing setpoints.

By convention tasks are contained in a subfolder of PX4-Autopilot/src/modules/flight_mode_manager/tasks (opens new window) named after the task, and the source files are named with the prefix "FlightTask".

Note

Video overviews from PX4 developer summits are provided below.

# Creating a Flight Task

The instructions below might be used to create a task named MyTask:

  1. Create a directory for the new flight task in PX4-Autopilot/src/modules/flight_mode_manager/tasks (opens new window). By convention the directory is named after the task, so we will call it /MyTask.

    mkdir PX4-Autopilot/src/modules/flight_mode_manager/tasks/MyTask
    
  2. Create empty source code and cmake files for the new flight task in the MyTask directory using the prefix "FlightTask":

    • CMakeLists.txt
    • FlightTaskMyTask.hpp
    • FlightTaskMyTask.cpp
  3. Update CMakeLists.txt for the new task

    • Copy the contents of the CMakeLists.txt for another task - e.g. Orbit/CMakeLists.txt (opens new window)

    • Update the copyright to the current year

      ############################################################################
      #
      #   Copyright (c) 2021 PX4 Development Team. All rights reserved.
      #
      
    • Modify the code to reflect the new task - e.g. replace FlightTaskOrbit with FlightTaskMyTask. The code will look something like this:

      px4_add_library(FlightTaskMyTask
          FlightTaskMyTask.cpp
      )
      
      target_link_libraries(FlightTaskMyTask PUBLIC FlightTask)
      target_include_directories(FlightTaskMyTask PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
      
  4. Update the header file (in this case FlightTaskMyTask.hpp): Most tasks reimplement the virtual methods activate() and update(), and in this example we also have a private variable.

    #pragma once
    
    #include "FlightTask.hpp"
    
    class FlightTaskMyTask : public FlightTask
    {
    public:
      FlightTaskMyTask() = default;
      virtual ~FlightTaskMyTask() = default;
    
      bool update();
      bool activate(const trajectory_setpoint_s &last_setpoint) override;
    
    private:
      float _origin_z{0.f};
    };
    
  5. Update the cpp file as appropriate. This example provides as simple implementation of FlightTaskMyTask.cpp that simply indicates that the task methods are called.

    #include "FlightTaskMyTask.hpp"
    
    bool FlightTaskMyTask::activate(const trajectory_setpoint_s &last_setpoint)
    {
      bool ret = FlightTask::activate(last_setpoint);
      PX4_INFO("FlightTaskMyTask activate was called! ret: %d", ret); // report if activation was successful
      return ret;
    }
    
    bool FlightTaskMyTask::update()
    {
      PX4_INFO("FlightTaskMyTask update was called!"); // report update
      return true;
    }
    
  6. Add the new task to the list of tasks to be built in PX4-Autopilot/src/modules/flight_mode_manager/CMakeLists.txt (opens new window):

    ...
    if(NOT px4_constrained_flash_build)
     list(APPEND flight_tasks_all
      AutoFollowTarget
      Orbit
      MyTask
     )
    endif()
    ...
    
  7. Update a flight mode to ensure that the task is called. Usually a parameter is used to select when a particular flight task should be used.

    For example, to enable our new MyTask in multicopter Position mode:

    • Update MPC_POS_MODE (multicopter_position_mode_params.c (opens new window)) to add an option for selecting "MyTask" if the parameter has a previously unused value like 5:

      ...
       * @value 0 Direct velocity
       * @value 3 Smoothed velocity
       * @value 4 Acceleration based
       * @value 5 My task
       * @group Multicopter Position Control
       */
      PARAM_DEFINE_INT32(MPC_POS_MODE, 5);
      
    • Add a case for your new option in the switch for the parameter FlightModeManager.cpp (opens new window) to enable the task when _param_mpc_pos_mode has the right value.

      ...
      // manual position control
      ...
      switch (_param_mpc_pos_mode.get()) {
        ...
        case 3:
           error = switchTask(FlightTaskIndex::ManualPositionSmoothVel);
           break;
        case 5: // Add case for new task: MyTask
           error = switchTask(FlightTaskIndex::MyTask);
           break;
      case 4:
      ....
      ...
      

# Test New Flight Task

To test the flight task you need to run the vehicle with the task enabled. For the example above, this means setting the parameter MPC_POS_MODE to 5, taking off, and switching the vehicle to Position mode.

Note

The task defined above should only be tested on the simulator. The code doesn't actually create setpoints so the vehicle will not fly.

Build SITL simulation (gazebo-classic)

make px4_sitl gazebo-classic

Open QGroundControl (if not open, no message information will be printed out). In the console, takeoff and switch to Position mode:

pxh> commander takeoff
pxh> commander mode posctl

The console will continuously display: INFO [FlightTaskMyTask] FlightTaskMyTask update was called!. If you want to change to another flight mode, you can type a command to change the mode, such as commander mode altctl.

# Video

The following videos provide an overview of flight tasks in PX4. The first covers the state of the flight task framework in PX4 v1.9. The second is an update, which covers the changes in PX4 v1.11.

# PX4 Flight Task Architecture Overview (PX4 Developer Summit 2019)

A description of how flight modes work in PX4 v1.9 (Dennis Mannhart, Matthias Grob).

# Overview of multicopter control from sensors to motors (PX4 Developer Summit Virtual 2020)

The relevant section of this video is an update of flight tasks in PX4 v11.1 at (9min 20sec). The slides can be found here (PDF) (opens new window) - Slides 9 and 12 are relevant.