Skip to content

Commit

Permalink
Merge pull request #149 from DroidPlanner/fix_optimization
Browse files Browse the repository at this point in the history
Events dispatching optimization
  • Loading branch information
m4gr3d committed May 28, 2015
2 parents 8816ea2 + e392484 commit e1b1d58
Show file tree
Hide file tree
Showing 3 changed files with 74 additions and 29 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@ public abstract class UdpConnection extends MavLinkConnection {

private int hostPort;
private InetAddress hostAdd;
private DatagramPacket sendPacket;
private DatagramPacket receivePacket;

private void getUdpStream() throws IOException {
final DatagramSocket socket = new DatagramSocket(serverPort);
Expand Down Expand Up @@ -46,8 +48,14 @@ public final void sendBuffer(byte[] buffer) throws IOException {
try {
if (hostAdd != null) { // We can't send to our sister until they
// have connected to us
DatagramPacket packet = new DatagramPacket(buffer, buffer.length, hostAdd, hostPort);
socket.send(packet);
if(sendPacket == null)
sendPacket = new DatagramPacket(buffer, buffer.length, hostAdd, hostPort);
else{
sendPacket.setData(buffer, 0, buffer.length);
sendPacket.setAddress(hostAdd);
sendPacket.setPort(hostPort);
}
socket.send(sendPacket);
}
} catch (Exception e) {
e.printStackTrace();
Expand All @@ -65,15 +73,19 @@ public void sendBuffer(InetAddress targetAddr, int targetPort, byte[] buffer) th

@Override
public final int readDataBlock(byte[] readData) throws IOException {
final DatagramSocket socket = socketRef.get();
if(socket == null)
return 0;

DatagramPacket packet = new DatagramPacket(readData, readData.length);
socket.receive(packet);
hostAdd = packet.getAddress();
hostPort = packet.getPort();
return packet.getLength();
final DatagramSocket socket = socketRef.get();
if (socket == null)
return 0;

if (receivePacket == null)
receivePacket = new DatagramPacket(readData, readData.length);
else
receivePacket.setData(readData);

socket.receive(receivePacket);
hostAdd = receivePacket.getAddress();
hostPort = receivePacket.getPort();
return receivePacket.getLength();
}

@Override
Expand Down
Original file line number Diff line number Diff line change
@@ -1,34 +1,67 @@
package org.droidplanner.core.drone;

import java.util.concurrent.ConcurrentLinkedQueue;

import org.droidplanner.core.drone.DroneInterfaces.DroneEventsType;
import org.droidplanner.core.drone.DroneInterfaces.OnDroneListener;
import org.droidplanner.core.model.Drone;

import java.util.concurrent.ConcurrentLinkedQueue;
import java.util.concurrent.atomic.AtomicBoolean;

public class DroneEvents extends DroneVariable {

public DroneEvents(Drone myDrone) {
super(myDrone);
}
private static final long EVENT_DISPATCHING_DELAY = 33l; //milliseconds

private final ConcurrentLinkedQueue<OnDroneListener> droneListeners = new ConcurrentLinkedQueue<OnDroneListener>();
private final AtomicBoolean isDispatcherRunning = new AtomicBoolean(false);

public void addDroneListener(OnDroneListener listener) {
if (listener != null & !droneListeners.contains(listener))
droneListeners.add(listener);
}
private final Runnable eventDispatcher = new Runnable() {

public void removeDroneListener(OnDroneListener listener) {
if (listener != null && droneListeners.contains(listener))
droneListeners.remove(listener);
}
@Override
public void run() {
handler.removeCallbacks(this);

final DroneEventsType event = eventQueue.poll();
if (event == null) {
isDispatcherRunning.set(false);
return;
}

public void notifyDroneEvent(DroneEventsType event) {
if (event != null && !droneListeners.isEmpty()) {
for (OnDroneListener listener : droneListeners) {
listener.onDroneEvent(event, myDrone);
}

handler.removeCallbacks(this);
handler.postDelayed(this, EVENT_DISPATCHING_DELAY);

isDispatcherRunning.set(true);
}
}
};

private final DroneInterfaces.Handler handler;

public DroneEvents(Drone myDrone, DroneInterfaces.Handler handler) {
super(myDrone);
this.handler = handler;
}

private final ConcurrentLinkedQueue<OnDroneListener> droneListeners = new ConcurrentLinkedQueue<OnDroneListener>();
private final ConcurrentLinkedQueue<DroneEventsType> eventQueue = new ConcurrentLinkedQueue<>();

public void addDroneListener(OnDroneListener listener) {
if (listener != null & !droneListeners.contains(listener))
droneListeners.add(listener);
}

public void removeDroneListener(OnDroneListener listener) {
if (listener != null && droneListeners.contains(listener))
droneListeners.remove(listener);
}

public void notifyDroneEvent(DroneEventsType event) {
if (event == null || droneListeners.isEmpty() || eventQueue.contains(event))
return;

eventQueue.add(event);
if (isDispatcherRunning.compareAndSet(false, true))
handler.postDelayed(eventDispatcher, EVENT_DISPATCHING_DELAY);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ public DroneImpl(MAVLinkStreams.MAVLinkOutputStream mavClient, DroneInterfaces.C
this.preferences = pref;
this.logListener = logListener;

events = new DroneEvents(this);
events = new DroneEvents(this, handler);
state = new State(this, clock, handler, warningParser);
heartbeat = new HeartBeat(this, handler);
parameters = new Parameters(this, handler);
Expand Down

0 comments on commit e1b1d58

Please sign in to comment.