mavsdk::Mission Class Reference

#include: mission.h


Enable waypoint missions.

Data Structures

struct MissionItem

struct MissionPlan

struct MissionProgress

Public Types

Type Description
enum Result Possible results returned for action requests.
std::function< void(Result)> ResultCallback Callback type for asynchronous Mission calls.
std::function< void(Result, MissionPlan)> DownloadMissionCallback Callback type for download_mission_async.
std::function< void(MissionProgress)> MissionProgressCallback Callback type for subscribe_mission_progress.
std::function< void(Result, MissionPlan)> ImportQgroundcontrolMissionCallback Callback type for import_qgroundcontrol_mission_async.

Public Member Functions

Type Name Description
  Mission (System & system) Constructor. Creates the plugin for a specific System.
  Mission (std::shared_ptr< System > system) Constructor. Creates the plugin for a specific System.
  ~Mission () Destructor (internal use only).
  Mission (const Mission & other) Copy constructor.
void upload_mission_async (MissionPlan mission_plan, const ResultCallback callback) Upload a list of mission items to the system.
Result upload_mission (MissionPlan mission_plan)const Upload a list of mission items to the system.
Result cancel_mission_upload () const Cancel an ongoing mission upload.
void download_mission_async (const DownloadMissionCallback callback) Download a list of mission items from the system (asynchronous).
std::pair< Result, Mission::MissionPlan > download_mission () const Download a list of mission items from the system (asynchronous).
Result cancel_mission_download () const Cancel an ongoing mission download.
void start_mission_async (const ResultCallback callback) Start the mission.
Result start_mission () const Start the mission.
void pause_mission_async (const ResultCallback callback) Pause the mission.
Result pause_mission () const Pause the mission.
void clear_mission_async (const ResultCallback callback) Clear the mission saved on the vehicle.
Result clear_mission () const Clear the mission saved on the vehicle.
void set_current_mission_item_async (int32_t index, const ResultCallback callback) Sets the mission item index to go to.
Result set_current_mission_item (int32_t index)const Sets the mission item index to go to.
std::pair< Result, bool > is_mission_finished () const Check if the mission has been finished.
void subscribe_mission_progress (MissionProgressCallback callback) Subscribe to mission progress updates.
MissionProgress mission_progress () const Poll for 'MissionProgress' (blocking).
std::pair< Result, bool > get_return_to_launch_after_mission () const Get whether to trigger Return-to-Launch (RTL) after mission is complete.
Result set_return_to_launch_after_mission (bool enable)const Set whether to trigger Return-to-Launch (RTL) after the mission is complete.
void import_qgroundcontrol_mission_async (std::string qgc_plan_path, const ImportQgroundcontrolMissionCallback callback) Import a QGroundControl (QGC) mission plan.
std::pair< Result, Mission::MissionPlan > import_qgroundcontrol_mission (std::string qgc_plan_path)const Import a QGroundControl (QGC) mission plan.
const Mission & operator= (const Mission &)=delete Equality operator (object is not copyable).

Constructor & Destructor Documentation

Mission()

