mavsdk::Geofence Class Reference ​
#include: geofence.h
Enable setting a geofence.
Data Structures ​
struct Circle
struct GeofenceData
struct Point
struct Polygon
Public Types ​
Type | Description |
---|---|
enum FenceType | Geofence types. |
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 () override | Destructor (internal use only). |
 | Geofence (const Geofence & other) | Copy constructor. |
void | upload_geofence_async (GeofenceData geofence_data, const ResultCallback callback) | Upload geofences. |
Result | upload_geofence (GeofenceData geofence_data)const | Upload geofences. |
void | clear_geofence_async (const ResultCallback callback) | Clear all geofences saved on the vehicle. |
Result | clear_geofence () const | Clear all geofences saved on the vehicle. |
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() override
Destructor (internal use only).
Geofence() ​
mavsdk::Geofence::Geofence(const Geofence &other)
Copy constructor.
Parameters
- const Geofence& other -
Member Typdef Documentation ​
typedef ResultCallback ​
using mavsdk::Geofence::ResultCallback = std::function<void(Result)>
Callback type for asynchronous Geofence calls.
Member Enumeration Documentation ​
enum FenceType ​
Geofence types.
Value | Description |
---|---|
Inclusion | Type representing an inclusion fence. |
Exclusion | Type representing an exclusion fence. |
enum Result ​
Possible results returned for geofence requests.
Value | Description |
---|---|
Unknown | Unknown result. |
Success | Request succeeded. |
Error | Error. |
TooManyGeofenceItems | Too many objects in the geofence. |
Busy | Vehicle is busy. |
Timeout | Request timed out. |
InvalidArgument | Invalid argument. |
NoSystem | No system connected. |
Member Function Documentation ​
upload_geofence_async() ​
void mavsdk::Geofence::upload_geofence_async(GeofenceData geofence_data, const ResultCallback callback)
Upload geofences.
Polygon and Circular geofences 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
- GeofenceData geofence_data -
- const ResultCallback callback -
upload_geofence() ​
Result mavsdk::Geofence::upload_geofence(GeofenceData geofence_data) const
Upload geofences.
Polygon and Circular geofences 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
- GeofenceData geofence_data -
Returns
 Result - Result of request.
clear_geofence_async() ​
void mavsdk::Geofence::clear_geofence_async(const ResultCallback callback)
Clear all geofences saved on the vehicle.
This function is non-blocking. See 'clear_geofence' for the blocking counterpart.
Parameters
- const ResultCallback callback -
clear_geofence() ​
Result mavsdk::Geofence::clear_geofence() const
Clear all geofences saved on the vehicle.
This function is blocking. See 'clear_geofence_async' for the non-blocking counterpart.
Returns
 Result - Result of request.
operator=() ​
const Geofence & mavsdk::Geofence::operator=(const Geofence &)=delete
Equality operator (object is not copyable).
Parameters
- const Geofence& -
Returns
 const Geofence & -