mavsdk::Mission Class Reference

#include: mission.h


Enable waypoint missions.

Data Structures

struct MissionItem

struct MissionPlan

struct MissionProgress

struct ProgressData

struct ProgressDataOrMission

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, ProgressData)> UploadMissionWithProgressCallback Callback type for upload_mission_with_progress_async.
std::function< void(Result, MissionPlan)> DownloadMissionCallback Callback type for download_mission_async.
std::function< void(Result, ProgressDataOrMission)> DownloadMissionWithProgressCallback Callback type for download_mission_with_progress_async.
std::function< void(MissionProgress)> MissionProgressCallback Callback type for subscribe_mission_progress.
Handle< MissionProgress > MissionProgressHandle Handle type for subscribe_mission_progress.

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 () override 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.
void upload_mission_with_progress_async (MissionPlan mission_plan, const UploadMissionWithProgressCallback & callback) Upload a list of mission items to the system and report upload progress.
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).
void download_mission_with_progress_async (const DownloadMissionWithProgressCallback & callback) Download a list of mission items from the system (asynchronous) and report progress.
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.
MissionProgressHandle subscribe_mission_progress (const MissionProgressCallback & callback) Subscribe to mission progress updates.
void unsubscribe_mission_progress (MissionProgressHandle handle) Unsubscribe from subscribe_mission_progress.
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.
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() override

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 UploadMissionWithProgressCallback

using mavsdk::Mission::UploadMissionWithProgressCallback =  std::function<void(Result, ProgressData)>

Callback type for upload_mission_with_progress_async.

typedef DownloadMissionCallback

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

Callback type for download_mission_async.

typedef DownloadMissionWithProgressCallback

using mavsdk::Mission::DownloadMissionWithProgressCallback =  std::function<void(Result, ProgressDataOrMission)>

Callback type for download_mission_with_progress_async.

typedef MissionProgressCallback

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

Callback type for subscribe_mission_progress.

typedef MissionProgressHandle

using mavsdk::Mission::MissionProgressHandle =  Handle<MissionProgress>

Handle type for subscribe_mission_progress.

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.
UnsupportedMissionCmd Unsupported mission command.
TransferCancelled Mission transfer (upload or download) has been cancelled.
NoSystem No system connected.
Next Intermediate message showing progress.
Denied Request denied.
ProtocolError There was a protocol error.
IntMessagesNotSupported The system does not support the MISSION_INT protocol.

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.

upload_mission_with_progress_async()

void mavsdk::Mission::upload_mission_with_progress_async(MissionPlan mission_plan, const UploadMissionWithProgressCallback &callback)

Upload a list of mission items to the system and report upload progress.

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

Parameters

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.

download_mission_with_progress_async()

void mavsdk::Mission::download_mission_with_progress_async(const DownloadMissionWithProgressCallback &callback)

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

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

Parameters

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()

MissionProgressHandle mavsdk::Mission::subscribe_mission_progress(const MissionProgressCallback &callback)

Subscribe to mission progress updates.

Parameters

Returns

MissionProgressHandle -

unsubscribe_mission_progress()

void mavsdk::Mission::unsubscribe_mission_progress(MissionProgressHandle handle)

Unsubscribe from subscribe_mission_progress.

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.

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const Mission & -

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

results matching ""

    No results matching ""