mavsdk::Mission::Mission(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto mission = Mission(system);

Parameters

  • System& system - The specific system associated with this plugin.

Mission()

mavsdk::Mission::Mission(std::shared_ptr< System > system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto mission = Mission(system);

Parameters

  • std::shared_ptr< System > system - The specific system associated with this plugin.

~Mission()

mavsdk::Mission::~Mission()

Destructor (internal use only).

Mission()

mavsdk::Mission::Mission(const Mission &other)

Copy constructor.

Parameters

Member Typdef Documentation

typedef ResultCallback

using mavsdk::Mission::ResultCallback =  std::function<void(Result)>

Callback type for asynchronous Mission calls.

typedef DownloadMissionCallback

using mavsdk::Mission::DownloadMissionCallback =  std::function<void(Result, MissionPlan)>

Callback type for download_mission_async.

typedef MissionProgressCallback

using mavsdk::Mission::MissionProgressCallback =  std::function<void(MissionProgress)>

Callback type for subscribe_mission_progress.

typedef ImportQgroundcontrolMissionCallback

using mavsdk::Mission::ImportQgroundcontrolMissionCallback =  std::function<void(Result, MissionPlan)>

Callback type for import_qgroundcontrol_mission_async.

Member Enumeration Documentation

enum Result

Possible results returned for action requests.

Value Description
Unknown Unknown result.
Success Request succeeded.
Error Error.
TooManyMissionItems Too many mission items in the mission.
Busy Vehicle is busy.
Timeout Request timed out.
InvalidArgument Invalid argument.
Unsupported Mission downloaded from the system is not supported.
NoMissionAvailable No mission available on the system.
FailedToOpenQgcPlan Failed to open the QGroundControl plan.
FailedToParseQgcPlan Failed to parse the QGroundControl plan.
UnsupportedMissionCmd Unsupported mission command.
TransferCancelled Mission transfer (upload or download) has been cancelled.

Member Function Documentation

upload_mission_async()

void mavsdk::Mission::upload_mission_async(MissionPlan mission_plan, const ResultCallback callback)

Upload a list of mission items to the system.

The mission items are uploaded to a drone. Once uploaded the mission can be started and executed even if the connection is lost.

This function is non-blocking. See 'upload_mission' for the blocking counterpart.

Parameters

upload_mission()

Result mavsdk::Mission::upload_mission(MissionPlan mission_plan) const

Upload a list of mission items to the system.

The mission items are uploaded to a drone. Once uploaded the mission can be started and executed even if the connection is lost.

This function is blocking. See 'upload_mission_async' for the non-blocking counterpart.

Parameters

Returns

Result - Result of request.

cancel_mission_upload()

Result mavsdk::Mission::cancel_mission_upload() const

Cancel an ongoing mission upload.

This function is blocking.

Returns

Result - Result of request.

download_mission_async()

void mavsdk::Mission::download_mission_async(const DownloadMissionCallback callback)

Download a list of mission items from the system (asynchronous).

Will fail if any of the downloaded mission items are not supported by the MAVSDK API.

This function is non-blocking. See 'download_mission' for the blocking counterpart.

Parameters

download_mission()

std::pair<Result, Mission::MissionPlan> mavsdk::Mission::download_mission() const

Download a list of mission items from the system (asynchronous).

Will fail if any of the downloaded mission items are not supported by the MAVSDK API.

This function is blocking. See 'download_mission_async' for the non-blocking counterpart.

Returns

 std::pair< Result, Mission::MissionPlan > - Result of request.

cancel_mission_download()

Result mavsdk::Mission::cancel_mission_download() const

Cancel an ongoing mission download.

This function is blocking.

Returns

Result - Result of request.

start_mission_async()

void mavsdk::Mission::start_mission_async(const ResultCallback callback)

Start the mission.

A mission must be uploaded to the vehicle before this can be called.

This function is non-blocking. See 'start_mission' for the blocking counterpart.

Parameters

start_mission()

Result mavsdk::Mission::start_mission() const

Start the mission.

A mission must be uploaded to the vehicle before this can be called.

This function is blocking. See 'start_mission_async' for the non-blocking counterpart.

Returns

Result - Result of request.

pause_mission_async()

void mavsdk::Mission::pause_mission_async(const ResultCallback callback)

Pause the mission.

Pausing the mission puts the vehicle into HOLD mode. A multicopter should just hover at the spot while a fixedwing vehicle should loiter around the location where it paused.

This function is non-blocking. See 'pause_mission' for the blocking counterpart.

Parameters

pause_mission()

Result mavsdk::Mission::pause_mission() const

Pause the mission.

Pausing the mission puts the vehicle into HOLD mode. A multicopter should just hover at the spot while a fixedwing vehicle should loiter around the location where it paused.

This function is blocking. See 'pause_mission_async' for the non-blocking counterpart.

Returns

Result - Result of request.

clear_mission_async()

void mavsdk::Mission::clear_mission_async(const ResultCallback callback)

Clear the mission saved on the vehicle.

This function is non-blocking. See 'clear_mission' for the blocking counterpart.

Parameters

clear_mission()

Result mavsdk::Mission::clear_mission() const

Clear the mission saved on the vehicle.

This function is blocking. See 'clear_mission_async' for the non-blocking counterpart.

Returns

Result - Result of request.

set_current_mission_item_async()

void mavsdk::Mission::set_current_mission_item_async(int32_t index, const ResultCallback callback)

Sets the mission item index to go to.

By setting the current index to 0, the mission is restarted from the beginning. If it is set to a specific index of a mission item, the mission will be set to this item.

Note that this is not necessarily true for general missions using MAVLink if loop counters are used.

This function is non-blocking. See 'set_current_mission_item' for the blocking counterpart.

Parameters

set_current_mission_item()

Result mavsdk::Mission::set_current_mission_item(int32_t index) const

Sets the mission item index to go to.

By setting the current index to 0, the mission is restarted from the beginning. If it is set to a specific index of a mission item, the mission will be set to this item.

Note that this is not necessarily true for general missions using MAVLink if loop counters are used.

This function is blocking. See 'set_current_mission_item_async' for the non-blocking counterpart.

Parameters

  • int32_t index -

Returns

Result - Result of request.

is_mission_finished()

std::pair<Result, bool> mavsdk::Mission::is_mission_finished() const

Check if the mission has been finished.

This function is blocking.

Returns

 std::pair< Result, bool > - Result of request.

subscribe_mission_progress()

void mavsdk::Mission::subscribe_mission_progress(MissionProgressCallback callback)

Subscribe to mission progress updates.

Parameters

mission_progress()

MissionProgress mavsdk::Mission::mission_progress() const

Poll for 'MissionProgress' (blocking).

Returns

MissionProgress - One MissionProgress update.

get_return_to_launch_after_mission()

std::pair<Result, bool> mavsdk::Mission::get_return_to_launch_after_mission() const

Get whether to trigger Return-to-Launch (RTL) after mission is complete.

Before getting this option, it needs to be set, or a mission needs to be downloaded.

This function is blocking.

Returns

 std::pair< Result, bool > - Result of request.

set_return_to_launch_after_mission()

Result mavsdk::Mission::set_return_to_launch_after_mission(bool enable) const

Set whether to trigger Return-to-Launch (RTL) after the mission is complete.

This will only take effect for the next mission upload, meaning that the mission may have to be uploaded again.

This function is blocking.

Parameters

  • bool enable -

Returns

Result - Result of request.

import_qgroundcontrol_mission_async()

void mavsdk::Mission::import_qgroundcontrol_mission_async(std::string qgc_plan_path, const ImportQgroundcontrolMissionCallback callback)

Import a QGroundControl (QGC) mission plan.

The method will fail if any of the imported mission items are not supported by the MAVSDK API.

This function is non-blocking. See 'import_qgroundcontrol_mission' for the blocking counterpart.

Parameters

import_qgroundcontrol_mission()

std::pair<Result, Mission::MissionPlan> mavsdk::Mission::import_qgroundcontrol_mission(std::string qgc_plan_path) const

Import a QGroundControl (QGC) mission plan.

The method will fail if any of the imported mission items are not supported by the MAVSDK API.

This function is blocking. See 'import_qgroundcontrol_mission_async' for the non-blocking counterpart.

Parameters

  • std::string qgc_plan_path -

Returns

 std::pair< Result, Mission::MissionPlan > - Result of request.

operator=()

const Mission& mavsdk::Mission::operator=(const Mission &)=delete

Equality operator (object is not copyable).

Parameters

Returns

 const Mission & -

© Dronecode 2017-2020. License: CC BY 4.0            Updated: 2021-02-08 13:41:53

results matching ""

    No results matching ""