mavsdk::Geofence Class Reference

#include: geofence.h


Enable setting a geofence.

Data Structures

struct Point

struct Polygon

Public Types

Type Description
enum Result Possible results returned for geofence requests.
std::function< void(Result)> ResultCallback Callback type for asynchronous Geofence calls.

Public Member Functions

Type Name Description
  Geofence (System & system) Constructor. Creates the plugin for a specific System.
  Geofence (std::shared_ptr< System > system) Constructor. Creates the plugin for a specific System.
  ~Geofence () Destructor (internal use only).
  Geofence (const Geofence & other) Copy constructor.
void upload_geofence_async (std::vector< Polygon > polygons, const ResultCallback callback) Upload a geofence.
Result upload_geofence (std::vector< Polygon > polygons)const Upload a geofence.
const Geofence & operator= (const Geofence &)=delete Equality operator (object is not copyable).

Constructor & Destructor Documentation

Geofence()

mavsdk::Geofence::Geofence(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto geofence = Geofence(system);

Parameters

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

Geofence()

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

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto geofence = Geofence(system);

Parameters

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

~Geofence()

mavsdk::Geofence::~Geofence()

Destructor (internal use only).

Geofence()

mavsdk::Geofence::Geofence(const Geofence &other)

Copy constructor.

Parameters

Member Typdef Documentation

typedef ResultCallback

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

Callback type for asynchronous Geofence calls.

Member Enumeration Documentation

enum Result

Possible results returned for geofence requests.

Value Description
Unknown Unknown result.
Success Request succeeded.
Error Error.
TooManyGeofenceItems Too many Polygon objects in the geofence.
Busy Vehicle is busy.
Timeout Request timed out.
InvalidArgument Invalid argument.

Member Function Documentation

upload_geofence_async()

void mavsdk::Geofence::upload_geofence_async(std::vector< Polygon > polygons, const ResultCallback callback)

Upload a geofence.

Polygons are uploaded to a drone. Once uploaded, the geofence will remain on the drone even if a connection is lost.

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

Parameters

upload_geofence()

Result mavsdk::Geofence::upload_geofence(std::vector< Polygon > polygons) const

Upload a geofence.

Polygons are uploaded to a drone. Once uploaded, the geofence will remain on the drone even if a connection is lost.

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

Parameters

  • std::vector< Polygon > polygons -

Returns

Result - Result of request.

operator=()

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

Equality operator (object is not copyable).

Parameters

Returns

 const Geofence & -

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

results matching ""

    No results matching ""