Skip to content

Commit b85e70d

Browse files
committed
Merge pull request #122 from DroidPlanner/feature_udp_ping
Feature UDP Client connection
2 parents 8efeab3 + 4b9270a commit b85e70d

File tree

11 files changed

+271
-77
lines changed

11 files changed

+271
-77
lines changed

ClientLib/build.gradle

+2-2
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ apply plugin: 'com.android.library'
22

33
ext {
44
PUBLISH_ARTIFACT_ID = 'dronekit-android'
5-
PUBLISH_VERSION = '2.3.09'
5+
PUBLISH_VERSION = '2.3.11'
66
PROJECT_DESCRIPTION = "Android DroneKit client library."
77
PROJECT_LABELS = ['3DR', '3DR Services', 'DroneAPI', 'Android', 'DroneKit']
88
PROJECT_LICENSES = ['Apache-2.0']
@@ -17,7 +17,7 @@ android {
1717
defaultConfig {
1818
minSdkVersion 14
1919
targetSdkVersion 21
20-
versionCode 20309
20+
versionCode 20311
2121
versionName PUBLISH_VERSION
2222
}
2323

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/connection/ConnectionParameter.java

+46-2
Original file line numberDiff line numberDiff line change
@@ -31,18 +31,62 @@ public DroneSharePrefs getDroneSharePrefs() {
3131
return droneSharePrefs;
3232
}
3333

34+
public String getUniqueId(){
35+
final String uniqueId;
36+
switch(connectionType){
37+
38+
case ConnectionType.TYPE_UDP:
39+
int udpPort = ConnectionType.DEFAULT_UDP_SERVER_PORT;
40+
if(paramsBundle != null){
41+
udpPort = paramsBundle.getInt(ConnectionType.EXTRA_UDP_SERVER_PORT, udpPort);
42+
}
43+
uniqueId = "udp." + udpPort;
44+
break;
45+
46+
case ConnectionType.TYPE_BLUETOOTH:
47+
String btAddress = null;
48+
if(paramsBundle != null){
49+
btAddress = paramsBundle.getString(ConnectionType.EXTRA_BLUETOOTH_ADDRESS);
50+
}
51+
52+
uniqueId = btAddress == null ? "bluetooth" : "bluetooth." + btAddress;
53+
break;
54+
55+
case ConnectionType.TYPE_TCP:
56+
String tcpIp = null;
57+
int tcpPort = ConnectionType.DEFAULT_TCP_SERVER_PORT;
58+
if(paramsBundle != null){
59+
tcpIp = paramsBundle.getString(ConnectionType.EXTRA_TCP_SERVER_IP);
60+
tcpPort = paramsBundle.getInt(ConnectionType.EXTRA_TCP_SERVER_PORT, tcpPort);
61+
}
62+
63+
uniqueId = "tcp" + "." + tcpPort + (tcpIp == null ? "" : "." + tcpIp);
64+
break;
65+
66+
case ConnectionType.TYPE_USB:
67+
uniqueId = "usb";
68+
break;
69+
70+
default:
71+
uniqueId = "";
72+
break;
73+
}
74+
75+
return uniqueId;
76+
}
77+
3478
@Override
3579
public boolean equals(Object o){
3680
if(this == o) return true;
3781
if(!(o instanceof ConnectionParameter)) return false;
3882

3983
ConnectionParameter that = (ConnectionParameter) o;
40-
return toString().equals(that.toString());
84+
return getUniqueId().equals(that.getUniqueId());
4185
}
4286

4387
@Override
4488
public int hashCode(){
45-
return toString().hashCode();
89+
return getUniqueId().hashCode();
4690
}
4791

4892
@Override

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/connection/ConnectionType.java

+23-1
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,29 @@ public class ConnectionType {
2929
/**
3030
* Default value for the upd server port.
3131
*/
32-
public static final int DEFAULT_UPD_SERVER_PORT = 14550;
32+
public static final int DEFAULT_UDP_SERVER_PORT = 14550;
33+
34+
/**
35+
* Key used to retrieve the ip address of the udp server to ping.
36+
*/
37+
public static final String EXTRA_UDP_PING_RECEIVER_IP = "extra_udp_ping_receiver_ip";
38+
39+
/**
40+
* Key used to retrieve the port of the udp server to ping.
41+
*/
42+
public static final String EXTRA_UDP_PING_RECEIVER_PORT = "extra_udp_ping_receiver_port";
43+
44+
/**
45+
* Ping payload.
46+
*/
47+
public static final String EXTRA_UDP_PING_PAYLOAD = "extra_udp_ping_payload";
48+
49+
/**
50+
* How often should the udp ping be performed.
51+
*/
52+
public static final String EXTRA_UDP_PING_PERIOD = "extra_udp_ping_period";
53+
54+
public static final long DEFAULT_UDP_PING_PERIOD = 10000l; //10 seconds
3355

3456
/**
3557
* TCP connection type

ClientLib/src/main/java/com/o3dr/services/android/lib/util/version/VersionUtils.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
*/
99
public class VersionUtils {
1010

11-
public static final int LIB_VERSION = 20200;
11+
public static final int LIB_VERSION = 20202;
1212

1313
public static int getVersion(Context context){
1414
try {

ServiceApp/src/org/droidplanner/services/android/api/DroidPlannerService.java

+32-10
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,8 @@
3939
import org.droidplanner.services.android.utils.analytics.GAUtils;
4040
import org.droidplanner.services.android.utils.file.IO.CameraInfoLoader;
4141

42+
import java.net.InetAddress;
43+
import java.net.UnknownHostException;
4244
import java.util.ArrayList;
4345
import java.util.List;
4446
import java.util.concurrent.ConcurrentHashMap;
@@ -65,7 +67,7 @@ public class DroidPlannerService extends Service {
6567
/**
6668
* Caches mavlink connections per connection type.
6769
*/
68-
final ConcurrentHashMap<ConnectionParameter, AndroidMavLinkConnection> mavConnections = new ConcurrentHashMap<>();
70+
final ConcurrentHashMap<String, AndroidMavLinkConnection> mavConnections = new ConcurrentHashMap<>();
6971

7072
/**
7173
* Caches drone managers per connection type.
@@ -137,12 +139,12 @@ void disconnectDroneManager(DroneManager droneMgr, String appId) throws Connecti
137139

138140
void connectMAVConnection(ConnectionParameter connParams, String listenerTag,
139141
MavLinkConnectionListener listener) {
140-
AndroidMavLinkConnection conn = mavConnections.get(connParams);
142+
AndroidMavLinkConnection conn = mavConnections.get(connParams.getUniqueId());
143+
final int connectionType = connParams.getConnectionType();
144+
final Bundle paramsBundle = connParams.getParamsBundle();
141145
if (conn == null) {
142146

143147
//Create a new mavlink connection
144-
final int connectionType = connParams.getConnectionType();
145-
final Bundle paramsBundle = connParams.getParamsBundle();
146148

147149
switch (connectionType) {
148150
case ConnectionType.TYPE_USB:
@@ -169,8 +171,8 @@ void connectMAVConnection(ConnectionParameter connParams, String listenerTag,
169171
break;
170172

171173
case ConnectionType.TYPE_UDP:
172-
final int udpServerPort = paramsBundle.getInt(ConnectionType
173-
.EXTRA_UDP_SERVER_PORT, ConnectionType.DEFAULT_UPD_SERVER_PORT);
174+
final int udpServerPort = paramsBundle
175+
.getInt(ConnectionType.EXTRA_UDP_SERVER_PORT, ConnectionType.DEFAULT_UDP_SERVER_PORT);
174176
conn = new AndroidUdpConnection(getApplicationContext(), udpServerPort);
175177
Log.d(TAG, "Connecting over udp.");
176178
break;
@@ -180,7 +182,26 @@ void connectMAVConnection(ConnectionParameter connParams, String listenerTag,
180182
return;
181183
}
182184

183-
mavConnections.put(connParams, conn);
185+
mavConnections.put(connParams.getUniqueId(), conn);
186+
}
187+
188+
if (connectionType == ConnectionType.TYPE_UDP) {
189+
final String pingIpAddress = paramsBundle.getString(ConnectionType.EXTRA_UDP_PING_RECEIVER_IP);
190+
if (!TextUtils.isEmpty(pingIpAddress)) {
191+
try {
192+
final InetAddress resolvedAddress = InetAddress.getByName(pingIpAddress);
193+
194+
final int pingPort = paramsBundle.getInt(ConnectionType.EXTRA_UDP_PING_RECEIVER_PORT);
195+
final long pingPeriod = paramsBundle.getLong(ConnectionType.EXTRA_UDP_PING_PERIOD,
196+
ConnectionType.DEFAULT_UDP_PING_PERIOD);
197+
final byte[] pingPayload = paramsBundle.getByteArray(ConnectionType.EXTRA_UDP_PING_PAYLOAD);
198+
199+
((AndroidUdpConnection) conn).addPingTarget(resolvedAddress, pingPort, pingPeriod, pingPayload);
200+
201+
} catch (UnknownHostException e) {
202+
Log.e(TAG, "Unable to resolve UDP ping server ip address.", e);
203+
}
204+
}
184205
}
185206

186207
conn.addMavLinkConnectionListener(listenerTag, listener);
@@ -196,23 +217,23 @@ void connectMAVConnection(ConnectionParameter connParams, String listenerTag,
196217
}
197218

198219
void addLoggingFile(ConnectionParameter connParams, String tag, String loggingFilePath) {
199-
AndroidMavLinkConnection conn = mavConnections.get(connParams);
220+
AndroidMavLinkConnection conn = mavConnections.get(connParams.getUniqueId());
200221
if (conn == null)
201222
return;
202223

203224
conn.addLoggingPath(tag, loggingFilePath);
204225
}
205226

206227
void removeLoggingFile(ConnectionParameter connParams, String tag) {
207-
AndroidMavLinkConnection conn = mavConnections.get(connParams);
228+
AndroidMavLinkConnection conn = mavConnections.get(connParams.getUniqueId());
208229
if (conn == null)
209230
return;
210231

211232
conn.removeLoggingPath(tag);
212233
}
213234

214235
void disconnectMAVConnection(ConnectionParameter connParams, String listenerTag) {
215-
final AndroidMavLinkConnection conn = mavConnections.get(connParams);
236+
final AndroidMavLinkConnection conn = mavConnections.get(connParams.getUniqueId());
216237
if (conn == null)
217238
return;
218239

@@ -289,6 +310,7 @@ public void onCreate() {
289310
updateForegroundNotification();
290311
}
291312

313+
@SuppressLint("NewApi")
292314
private void updateForegroundNotification() {
293315
final Context context = getApplicationContext();
294316

ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java

+1
Original file line numberDiff line numberDiff line change
@@ -685,6 +685,7 @@ public void onDroneEvent(DroneInterfaces.DroneEventsType event, Drone drone) {
685685
break;
686686

687687
case CONNECTION_FAILED:
688+
disconnect();
688689
onConnectionFailed("");
689690
break;
690691

ServiceApp/src/org/droidplanner/services/android/api/MavLinkServiceApi.java

+3-4
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ private DroidPlannerService getService() {
3030
}
3131

3232
public boolean sendData(ConnectionParameter connParams, MAVLinkPacket packet) {
33-
final AndroidMavLinkConnection mavConnection = getService().mavConnections.get(connParams);
33+
final AndroidMavLinkConnection mavConnection = getService().mavConnections.get(connParams.getUniqueId());
3434
if (mavConnection == null) return false;
3535

3636
if (mavConnection.getConnectionStatus() != MavLinkConnection.MAVLINK_DISCONNECTED) {
@@ -42,16 +42,15 @@ public boolean sendData(ConnectionParameter connParams, MAVLinkPacket packet) {
4242
}
4343

4444
public int getConnectionStatus(ConnectionParameter connParams, String tag) {
45-
final AndroidMavLinkConnection mavConnection = getService().mavConnections.get(connParams);
45+
final AndroidMavLinkConnection mavConnection = getService().mavConnections.get(connParams.getUniqueId());
4646
if (mavConnection == null || !mavConnection.hasMavLinkConnectionListener(tag)) {
4747
return MavLinkConnection.MAVLINK_DISCONNECTED;
4848
}
4949

5050
return mavConnection.getConnectionStatus();
5151
}
5252

53-
public void connectMavLink(ConnectionParameter connParams, String tag,
54-
MavLinkConnectionListener listener) {
53+
public void connectMavLink(ConnectionParameter connParams, String tag, MavLinkConnectionListener listener) {
5554
getService().connectMAVConnection(connParams, tag, listener);
5655
}
5756

0 commit comments

Comments
 (0)