mavsdk::MissionRaw Class Reference

#include: mission_raw.h


Enable raw missions as exposed by MAVLink.

Data Structures

struct MissionImportData

struct MissionItem

struct MissionProgress

Public Types

Type Description
enum Result Possible results returned for action requests.
std::function< void(Result)> ResultCallback Callback type for asynchronous MissionRaw calls.
std::function< void(Result, std::vector< MissionItem >)> DownloadMissionCallback Callback type for download_mission_async.
std::function< void(MissionProgress)> MissionProgressCallback Callback type for subscribe_mission_progress.
Handle< MissionProgress > MissionProgressHandle Handle type for subscribe_mission_progress.
std::function< void(bool)> MissionChangedCallback Callback type for subscribe_mission_changed.
Handle< bool > MissionChangedHandle Handle type for subscribe_mission_changed.

Public Member Functions

Type Name Description
  MissionRaw (System & system) Constructor. Creates the plugin for a specific System.
  MissionRaw (std::shared_ptr< System > system) Constructor. Creates the plugin for a specific System.
  ~MissionRaw () override Destructor (internal use only).
  MissionRaw (const MissionRaw & other) Copy constructor.
void upload_mission_async (std::vector< MissionItem > mission_items, const ResultCallback callback) Upload a list of raw mission items to the system.
Result upload_mission (std::vector< MissionItem > mission_items)const Upload a list of raw mission items to the system.
void upload_geofence_async (std::vector< MissionItem > mission_items, const ResultCallback callback) Upload a list of geofence items to the system.
Result upload_geofence (std::vector< MissionItem > mission_items)const Upload a list of geofence items to the system.
void upload_rally_points_async (std::vector< MissionItem > mission_items, const ResultCallback callback) Upload a list of rally point items to the system.
Result upload_rally_points (std::vector< MissionItem > mission_items)const Upload a list of rally point 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 raw mission items from the system (asynchronous).
std::pair< Result, std::vector< MissionRaw::MissionItem > > download_mission () const Download a list of raw 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 raw mission item index to go to.
Result set_current_mission_item (int32_t index)const Sets the raw mission item index to go to.
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).
MissionChangedHandle subscribe_mission_changed (const MissionChangedCallback & callback)

  • Subscribes to mission changed.

  • </ul> void | unsubscribe_mission_changed (MissionChangedHandle handle) | Unsubscribe from subscribe_mission_changed. std::pair< Result, MissionRaw::MissionImportData > | import_qgroundcontrol_mission (std::string qgc_plan_path)const | Import a QGroundControl missions in JSON .plan format, from a file. std::pair< Result, MissionRaw::MissionImportData > | import_qgroundcontrol_mission_from_string (std::string qgc_plan)const | Import a QGroundControl missions in JSON .plan format, from a string. const MissionRaw & | operator= (const MissionRaw &)=delete | Equality operator (object is not copyable).

    Constructor & Destructor Documentation

    MissionRaw()

    mavsdk::MissionRaw::MissionRaw(System &system)
    

    Constructor. Creates the plugin for a specific System.

    The plugin is typically created as shown below:

    auto mission_raw = MissionRaw(system);
    

    Parameters

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

    MissionRaw()

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

    Constructor. Creates the plugin for a specific System.

    The plugin is typically created as shown below:

    auto mission_raw = MissionRaw(system);
    

    Parameters

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

    ~MissionRaw()

    mavsdk::MissionRaw::~MissionRaw() override
    

    Destructor (internal use only).

    MissionRaw()

    mavsdk::MissionRaw::MissionRaw(const MissionRaw &other)
    

    Copy constructor.

    Parameters

    Member Typdef Documentation

    typedef ResultCallback

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

    Callback type for asynchronous MissionRaw calls.

    typedef DownloadMissionCallback

    using mavsdk::MissionRaw::DownloadMissionCallback =  std::function<void(Result, std::vector<MissionItem>)>
    

    Callback type for download_mission_async.

    typedef MissionProgressCallback

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

    Callback type for subscribe_mission_progress.

    typedef MissionProgressHandle

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

    Handle type for subscribe_mission_progress.

    typedef MissionChangedCallback

    using mavsdk::MissionRaw::MissionChangedCallback =  std::function<void(bool)>
    

    Callback type for subscribe_mission_changed.

    typedef MissionChangedHandle

    using mavsdk::MissionRaw::MissionChangedHandle =  Handle<bool>
    

    Handle type for subscribe_mission_changed.

    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.
    TransferCancelled Mission transfer (upload or download) has been cancelled.
    FailedToOpenQgcPlan Failed to open the QGroundControl plan.
    FailedToParseQgcPlan Failed to parse the QGroundControl plan.
    NoSystem No system connected.
    Denied Request denied.
    MissionTypeNotConsistent Mission type is not consistent.
    InvalidSequence The mission item sequences are not increasing correctly.
    CurrentInvalid The current item is not set correctly.
    ProtocolError There was a protocol error.
    IntMessagesNotSupported The system does not support the MISSION_INT protocol.

    Member Function Documentation

    upload_mission_async()

    void mavsdk::MissionRaw::upload_mission_async(std::vector< MissionItem > mission_items, const ResultCallback callback)
    

    Upload a list of raw mission items to the system.

    The raw 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::MissionRaw::upload_mission(std::vector< MissionItem > mission_items) const
    

    Upload a list of raw mission items to the system.

    The raw 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_geofence_async()

    void mavsdk::MissionRaw::upload_geofence_async(std::vector< MissionItem > mission_items, const ResultCallback callback)
    

    Upload a list of geofence items to the system.

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

    Parameters

    upload_geofence()

    Result mavsdk::MissionRaw::upload_geofence(std::vector< MissionItem > mission_items) const
    

    Upload a list of geofence items to the system.

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

    Parameters

    Returns

    Result - Result of request.

    upload_rally_points_async()

    void mavsdk::MissionRaw::upload_rally_points_async(std::vector< MissionItem > mission_items, const ResultCallback callback)
    

    Upload a list of rally point items to the system.

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

    Parameters

    upload_rally_points()

    Result mavsdk::MissionRaw::upload_rally_points(std::vector< MissionItem > mission_items) const
    

    Upload a list of rally point items to the system.

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

    Parameters

    Returns

    Result - Result of request.

    cancel_mission_upload()

    Result mavsdk::MissionRaw::cancel_mission_upload() const
    

    Cancel an ongoing mission upload.

    This function is blocking.

    Returns

    Result - Result of request.

    download_mission_async()

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

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

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

    Parameters

    download_mission()

    std::pair<Result, std::vector<MissionRaw::MissionItem> > mavsdk::MissionRaw::download_mission() const
    

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

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

    Returns

     std::pair< Result, std::vector< MissionRaw::MissionItem > > - Result of request.

    cancel_mission_download()

    Result mavsdk::MissionRaw::cancel_mission_download() const
    

    Cancel an ongoing mission download.

    This function is blocking.

    Returns

    Result - Result of request.

    start_mission_async()

    void mavsdk::MissionRaw::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::MissionRaw::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::MissionRaw::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::MissionRaw::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::MissionRaw::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::MissionRaw::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::MissionRaw::set_current_mission_item_async(int32_t index, const ResultCallback callback)
    

    Sets the raw 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 raw mission item, the mission will be set to this item.

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

    Parameters

    set_current_mission_item()

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

    Sets the raw 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 raw mission item, the mission will be set to this item.

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

    Parameters

    • int32_t index -

    Returns

    Result - Result of request.

    subscribe_mission_progress()

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

    Subscribe to mission progress updates.

    Parameters

    Returns

    MissionProgressHandle -

    unsubscribe_mission_progress()

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

    Unsubscribe from subscribe_mission_progress.

    Parameters

    mission_progress()

    MissionProgress mavsdk::MissionRaw::mission_progress() const
    

    Poll for 'MissionProgress' (blocking).

    Returns

    MissionProgress - One MissionProgress update.

    subscribe_mission_changed()

    MissionChangedHandle mavsdk::MissionRaw::subscribe_mission_changed(const MissionChangedCallback &callback)
    
    • Subscribes to mission changed.

    This notification can be used to be informed if a ground station has been uploaded or changed by a ground station or companion computer.

    Parameters

    Returns

    MissionChangedHandle -

    unsubscribe_mission_changed()

    void mavsdk::MissionRaw::unsubscribe_mission_changed(MissionChangedHandle handle)
    

    Unsubscribe from subscribe_mission_changed.

    Parameters

    import_qgroundcontrol_mission()

    std::pair<Result, MissionRaw::MissionImportData> mavsdk::MissionRaw::import_qgroundcontrol_mission(std::string qgc_plan_path) const
    

    Import a QGroundControl missions in JSON .plan format, from a file.

    Supported:

    • Waypoints

    • Survey Not supported:

    • Structure Scan

    This function is blocking.

    Parameters

    • std::string qgc_plan_path -

    Returns

     std::pair< Result, MissionRaw::MissionImportData > - Result of request.

    import_qgroundcontrol_mission_from_string()

    std::pair<Result, MissionRaw::MissionImportData> mavsdk::MissionRaw::import_qgroundcontrol_mission_from_string(std::string qgc_plan) const
    

    Import a QGroundControl missions in JSON .plan format, from a string.

    Supported:

    • Waypoints

    • Survey Not supported:

    • Structure Scan

    This function is blocking.

    Parameters

    • std::string qgc_plan -

    Returns

     std::pair< Result, MissionRaw::MissionImportData > - Result of request.

    operator=()

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

    Equality operator (object is not copyable).

    Parameters

    Returns

     const MissionRaw & -

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

    results matching ""

      No results matching ""