mavsdk::Mission Class Reference
#include: mission.h
The Mission class enables waypoint missions.
Public Types
Type | Description |
---|---|
enum Result | Possible results returned for mission requests. |
std::function< void(Result)> result_callback_t | Callback type for async mission calls. |
std::vector< std::shared_ptr< MissionItem > > mission_items_t | Type for vector of mission items. |
std::function< void(Result, std::vector< std::shared_ptr< MissionItem > >)> mission_items_and_result_callback_t | Callback type for download_mission_async() call to get mission items and result. |
std::function< void(int current, int total)> progress_callback_t | Callback type to receive mission progress. |
Public Member Functions
Type | Name | Description |
---|---|---|
Mission (System & system) | Constructor. Creates the plugin for a specific System. | |
~Mission () | Destructor (internal use only). | |
Mission (const Mission &)=delete | Copy constructor (object is not copyable). | |
void | upload_mission_async (const std::vector< std::shared_ptr< MissionItem >> & mission_items, result_callback_t callback) | Uploads a vector of mission items to the system (asynchronous). |
void | upload_mission_cancel () | Cancel a mission upload (asynchronous). |
void | download_mission_async (mission_items_and_result_callback_t callback) | Downloads a vector of mission items from the system (asynchronous). |
void | download_mission_cancel () | Cancel a mission download (asynchronous). |
void | set_return_to_launch_after_mission (bool enable) | Set whether to trigger Return-to-Launch (RTL) after mission is complete. |
bool | get_return_to_launch_after_mission () | Get whether to trigger Return-to-Launch (RTL) after mission is complete. |
void | start_mission_async (result_callback_t callback) | Starts the mission (asynchronous). |
void | pause_mission_async (result_callback_t callback) | Pauses the mission (asynchronous). |
void | clear_mission_async (result_callback_t callback) | Clears the mission saved on the vehicle (asynchronous). |
void | set_current_mission_item_async (int current, result_callback_t callback) | Sets the mission item index to go to (asynchronous). |
bool | mission_finished () const | Checks if mission has been finished (synchronous). |
int | current_mission_item () const | Returns the current mission item index (synchronous). |
int | total_mission_items () const | Returns the total number of mission items (synchronous). |
void | subscribe_progress (progress_callback_t callback) | Subscribes to mission progress (asynchronous). |
const Mission & | operator= (const Mission &)=delete | Equality operator (object is not copyable). |
Static Public Member Functions
Type | Name | Description |
---|---|---|
const char * | result_str (Result result) | Gets a human-readable English string for an Mission::Result. |
Result | import_qgroundcontrol_mission (mission_items_t & mission_items, const std::string & qgc_plan_file) | Imports a QGroundControl (QGC) mission plan. |
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 = std::make_shared<Mission>(system);
Parameters
- System& system - The specific system associated with this plugin.
~Mission()
mavsdk::Mission::~Mission()
Destructor (internal use only).
Mission()
mavsdk::Mission::Mission(const Mission &)=delete
Copy constructor (object is not copyable).
Parameters
- const Mission& -
Member Typdef Documentation
typedef result_callback_t
typedef std::function<void(Result)> mavsdk::Mission::result_callback_t
Callback type for async mission calls.
typedef mission_items_t
typedef std::vector<std::shared_ptr<MissionItem> > mavsdk::Mission::mission_items_t
Type for vector of mission items.
typedef mission_items_and_result_callback_t
typedef std::function<void(Result, std::vector<std::shared_ptr<MissionItem> >)> mavsdk::Mission::mission_items_and_result_callback_t
Callback type for download_mission_async() call to get mission items and result.
typedef progress_callback_t
typedef std::function<void(int current, int total)> mavsdk::Mission::progress_callback_t
Callback type to receive mission progress.
The mission is finished if current == total.
Parameters
- current - Current mission item index (0 based).
- total - Total number of mission items.
Member Enumeration Documentation
enum Result
Possible results returned for mission requests.
Value | Description |
---|---|
UNKNOWN |
Unknown error. |
SUCCESS |
Request succeeded. |
ERROR |
Error. |
TOO_MANY_MISSION_ITEMS |
Too many MissionItem objects in the mission. |
BUSY |
Vehicle busy. |
TIMEOUT |
Request timed out. |
INVALID_ARGUMENT |
Invalid argument. |
UNSUPPORTED |
The mission downloaded from the system is not supported. |
NO_MISSION_AVAILABLE |
No mission available on system. |
FAILED_TO_OPEN_QGC_PLAN |
Failed to open QGroundControl plan. |
FAILED_TO_PARSE_QGC_PLAN |
Failed to parse QGroundControl plan. |
UNSUPPORTED_MISSION_CMD |
Unsupported mission command. |
CANCELLED |
Mission upload or download has been cancelled. |
Member Function Documentation
upload_mission_async()
void mavsdk::Mission::upload_mission_async(const std::vector< std::shared_ptr< MissionItem >> &mission_items, result_callback_t callback)
Uploads a vector of mission items to the system (asynchronous).
The mission items are uploaded to a drone. Once uploaded the mission can be started and executed even if a connection is lost.
Parameters
- const std::vector< std::shared_ptr< MissionItem >>& mission_items - Reference to vector of mission items.
- result_callback_t callback - Callback to receive result of this request.
upload_mission_cancel()
void mavsdk::Mission::upload_mission_cancel()
Cancel a mission upload (asynchronous).
This cancels an ongoing mission upload. The mission upload will fail with the result Result::CANCELLED.
download_mission_async()
void mavsdk::Mission::download_mission_async(mission_items_and_result_callback_t callback)
Downloads a vector of mission items from the system (asynchronous).
The method will fail if any of the downloaded mission items are not supported by the MAVSDK API.
Parameters
- mission_items_and_result_callback_t callback - Callback to receive mission items and result of this request.
download_mission_cancel()
void mavsdk::Mission::download_mission_cancel()
Cancel a mission download (asynchronous).
This cancels an ongoing mission download. The mission download will fail with the result Result::CANCELLED.
set_return_to_launch_after_mission()
void mavsdk::Mission::set_return_to_launch_after_mission(bool enable)
Set whether to trigger Return-to-Launch (RTL) after mission is complete.
This enables/disables to command RTL at the end of a mission.
After setting this option, the mission needs to be re-uploaded.
Parameters
- bool enable - Enables RTL after mission is complete.
get_return_to_launch_after_mission()
bool mavsdk::Mission::get_return_to_launch_after_mission()
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.
Returns
bool - True if RTL after mission is complete is enabled.
start_mission_async()
void mavsdk::Mission::start_mission_async(result_callback_t callback)
Starts the mission (asynchronous).
Note that the mission must be uploaded to the vehicle using upload_mission_async() before this method is called.
Parameters
- result_callback_t callback - callback to receive result of this request.
pause_mission_async()
void mavsdk::Mission::pause_mission_async(result_callback_t callback)
Pauses the mission (asynchronous).
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.
Parameters
- result_callback_t callback - Callback to receive result of this request.
clear_mission_async()
void mavsdk::Mission::clear_mission_async(result_callback_t callback)
Clears the mission saved on the vehicle (asynchronous).
Parameters
- result_callback_t callback - Callback to receive result of this request.
set_current_mission_item_async()
void mavsdk::Mission::set_current_mission_item_async(int current, result_callback_t callback)
Sets the mission item index to go to (asynchronous).
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.
Parameters
- int current - Index for mission index to go to next (0 based).
- result_callback_t callback - Callback to receive result of this request.
mission_finished()
bool mavsdk::Mission::mission_finished() const
Checks if mission has been finished (synchronous).
Returns
bool - true if mission is finished and the last mission item has been reached.
current_mission_item()
int mavsdk::Mission::current_mission_item() const
Returns the current mission item index (synchronous).
If the mission is finished, the current mission item will be the total number of mission items (so the last mission item index + 1).
Returns
int - current mission item index (0 based).
total_mission_items()
int mavsdk::Mission::total_mission_items() const
Returns the total number of mission items (synchronous).
Returns
int - total number of mission items
subscribe_progress()
void mavsdk::Mission::subscribe_progress(progress_callback_t callback)
Subscribes to mission progress (asynchronous).
Parameters
- progress_callback_t callback - Callback to receive mission progress.
operator=()
const Mission& mavsdk::Mission::operator=(const Mission &)=delete
Equality operator (object is not copyable).
Parameters
- const Mission& -
Returns
const Mission & -
result_str()
static const char* mavsdk::Mission::result_str(Result result)
Gets a human-readable English string for an Mission::Result.
Parameters
- Result result - Enum for which string is required.
Returns
const char * - Human readable string for the Mission::Result.
import_qgroundcontrol_mission()
static Result mavsdk::Mission::import_qgroundcontrol_mission(mission_items_t &mission_items, const std::string &qgc_plan_file)
Imports a QGroundControl (QGC) mission plan.
The method composes the plan into a vector of MissionItem shared pointers that can then be uploaded to a vehicle. The method will fail if any of the imported mission items are not supported by the MAVSDK API.
Parameters
- mission_items_t& mission_items - Vector of mission items imported from QGC plan.
- const std::string& qgc_plan_file - File path of the QGC plan.
Returns
Result - Result::SUCCESS if successful in importing QGC mission items. Otherwise one of the error codes: Result::FAILED_TO_OPEN_QGC_PLAN, Result::FAILED_TO_PARSE_QGC_PLAN, Result::UNSUPPORTED_MISSION_CMD.
See Also:
- QGroundControl Plan file format (QGroundControl Dev Guide)