Skip to content

Commit 4b9270a

Browse files
committed
Fixed udp connection issues.
1 parent 566f0ed commit 4b9270a

File tree

7 files changed

+46
-32
lines changed

7 files changed

+46
-32
lines changed

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

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ public String getUniqueId(){
6868
break;
6969

7070
default:
71-
uniqueId = null;
71+
uniqueId = "";
7272
break;
7373
}
7474

@@ -81,12 +81,12 @@ public boolean equals(Object o){
8181
if(!(o instanceof ConnectionParameter)) return false;
8282

8383
ConnectionParameter that = (ConnectionParameter) o;
84-
return toString().equals(that.toString());
84+
return getUniqueId().equals(that.getUniqueId());
8585
}
8686

8787
@Override
8888
public int hashCode(){
89-
return toString().hashCode();
89+
return getUniqueId().hashCode();
9090
}
9191

9292
@Override

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -173,7 +173,7 @@ void connectMAVConnection(ConnectionParameter connParams, String listenerTag,
173173
case ConnectionType.TYPE_UDP:
174174
final int udpServerPort = paramsBundle
175175
.getInt(ConnectionType.EXTRA_UDP_SERVER_PORT, ConnectionType.DEFAULT_UDP_SERVER_PORT);
176-
conn = new AndroidUdpConnection(getApplicationContext(), udpServerPort, new Handler(Looper.getMainLooper()));
176+
conn = new AndroidUdpConnection(getApplicationContext(), udpServerPort);
177177
Log.d(TAG, "Connecting over udp.");
178178
break;
179179

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

Lines changed: 1 addition & 0 deletions
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

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -50,8 +50,7 @@ public int getConnectionStatus(ConnectionParameter connParams, String tag) {
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

ServiceApp/src/org/droidplanner/services/android/communication/connection/AndroidUdpConnection.java

Lines changed: 31 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
11
package org.droidplanner.services.android.communication.connection;
22

33
import android.content.Context;
4-
import android.os.Handler;
54
import android.util.Log;
65

76
import org.droidplanner.core.MAVLink.connection.UdpConnection;
@@ -10,7 +9,9 @@
109
import java.io.IOException;
1110
import java.net.InetAddress;
1211
import java.util.HashSet;
13-
import java.util.LinkedList;
12+
import java.util.concurrent.Executors;
13+
import java.util.concurrent.ScheduledExecutorService;
14+
import java.util.concurrent.TimeUnit;
1415

1516
public class AndroidUdpConnection extends AndroidMavLinkConnection {
1617

@@ -21,12 +22,11 @@ public class AndroidUdpConnection extends AndroidMavLinkConnection {
2122
private final UdpConnection mConnectionImpl;
2223
private final int serverPort;
2324

24-
private Handler pingHandler;
25+
private ScheduledExecutorService pingRunner;
2526

26-
public AndroidUdpConnection(Context context, int udpServerPort, Handler pingHandler) {
27+
public AndroidUdpConnection(Context context, int udpServerPort) {
2728
super(context);
2829
this.serverPort = udpServerPort;
29-
this.pingHandler = pingHandler;
3030

3131
mConnectionImpl = new UdpConnection() {
3232
@Override
@@ -53,22 +53,24 @@ protected void onConnectionFailed(String errMsg) {
5353
}
5454

5555
public void addPingTarget(final InetAddress address, final int port, final long period, final byte[] payload) {
56-
if (pingHandler == null || address == null || payload == null || period <= 0)
56+
if (address == null || payload == null || period <= 0)
5757
return;
5858

5959
final PingTask pingTask = new PingTask(address, port, period, payload);
6060

6161
pingTasks.add(pingTask);
6262

63-
if (getConnectionStatus() == AndroidMavLinkConnection.MAVLINK_CONNECTED)
64-
pingHandler.postDelayed(pingTask, period);
63+
if (getConnectionStatus() == AndroidMavLinkConnection.MAVLINK_CONNECTED && pingRunner != null && !pingRunner.isShutdown())
64+
pingRunner.scheduleWithFixedDelay(pingTask, 0, period, TimeUnit.MILLISECONDS);
6565
}
6666

6767
@Override
6868
protected void closeConnection() throws IOException {
69-
if (pingHandler != null) {
70-
for (PingTask pingTask : pingTasks)
71-
pingHandler.removeCallbacks(pingTask);
69+
Log.d(TAG, "Closing udp connection.");
70+
if (pingRunner != null) {
71+
Log.d(TAG, "Shutting down pinging tasks.");
72+
pingRunner.shutdownNow();
73+
pingRunner = null;
7274
}
7375

7476
mConnectionImpl.closeConnection();
@@ -81,12 +83,14 @@ protected void loadPreferences() {
8183

8284
@Override
8385
protected void openConnection() throws IOException {
86+
Log.d(TAG, "Opening udp connection");
8487
mConnectionImpl.openConnection();
8588

86-
if (pingHandler != null) {
87-
for (PingTask pingTask : pingTasks)
88-
pingHandler.post(pingTask);
89-
}
89+
if (pingRunner == null || pingRunner.isShutdown())
90+
pingRunner = Executors.newSingleThreadScheduledExecutor();
91+
92+
for (PingTask pingTask : pingTasks)
93+
pingRunner.scheduleWithFixedDelay(pingTask, 0, pingTask.period, TimeUnit.MILLISECONDS);
9094
}
9195

9296
@Override
@@ -119,27 +123,34 @@ private PingTask(InetAddress address, int port, long period, byte[] payload) {
119123
}
120124

121125
@Override
122-
public boolean equals(Object other){
123-
if(this == other)
126+
public boolean equals(Object other) {
127+
if (this == other)
124128
return true;
125129

126-
if(!(other instanceof AndroidUdpConnection))
130+
if (!(other instanceof PingTask))
127131
return false;
128132

129133
PingTask that = (PingTask) other;
130134
return this.address.equals(that.address) && this.port == that.port && this.period == that.period;
131135
}
132136

137+
@Override
138+
public int hashCode(){
139+
return toString().hashCode();
140+
}
141+
133142
@Override
134143
public void run() {
135144
try {
136145
mConnectionImpl.sendBuffer(address, port, payload);
137146
} catch (IOException e) {
138147
Log.e(TAG, "Error occurred while sending ping message.", e);
139148
}
149+
}
140150

141-
if (getConnectionStatus() == AndroidMavLinkConnection.MAVLINK_CONNECTED)
142-
pingHandler.postDelayed(this, period);
151+
@Override
152+
public String toString(){
153+
return "[" + address.toString() + "; " + port + "; " + period + "]";
143154
}
144155
}
145156
}

ServiceApp/src/org/droidplanner/services/android/communication/service/MAVLinkClient.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,9 @@ public void openConnection() {
8686
return;
8787

8888
final String tag = toString();
89-
if (mavLinkApi.getConnectionStatus(this.connParams, tag) == MavLinkConnection.MAVLINK_DISCONNECTED) {
89+
final int connectionStatus = mavLinkApi.getConnectionStatus(this.connParams, tag);
90+
if (connectionStatus == MavLinkConnection.MAVLINK_DISCONNECTED
91+
|| connectionStatus == MavLinkConnection.MAVLINK_CONNECTING) {
9092
mavLinkApi.connectMavLink(this.connParams, tag, mConnectionListener);
9193
}
9294
}

ServiceApp/src/org/droidplanner/services/android/drone/DroneManager.java

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -168,19 +168,20 @@ public void disconnect(String appId) throws ConnectionException {
168168
if (TextUtils.isEmpty(appId))
169169
return;
170170

171+
Log.d(TAG, "Disconnecting client " + appId);
171172
DroneEventsListener listener = connectedApps.remove(appId);
172173

174+
final MAVLinkClient mavClient = (MAVLinkClient) drone.getMavClient();
173175
if (listener != null) {
174-
MAVLinkClient mavClient = (MAVLinkClient) drone.getMavClient();
175176
mavClient.removeLoggingFile(appId);
176177

177-
if (mavClient.isConnected() && connectedApps.isEmpty()) {
178-
mavClient.closeConnection();
179-
}
180-
181178
listener.onDroneEvent(DroneInterfaces.DroneEventsType.DISCONNECTED, drone);
182179
notifyDisconnected(appId, listener);
183180
}
181+
182+
if (mavClient.isConnected() && connectedApps.isEmpty()) {
183+
mavClient.closeConnection();
184+
}
184185
}
185186

186187
@Override

0 commit comments

Comments
 (0)