Actions (Take-off, Landing, Arming, etc)

The Action class is used for commanding the vehicle to arm, takeoff, land, return home and land, disarm, kill and transition between VTOL modes.

Most of the methods have both synchronous and asynchronous versions. The methods send commands to a vehicle, and return/complete with the vehicle's response. It is important to understand that a successful response indicates whether or not the vehicle intends to act on the command, not that it has finished the action (e.g. arming, landing, taking off etc.).

The implication is that you may need to monitor for completion of actions!

Create the Plugin

Action objects are created in the same way as for other SDK plugins. General instructions are provided in the topic: Using Plugins.

The main steps are:

  1. Link the plugin library into your application. Do this by adding mavsdk_action to the target_link_libraries section of the app's cmake build definition file

    find_package(MAVSDK REQUIRED)
    
    target_link_libraries(your_application_name
      MAVSDK::mavsdk
      ...
      MAVSDK::mavsdk_action
      ...
    )
    
  2. Create a connection to a system. For example (basic code without error checking):
    #include <mavsdk/mavsdk.h>
    Mavsdk mavsdk;
    ConnectionResult conn_result = mavsdk.add_udp_connection();
    // Wait for the system to connect via heartbeat
    while (mavsdk.system().size() == 0) {
       sleep_for(seconds(1));
    }
    // System got discovered.
    System system = mavsdk.systems()[0];
    
  3. Create an instance of Action with the system:
    #include <mavsdk/plugins/action/action.h>
    auto action = Action{system};
    

The action object can then used to access the plugin API (as shown in the following sections).

Some of the sections below additionally assume you have created a Telemetry instance that can be accessed using telemetry.

Taking Off

The recommended way to take off using the SDK (and PX4) is to use either of the takeoff() or takeoff_async() methods. If a takeoff command is accepted the vehicle will change to the Takeoff mode, fly to the takeoff altitude, and then hover (in takeoff mode) until another instruction is received.

PX4/SDK also provides other ways to take off:

  • A copter or VTOL will take off automatically if a mission is started (fixed-wing will not).
  • You can also take off by manually driving the vehicle using the offboard API.

The vehicle will only take off once armed, and can only arm once it is "healthy" (has been calibrated, the home position has been set, and there is a high-enough quality GPS lock). After it starts flying, code needs to check that takeoff is complete before sending additional instructions.

Health Check

The code fragment below shows very simple code to synchronously poll for health status (using Telemetry:health_all_ok()) prior to arming:

// Wait until health is OK and vehicle is ready to arm
while (telemetry.health_all_ok() != true) {
    std::cout << "Vehicle not ready to arm ..." << '\n';
    std::this_thread::sleep_for(std::chrono::seconds(1));
}

The code fragment below performs the same task, but additionally exits the app if calibration is required reports what conditions are still required before the vehicle is "healthy":

// Exit if calibration is required
Telemetry::Health check_health = telemetry.health();
bool calibration_required = false;
if (!check_health.gyrometer_calibration_ok) {
    std::cout << ERROR_CONSOLE_TEXT << "Gyro requires calibration." << NORMAL_CONSOLE_TEXT << '\n';
    calibration_required=true;
}
if (!check_health.accelerometer_calibration_ok) {
    std::cout << ERROR_CONSOLE_TEXT << "Accelerometer requires calibration." << NORMAL_CONSOLE_TEXT << '\n';
    calibration_required=true;
}
if (!check_health.magnetometer_calibration_ok) {
    std::cout << ERROR_CONSOLE_TEXT << "Magnetometer (compass) requires calibration." << NORMAL_CONSOLE_TEXT << '\n';
    calibration_required=true;
}
if (!check_health.level_calibration_ok) {
    std::cout << ERROR_CONSOLE_TEXT << "Level calibration required." << NORMAL_CONSOLE_TEXT << '\n';
    calibration_required=true;
}
if (calibration_required) {
    return 1;
}


// Check if ready to arm (reporting status)
while (telemetry.health_all_ok() != true) {
    std::cout << ERROR_CONSOLE_TEXT << "Vehicle not ready to arm. Waiting on:" << NORMAL_CONSOLE_TEXT << '\n';
    Telemetry::Health current_health = telemetry.health();
    if (!current_health.global_position_ok) {
        std::cout << ERROR_CONSOLE_TEXT << "  - GPS fix." << NORMAL_CONSOLE_TEXT << '\n';
    }
    if (!current_health.local_position_ok) {
        std::cout << ERROR_CONSOLE_TEXT << "  - Local position estimate." << NORMAL_CONSOLE_TEXT << '\n';
    }
    if (!current_health.home_position_ok) {
        std::cout << ERROR_CONSOLE_TEXT << "  - Home position to be set." << NORMAL_CONSOLE_TEXT << '\n';
    }
    std::this_thread::sleep_for(std::chrono::seconds(1));
}

