forked from mavlink/MAVSDK
-
Notifications
You must be signed in to change notification settings - Fork 0
/
dronecore.h
211 lines (184 loc) · 6.53 KB
/
dronecore.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
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
#pragma once
#include "device.h"
#include <string>
#include <vector>
#include <functional>
namespace dronecore {
class DroneCoreImpl;
/**
* @brief This is the main class of **%DroneCore MAVLink API Library** (for the Dronecode Platform).
* It is used to discover vehicles and manage active connections.
*
* An instance of this class must be created (first) in order to use the library.
* The instance must be destroyed after use in order to break connections and release all resources.
*/
class DroneCore
{
public:
/**
* @brief Constructor.
*/
DroneCore();
/**
* @brief Destructor.
*
* Disconnects all connected vehicles and releases all resources.
*/
~DroneCore();
/**
* @brief Result type returned when adding a connection.
*
* **Note**: DroneCore does not throw exceptions. Instead a result of this type will be
* returned when you add a connection: add_udp_connection().
*/
enum class ConnectionResult {
SUCCESS = 0, /**< @brief %Connection succeeded. */
TIMEOUT, /**< @brief %Connection timed out. */
SOCKET_ERROR, /**< @brief Socket error. */
BIND_ERROR, /**< @brief Bind error. */
SOCKET_CONNECTION_ERROR,
CONNECTION_ERROR, /**< @brief %Connection error. */
NOT_IMPLEMENTED, /**< @brief %Connection type not implemented. */
DEVICE_NOT_CONNECTED, /**< @brief No device is connected. */
DEVICE_BUSY, /**< @brief %Device is busy. */
COMMAND_DENIED, /**< @brief Command is denied. */
DESTINATION_IP_UNKNOWN, /**< @brief %Connection IP is unknown. */
CONNECTIONS_EXHAUSTED /**< @brief %Connections exhausted. */
};
/**
* @brief Translates the DroneCore::ConnectionResult enum to a human-readable English string.
*/
static const char *connection_result_str(ConnectionResult);
/**
* @brief Adds a UDP connection to the default port.
*
* This will listen on UDP port 14540.
*
* @return The result of adding the connection.
*/
ConnectionResult add_udp_connection();
/**
* @brief Adds a UDP connection to the specified port number.
*
* @param local_port_number The local UDP port to listen to.
* @return The result of adding the connection.
*/
ConnectionResult add_udp_connection(int local_port_number);
/**
* @brief Adds a TCP connection to the default IP address/port.
*
* This will connect to local TCP port 5760.
*
* @return The result of adding the connection.
*/
ConnectionResult add_tcp_connection();
/**
* @brief Adds a TCP connection with a specific IP address and port number.
*
* @param remote_ip Remote IP address to connect to.
* @param remote_port The TCP port to connect to.
* @return The result of adding the connection.
*/
ConnectionResult add_tcp_connection(std::string remote_ip, int remote_port);
/**
* @brief Adds a serial connection with the default arguments.
*
* This will connect to serial port ttyS1 (COM0).
*
* @return The result of adding the connection.
*/
ConnectionResult add_serial_connection();
/**
* @brief Adds a serial connection with a specific port (COM or UART dev node) and baudrate as specified.
*
* @param dev_path COM or UART dev node name/path.
* @param baudrate Baudrate of the serial port.
* @return The result of adding the connection.
*/
ConnectionResult add_serial_connection(std::string dev_path, int baudrate);
/**
* @brief Get vector of device UUIDs.
*
* This returns a vector of the UUIDs of all devices that have been discovered.
* If a device doesn't have a UUID then DroneCore will instead use its MAVLink system ID (range: 0..255).
*
* @return A reference to the vector containing the UUIDs.
*/
const std::vector<uint64_t> &device_uuids() const;
/**
* @brief Get the first discovered device.
*
* This returns the first discovered device or a null device if no device has yet been found.
*
* @return A reference to a device.
*/
Device &device() const;
/**
* @brief Get the device with the specified UUID.
*
* This returns a device for a given UUID if such a device has been discovered and a null
* device otherwise.
*
* @param uuid UUID of device to get.
* @return A reference to the specified device.
*/
Device &device(uint64_t uuid) const;
/**
* @brief Callback type for discover and timeout notifications.
*
* @param uuid UUID of device (or MAVLink system ID for devices that don't have a UUID).
*/
typedef std::function<void(uint64_t uuid)> event_callback_t;
/**
* @brief Returns `true` if exactly one device is currently connected.
*
* Connected means we are receiving heartbeats from this device.
* It means the same as "discovered" and "not timed out".
*
* If multiple devices have connected, this will return `false`.
*
* @return `true` if exactly one device is connected.
*/
bool is_connected() const;
/**
* @brief Returns `true` if a device is currently connected.
*
* Connected means we are receiving heartbeats from this device.
* It means the same as "discovered" and "not timed out".
*
* @param uuid UUID of device to check.
* @return `true` if device is connected.
*/
bool is_connected(uint64_t uuid) const;
/**
* @brief Register callback for device discovery.
*
* This sets a callback that will be notified if a new device is discovered.
*
* **Note** Only one callback can be registered at a time. If this function is called several
* times, previous callbacks will be overwritten.
*
* @param callback Callback to register.
*
*/
void register_on_discover(event_callback_t callback);
/**
* @brief Register callback for device timeout.
*
* This sets a callback that will be notified if no heartbeat of the device has been received
* in 3 seconds.
*
* **Note** Only one callback can be registered at a time. If this function is called several
* times, previous callbacks will be overwritten.
*
* @param callback Callback to register.
*/
void register_on_timeout(event_callback_t callback);
private:
/* @private. */
DroneCoreImpl *_impl;
// Non-copyable
DroneCore(const DroneCore &) = delete;
const DroneCore &operator=(const DroneCore &) = delete;
};
} // namespace dronecore