forked from mavlink/MAVSDK
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathdronecode_sdk.h
More file actions
236 lines (209 loc) · 7.86 KB
/
dronecode_sdk.h
File metadata and controls
236 lines (209 loc) · 7.86 KB
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
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
#pragma once
#include <string>
#include <memory>
#include <vector>
#include <functional>
#include "system.h"
#include "connection_result.h"
namespace dronecode_sdk {
class DronecodeSDKImpl;
class System;
/**
* @brief This is the main class of Dronecode SDK (a 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 DronecodeSDK {
public:
/** @brief Default UDP bind IP (accepts any incoming connections). */
static constexpr auto DEFAULT_UDP_BIND_IP = "0.0.0.0";
/** @brief Default UDP bind port (same port as used by MAVROS). */
static constexpr int DEFAULT_UDP_PORT = 14540;
/** @brief Default TCP remote IP (localhost). */
static constexpr auto DEFAULT_TCP_REMOTE_IP = "127.0.0.1";
/** @brief Default TCP remote port. */
static constexpr int DEFAULT_TCP_REMOTE_PORT = 5760;
/** @brief Default serial baudrate. */
static constexpr int DEFAULT_SERIAL_BAUDRATE = 57600;
/**
* @brief Constructor.
*/
DronecodeSDK();
/**
* @brief Destructor.
*
* Disconnects all connected vehicles and releases all resources.
*/
~DronecodeSDK();
/**
* @brief Adds Connection via URL
*
* Supports connection: Serial, TCP or UDP.
* Connection URL format should be:
* - UDP - udp://[Bind_host][:Bind_port]
* - TCP - tcp://[Remote_host][:Remote_port]
* - Serial - serial://Dev_Node[:Baudrate]
*
* @param connection_url connection URL string.
* @return The result of adding the connection.
*/
ConnectionResult add_any_connection(const std::string &connection_url);
/**
* @brief Adds a UDP connection to the specified port number.
*
* Any incoming connections are accepted (0.0.0.0).
*
* @param local_port The local UDP port to listen to (defaults to 14540, the same as MAVROS).
* @return The result of adding the connection.
*/
ConnectionResult add_udp_connection(int local_port = DEFAULT_UDP_PORT);
/**
* @brief Adds a UDP connection to the specified port number and local interface.
*
* To accept only local connections of the machine, use 127.0.0.1.
* For any incoming connections, use 0.0.0.0.
*
* @param local_ip The local UDP IP address to listen to.
* @param local_port The local UDP port to listen to (defaults to 14540, the same as MAVROS).
* @return The result of adding the connection.
*/
ConnectionResult add_udp_connection(const std::string &local_ip,
int local_port = DEFAULT_UDP_PORT);
/**
* @brief Adds a TCP connection with a specific port number on localhost.
*
* @param remote_port The TCP port to connect to (defaults to 5760).
* @return The result of adding the connection.
*/
ConnectionResult add_tcp_connection(int remote_port = DEFAULT_TCP_REMOTE_PORT);
/**
* @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 (defaults to 5760).
* @return The result of adding the connection.
*/
ConnectionResult add_tcp_connection(const std::string &remote_ip,
int remote_port = DEFAULT_TCP_REMOTE_PORT);
/**
* @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 (e.g. "/dev/ttyS0", or "COM3" on Windows).
* @param baudrate Baudrate of the serial port (defaults to 57600).
* @return The result of adding the connection.
*/
ConnectionResult add_serial_connection(const std::string &dev_path,
int baudrate = DEFAULT_SERIAL_BAUDRATE);
/**
* @brief Possible configurations.
*/
enum class Configuration {
GroundStation, /**< @brief SDK is used as a ground station. */
CompanionComputer /**< @brief SDK is used on a companion computer onboard the system (e.g.
drone). */
};
/**
* @brief Set `Configuration` of SDK.
*
* The default configuration is `Configuration::GroundStation`
* The configuration is used in order to set the MAVLink system ID, the
* component ID, as well as the MAV_TYPE accordingly.
*
* @param configuration Configuration chosen.
*/
void set_configuration(Configuration configuration);
/**
* @brief Get vector of system UUIDs.
*
* This returns a vector of the UUIDs of all systems that have been discovered.
* If a system doesn't have a UUID then DronecodeSDK will instead use its MAVLink system ID
* (range: 0..255).
*
* @return A vector containing the UUIDs.
*/
std::vector<uint64_t> system_uuids() const;
/**
* @brief Get the first discovered system.
*
* This returns the first discovered system or a null system if no system has yet been found.
*
* @return A reference to a system.
*/
System &system() const;
/**
* @brief Get the system with the specified UUID.
*
* This returns a system for a given UUID if such a system has been discovered and a null
* system otherwise.
*
* @param uuid UUID of system to get.
* @return A reference to the specified system.
*/
System &system(uint64_t uuid) const;
/**
* @brief Callback type for discover and timeout notifications.
*
* @param uuid UUID of system (or MAVLink system ID for systems that don't have a UUID).
*/
typedef std::function<void(uint64_t uuid)> event_callback_t;
/**
* @brief Returns `true` if exactly one system is currently connected.
*
* Connected means we are receiving heartbeats from this system.
* It means the same as "discovered" and "not timed out".
*
* If multiple systems have connected, this will return `false`.
*
* @return `true` if exactly one system is connected.
*/
bool is_connected() const;
/**
* @brief Returns `true` if a system is currently connected.
*
* Connected means we are receiving heartbeats from this system.
* It means the same as "discovered" and "not timed out".
*
* @param uuid UUID of system to check.
* @return `true` if system is connected.
*/
bool is_connected(uint64_t uuid) const;
/**
* @brief Register callback for system discovery.
*
* This sets a callback that will be notified if a new system is discovered.
*
* If systems have been discovered before this callback is registered, they will be notified
* at the time this callback is registered.
*
* @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 system timeout.
*
* This sets a callback that will be notified if no heartbeat of the system 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. */
std::unique_ptr<DronecodeSDKImpl> _impl;
// Non-copyable
DronecodeSDK(const DronecodeSDK &) = delete;
const DronecodeSDK &operator=(const DronecodeSDK &) = delete;
};
} // namespace dronecode_sdk