Vehicle health can also be checked using Telemetry:subscribe_health_all_ok().

Arming

Once the vehicle is ready, use the following synchronous code to arm:

// Arm vehicle
std::cout << "Arming..." << '\n';
const Action::Result arm_result = action.arm();

if (arm_result != Action::Result::Success) {
    std::cout << "Arming failed:" << arm_result <<  '\n';
    return 1; //Exit if arming fails
}

If the arm() method returns Action::Result::Success then the vehicle is armed and can proceed to takeoff. This can be confirmed using Telemetry::armed().

Get/Set Takeoff Altitude

The default/current takeoff altitude can be queried using get_takeoff_altitude(). This target can be changed at any point before takeoff using set_takeoff_altitude(). The code fragment below shows how to set the takeoff altitude to 3 metres:

action.set_takeoff_altitude(3.0);

Takeoff Action

Once the vehicle is armed it can be commanded to take off. The code below uses the synchronous takeoff() method, and fails if the vehicle refuses the command:

// Command Take off
std::cout << "Taking off..." << '\n';
const Action::Result takeoff_result = action.takeoff();
if (takeoff_result != Action::Result::Success) {
    std::cout << "Takeoff failed:" << takeoff_result << '\n';
    return 1;
}

If the command succeeds the vehicle will takeoff, and hover at the takeoff altitude. Code should wait until takeoff has completed before sending the next instruction. Unfortunately there is no specific indicator to inform code that takeoff is complete.

One alternative is to simply wait for enough time that the vehicle should have reached the takeoff altitude.

The code below checks for takeoff completion by polling the current altitude until the target altitude is reached:

float target_alt=action.get_takeoff_altitude_m();
float current_position=0;
while (current_position<target_alt) {
    current_position = telemetry.position().relative_altitude_m;
    std::this_thread::sleep_for(std::chrono::seconds(1));
}
// Reached target altitude - continue with next instruction.

Landing

The best way to land the vehicle at the current location is to use the land() or land_async() methods. If the command is accepted the vehicle will change to the Land mode and land at the current point.

The SDK does not at time of writing recommend other approaches for landing: land mission items are not supported and manually landing the vehicle using the offboard is not as safe.

The code below shows how to use the land action.

const Action::Result land_result = action.land();
if (land_result != Action::Result::Success) {
    //Land failed, so exit (in reality might try a return to land or kill.)
    return 1;
}

The vehicle should land and then automatically disarm. If you want to monitor the landing you can trigger completion of the app based on the armed state, as shown below.

while (telemetry.armed()) {
    std::this_thread::sleep_for(std::chrono::seconds(1));
}
std::cout << "Disarmed, exiting." << '\n';

Return/RTL

Return mode (also known as "Return to Launch", "Return to Land", "Return to Home") flies the vehicle back to the home position and may also land the vehicle (depending on vehicle configuration). This mode is invoked from Action using the return_to_launch() or return_to_launch_async() methods.

The code below shows how to use the synchronous method:

const Action::Result rtl_result = telemetry.return_to_launch();
if (rtl_result != Action::Result::Success) {
    //RTL failed, so exit (in reality might send kill command.)
    return 1;
}

Depending on the vehicle it may land or hover around the return point. For vehicles that are configured to land you can use the same code as in the previous section to determine when the vehicle has disarmed.

Disarm/Kill

Use the disarm or kill methods to stop the drone motors (the difference is that disarming will only succeed if the drone considers itself landed, while kill will disarm a vehicle even in flight).

The methods are listed below. These are used in the same way as other similar Action APIs:

PX4 will automatically disarm the vehicle after landing. The disarm methods explicitly invoke the same functionality.

Get/Set Cruise Speed

You can get/set the normal horizontal velocity used in Return mode, Hold mode, Takeoff (and other AUTO Flight Modes using the following methods:

These methods get/set the MPC_XY_CRUISE parameter. They are used in the same way as the other Action methods.

Switch Between VTOL Modes

Action provides methods to transition between VTOL fixed wing and multicopter modes, with both synchronous and asynchronous versions:

The associated action will only be executed for VTOL vehicles (on other vehicle types the command will fail with a Result of VTOL_TRANSITION_SUPPORT_UNKNOWN or NO_VTOL_TRANSITION_SUPPORT). The command will succeed if called when the vehicle is already in the mode.

The code fragment below shows how to call the synchronous action to transition to fixed wing, and to print the result of the call (the other synchronous method is used in the same way).

const Action::Result fw_result = action.transition_to_fixedwing();

if (fw_result != Action::Result::Success) {
    std::cout << "Transition to fixed wing failed: "
        << fw_result << '\n';
}

Further Information

Additional information/examples for the Action API are linked below:

© MAVSDK Development Team 2017-2023. License: CC BY 4.0            Updated: 2023-12-27 03:10:20

results matching ""

    No results matching ""