/
geofence.h
123 lines (105 loc) · 3.32 KB
/
geofence.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
#pragma once
#include <functional>
#include <memory>
#include <vector>
#include "plugin_base.h"
namespace mavsdk {
class GeofenceImpl;
class System;
/**
* @brief The Geofence class enables setting a geofence.
*/
class Geofence : public PluginBase {
public:
/**
* @brief Constructor. Creates the plugin for a specific System.
*
* The plugin is typically created as shown below:
*
* ```cpp
* auto geofence = std::make_shared<Geofence>(system);
* ```
*
* @param system The specific system associated with this plugin.
*/
explicit Geofence(System& system);
/**
* @brief Destructor (internal use only).
*/
~Geofence();
/**
* @brief Possible results returned for geofence requests.
*/
enum class Result {
UNKNOWN = 0, /**< @brief %Unknown result. */
SUCCESS, /**< @brief %Request succeeded. */
ERROR, /**< @brief Error. */
TOO_MANY_GEOFENCE_ITEMS, /**< @brief Too many Polygon objects in the geofence. */
BUSY, /**< @brief %Vehicle busy. */
TIMEOUT, /**< @brief Request timed out. */
INVALID_ARGUMENT, /**< @brief Invalid argument. */
};
/**
* @brief Gets a human-readable English string for an Geofence::Result.
*
* @param result Enum for which string is required.
* @return Human readable string for the Geofence::Result.
*/
static const char* result_str(Result result);
/**
* @brief Callback type for async geofence calls.
*/
typedef std::function<void(Result)> result_callback_t;
/**
* @brief Polygon type.
*/
struct Polygon {
/**
* @brief Point type.
*/
struct Point {
double latitude_deg; /**< @brief Latitude in degrees (range: -90 to +90) */
double longitude_deg; /**< @brief Longitude in degrees (range: -180 to 180) */
};
/**
* @brief Polygon Fence Types.
*
* @note MAVLink supports inclusion and exclusion polygon fences.
*/
enum class Type { INCLUSION, EXCLUSION };
std::vector<Point> points; /**< @brief Vector of points that define the polygon. */
Type type; /**< @brief Polygon fence type. */
/**
* @brief Constructor. Creates the Polygon for a specific geometry.
*/
explicit Polygon();
/**
* @brief Destructor (internal use only).
*/
~Polygon();
};
/**
* @brief 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.
*
* @param polygons Reference to vector of polygons.
* @param callback Callback to receive result of this request.
*/
void send_geofence_async(
const std::vector<std::shared_ptr<Polygon>>& polygons, result_callback_t callback);
// Non-copyable
/**
* @brief Copy constructor (object is not copyable).
*/
Geofence(const Geofence&) = delete;
/**
* @brief Equality operator (object is not copyable).
*/
const Geofence& operator=(const Geofence&) = delete;
private:
/** @private Underlying implementation, set at instantiation */
std::unique_ptr<GeofenceImpl> _impl;
};
} // namespace mavsdk