39
39
import org .droidplanner .services .android .utils .analytics .GAUtils ;
40
40
import org .droidplanner .services .android .utils .file .IO .CameraInfoLoader ;
41
41
42
+ import java .net .InetAddress ;
43
+ import java .net .UnknownHostException ;
42
44
import java .util .ArrayList ;
43
45
import java .util .List ;
44
46
import java .util .concurrent .ConcurrentHashMap ;
@@ -65,7 +67,7 @@ public class DroidPlannerService extends Service {
65
67
/**
66
68
* Caches mavlink connections per connection type.
67
69
*/
68
- final ConcurrentHashMap <ConnectionParameter , AndroidMavLinkConnection > mavConnections = new ConcurrentHashMap <>();
70
+ final ConcurrentHashMap <String , AndroidMavLinkConnection > mavConnections = new ConcurrentHashMap <>();
69
71
70
72
/**
71
73
* Caches drone managers per connection type.
@@ -137,12 +139,12 @@ void disconnectDroneManager(DroneManager droneMgr, String appId) throws Connecti
137
139
138
140
void connectMAVConnection (ConnectionParameter connParams , String listenerTag ,
139
141
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 ();
141
145
if (conn == null ) {
142
146
143
147
//Create a new mavlink connection
144
- final int connectionType = connParams .getConnectionType ();
145
- final Bundle paramsBundle = connParams .getParamsBundle ();
146
148
147
149
switch (connectionType ) {
148
150
case ConnectionType .TYPE_USB :
@@ -169,8 +171,8 @@ void connectMAVConnection(ConnectionParameter connParams, String listenerTag,
169
171
break ;
170
172
171
173
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 );
174
176
conn = new AndroidUdpConnection (getApplicationContext (), udpServerPort );
175
177
Log .d (TAG , "Connecting over udp." );
176
178
break ;
@@ -180,7 +182,26 @@ void connectMAVConnection(ConnectionParameter connParams, String listenerTag,
180
182
return ;
181
183
}
182
184
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
+ }
184
205
}
185
206
186
207
conn .addMavLinkConnectionListener (listenerTag , listener );
@@ -196,23 +217,23 @@ void connectMAVConnection(ConnectionParameter connParams, String listenerTag,
196
217
}
197
218
198
219
void addLoggingFile (ConnectionParameter connParams , String tag , String loggingFilePath ) {
199
- AndroidMavLinkConnection conn = mavConnections .get (connParams );
220
+ AndroidMavLinkConnection conn = mavConnections .get (connParams . getUniqueId () );
200
221
if (conn == null )
201
222
return ;
202
223
203
224
conn .addLoggingPath (tag , loggingFilePath );
204
225
}
205
226
206
227
void removeLoggingFile (ConnectionParameter connParams , String tag ) {
207
- AndroidMavLinkConnection conn = mavConnections .get (connParams );
228
+ AndroidMavLinkConnection conn = mavConnections .get (connParams . getUniqueId () );
208
229
if (conn == null )
209
230
return ;
210
231
211
232
conn .removeLoggingPath (tag );
212
233
}
213
234
214
235
void disconnectMAVConnection (ConnectionParameter connParams , String listenerTag ) {
215
- final AndroidMavLinkConnection conn = mavConnections .get (connParams );
236
+ final AndroidMavLinkConnection conn = mavConnections .get (connParams . getUniqueId () );
216
237
if (conn == null )
217
238
return ;
218
239
@@ -289,6 +310,7 @@ public void onCreate() {
289
310
updateForegroundNotification ();
290
311
}
291
312
313
+ @ SuppressLint ("NewApi" )
292
314
private void updateForegroundNotification () {
293
315
final Context context = getApplicationContext ();
294
316
0 commit comments