Skip to content

Commit e1b1d58

Browse files
committed
Merge pull request #149 from DroidPlanner/fix_optimization
Events dispatching optimization
2 parents 8816ea2 + e392484 commit e1b1d58

File tree

3 files changed

+74
-29
lines changed

3 files changed

+74
-29
lines changed

dependencyLibs/Core/src/org/droidplanner/core/MAVLink/connection/UdpConnection.java

Lines changed: 23 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@ public abstract class UdpConnection extends MavLinkConnection {
1616

1717
private int hostPort;
1818
private InetAddress hostAdd;
19+
private DatagramPacket sendPacket;
20+
private DatagramPacket receivePacket;
1921

2022
private void getUdpStream() throws IOException {
2123
final DatagramSocket socket = new DatagramSocket(serverPort);
@@ -46,8 +48,14 @@ public final void sendBuffer(byte[] buffer) throws IOException {
4648
try {
4749
if (hostAdd != null) { // We can't send to our sister until they
4850
// have connected to us
49-
DatagramPacket packet = new DatagramPacket(buffer, buffer.length, hostAdd, hostPort);
50-
socket.send(packet);
51+
if(sendPacket == null)
52+
sendPacket = new DatagramPacket(buffer, buffer.length, hostAdd, hostPort);
53+
else{
54+
sendPacket.setData(buffer, 0, buffer.length);
55+
sendPacket.setAddress(hostAdd);
56+
sendPacket.setPort(hostPort);
57+
}
58+
socket.send(sendPacket);
5159
}
5260
} catch (Exception e) {
5361
e.printStackTrace();
@@ -65,15 +73,19 @@ public void sendBuffer(InetAddress targetAddr, int targetPort, byte[] buffer) th
6573

6674
@Override
6775
public final int readDataBlock(byte[] readData) throws IOException {
68-
final DatagramSocket socket = socketRef.get();
69-
if(socket == null)
70-
return 0;
71-
72-
DatagramPacket packet = new DatagramPacket(readData, readData.length);
73-
socket.receive(packet);
74-
hostAdd = packet.getAddress();
75-
hostPort = packet.getPort();
76-
return packet.getLength();
76+
final DatagramSocket socket = socketRef.get();
77+
if (socket == null)
78+
return 0;
79+
80+
if (receivePacket == null)
81+
receivePacket = new DatagramPacket(readData, readData.length);
82+
else
83+
receivePacket.setData(readData);
84+
85+
socket.receive(receivePacket);
86+
hostAdd = receivePacket.getAddress();
87+
hostPort = receivePacket.getPort();
88+
return receivePacket.getLength();
7789
}
7890

7991
@Override
Lines changed: 50 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -1,34 +1,67 @@
11
package org.droidplanner.core.drone;
22

3-
import java.util.concurrent.ConcurrentLinkedQueue;
4-
53
import org.droidplanner.core.drone.DroneInterfaces.DroneEventsType;
64
import org.droidplanner.core.drone.DroneInterfaces.OnDroneListener;
75
import org.droidplanner.core.model.Drone;
86

7+
import java.util.concurrent.ConcurrentLinkedQueue;
8+
import java.util.concurrent.atomic.AtomicBoolean;
9+
910
public class DroneEvents extends DroneVariable {
1011

11-
public DroneEvents(Drone myDrone) {
12-
super(myDrone);
13-
}
12+
private static final long EVENT_DISPATCHING_DELAY = 33l; //milliseconds
1413

15-
private final ConcurrentLinkedQueue<OnDroneListener> droneListeners = new ConcurrentLinkedQueue<OnDroneListener>();
14+
private final AtomicBoolean isDispatcherRunning = new AtomicBoolean(false);
1615

17-
public void addDroneListener(OnDroneListener listener) {
18-
if (listener != null & !droneListeners.contains(listener))
19-
droneListeners.add(listener);
20-
}
16+
private final Runnable eventDispatcher = new Runnable() {
2117

22-
public void removeDroneListener(OnDroneListener listener) {
23-
if (listener != null && droneListeners.contains(listener))
24-
droneListeners.remove(listener);
25-
}
18+
@Override
19+
public void run() {
20+
handler.removeCallbacks(this);
21+
22+
final DroneEventsType event = eventQueue.poll();
23+
if (event == null) {
24+
isDispatcherRunning.set(false);
25+
return;
26+
}
2627

27-
public void notifyDroneEvent(DroneEventsType event) {
28-
if (event != null && !droneListeners.isEmpty()) {
2928
for (OnDroneListener listener : droneListeners) {
3029
listener.onDroneEvent(event, myDrone);
3130
}
31+
32+
handler.removeCallbacks(this);
33+
handler.postDelayed(this, EVENT_DISPATCHING_DELAY);
34+
35+
isDispatcherRunning.set(true);
3236
}
33-
}
37+
};
38+
39+
private final DroneInterfaces.Handler handler;
40+
41+
public DroneEvents(Drone myDrone, DroneInterfaces.Handler handler) {
42+
super(myDrone);
43+
this.handler = handler;
44+
}
45+
46+
private final ConcurrentLinkedQueue<OnDroneListener> droneListeners = new ConcurrentLinkedQueue<OnDroneListener>();
47+
private final ConcurrentLinkedQueue<DroneEventsType> eventQueue = new ConcurrentLinkedQueue<>();
48+
49+
public void addDroneListener(OnDroneListener listener) {
50+
if (listener != null & !droneListeners.contains(listener))
51+
droneListeners.add(listener);
52+
}
53+
54+
public void removeDroneListener(OnDroneListener listener) {
55+
if (listener != null && droneListeners.contains(listener))
56+
droneListeners.remove(listener);
57+
}
58+
59+
public void notifyDroneEvent(DroneEventsType event) {
60+
if (event == null || droneListeners.isEmpty() || eventQueue.contains(event))
61+
return;
62+
63+
eventQueue.add(event);
64+
if (isDispatcherRunning.compareAndSet(false, true))
65+
handler.postDelayed(eventDispatcher, EVENT_DISPATCHING_DELAY);
66+
}
3467
}

dependencyLibs/Core/src/org/droidplanner/core/drone/DroneImpl.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ public DroneImpl(MAVLinkStreams.MAVLinkOutputStream mavClient, DroneInterfaces.C
7272
this.preferences = pref;
7373
this.logListener = logListener;
7474

75-
events = new DroneEvents(this);
75+
events = new DroneEvents(this, handler);
7676
state = new State(this, clock, handler, warningParser);
7777
heartbeat = new HeartBeat(this, handler);
7878
parameters = new Parameters(this, handler);

0 commit comments

Comments
 (0)