mavsdk::Geofence Class Reference
#include: geofence.h
The Geofence class enables setting a geofence.
Data Structures
struct Polygon
Public Types
Type | Description |
---|---|
enum Result | Possible results returned for geofence requests. |
std::function< void(Result)> result_callback_t | Callback type for async geofence calls. |
Public Member Functions
Type | Name | Description |
---|---|---|
Geofence (System & system) | Constructor. Creates the plugin for a specific System. | |
~Geofence () | Destructor (internal use only). | |
Geofence (const Geofence &)=delete | Copy constructor (object is not copyable). | |
void | send_geofence_async (const std::vector< std::shared_ptr< Polygon >> & polygons, result_callback_t callback) | Uploads a geofence to the system (asynchronous). |
const Geofence & | operator= (const Geofence &)=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 Geofence::Result. |
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 = std::make_shared<Geofence>(system);
Parameters
- System& system - The specific system associated with this plugin.
~Geofence()
mavsdk::Geofence::~Geofence()
Destructor (internal use only).
Geofence()
mavsdk::Geofence::Geofence(const Geofence &)=delete
Copy constructor (object is not copyable).
Parameters
- const Geofence& -
Member Typdef Documentation
typedef result_callback_t
typedef std::function<void(Result)> mavsdk::Geofence::result_callback_t
Callback type for async geofence calls.
Member Enumeration Documentation
enum Result
Possible results returned for geofence requests.
Value | Description |
---|---|
UNKNOWN |
Unknown result. |
SUCCESS |
Request succeeded. |
ERROR |
Error. |
TOO_MANY_GEOFENCE_ITEMS |
Too many Polygon objects in the geofence. |
BUSY |
Vehicle busy. |
TIMEOUT |
Request timed out. |
INVALID_ARGUMENT |
Invalid argument. |
Member Function Documentation
send_geofence_async()
void mavsdk::Geofence::send_geofence_async(const std::vector< std::shared_ptr< Polygon >> &polygons, result_callback_t callback)
Uploads a geofence to the system (asynchronous).
The polygons are uploaded to a drone. Once uploaded the geofence will remain on the drone even if a connection is lost.
Parameters
- const std::vector< std::shared_ptr< Polygon >>& polygons - Reference to vector of polygons.
- result_callback_t callback - Callback to receive result of this request.
operator=()
const Geofence& mavsdk::Geofence::operator=(const Geofence &)=delete
Equality operator (object is not copyable).
Parameters
- const Geofence& -
Returns
const Geofence & -
result_str()
static const char* mavsdk::Geofence::result_str(Result result)
Gets a human-readable English string for an Geofence::Result.
Parameters
- Result result - Enum for which string is required.
Returns
const char * - Human readable string for the Geofence::Result.