Skip to content

Commit

Permalink
Merge pull request #59 from 3drobotics/connect_wifi_inapp
Browse files Browse the repository at this point in the history
[WIP] Updated services to support in app wifi
  • Loading branch information
m4gr3d committed Feb 27, 2016
2 parents 9d2a69b + 1330074 commit 9e75fff
Show file tree
Hide file tree
Showing 8 changed files with 310 additions and 84 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import android.os.Bundle;
import android.os.Parcel;
import android.os.Parcelable;
import android.support.annotation.Nullable;
import android.text.TextUtils;

/**
Expand All @@ -14,6 +15,149 @@ public class ConnectionParameter implements Parcelable {
private final Bundle paramsBundle;
private final DroneSharePrefs droneSharePrefs;

/**
* @return Returns a new {@link ConnectionParameter} with type {@link ConnectionType#TYPE_USB}
* and baud rate {@link ConnectionType#DEFAULT_USB_BAUD_RATE}.
*/
public static ConnectionParameter newUsbConnection() {
return newUsbConnection(ConnectionType.DEFAULT_USB_BAUD_RATE);
}

/**
*
* @param usbBaudRate Baud rate for USB connection.
*
* @return Returns a new {@link ConnectionParameter} with type {@link ConnectionType#TYPE_USB}.
*/
public static ConnectionParameter newUsbConnection(int usbBaudRate) {
Bundle paramsBundle = new Bundle(1);
paramsBundle.putInt(ConnectionType.EXTRA_USB_BAUD_RATE, usbBaudRate);

return new ConnectionParameter(ConnectionType.TYPE_USB, paramsBundle);
}

/**
*
* @return Returns {@link ConnectionParameter} with type {@link ConnectionType#TYPE_UDP}, using
* {@link ConnectionType#DEFAULT_UDP_SERVER_PORT} port.
*/
public static ConnectionParameter newUdpConnection() {
return newUdpConnection(ConnectionType.DEFAULT_UDP_SERVER_PORT);
}

/**
*
* @param udpPort Port for the UDP connection.
*
* @return Returns {@link ConnectionParameter} with type {@link ConnectionType#TYPE_UDP}.
*/
public static ConnectionParameter newUdpConnection(int udpPort) {
return newUdpConnection(udpPort, null, 0, null);
}

/**
*
* @param udpPort Port for the UDP connection.
* @param udpPingReceiverIp IP address of the UDP server to ping. If this value is null, it is ignored
* along with udpPingReceiverPort and udpPingPayload.
* @param udpPingReceiverPort Port of the UDP server to ping.
* @param udpPingPayload Ping payload.
*
* @return Returns {@link ConnectionParameter} with type {@link ConnectionType#TYPE_UDP}. The ping
* period is set to {@link ConnectionType#DEFAULT_UDP_PING_PERIOD}
*/
public static ConnectionParameter newUdpConnection(int udpPort, @Nullable String udpPingReceiverIp, int udpPingReceiverPort,
byte[] udpPingPayload) {
return newUdpConnection(udpPort, udpPingReceiverIp, udpPingReceiverPort, udpPingPayload, ConnectionType.DEFAULT_UDP_PING_PERIOD);
}

/**
*
* @param udpPort Port for the UDP connection.
* @param udpPingReceiverIp IP address of the UDP server to ping. If this value is null, it is ignored
* along with udpPingReceiverPort, udpPingPayload, and pingPeriod.
* @param udpPingReceiverPort Port of the UDP server to ping.
* @param udpPingPayload Ping payload.
* @param pingPeriod How often should the udp ping be performed.
*
* @return Returns {@link ConnectionParameter} with type {@link ConnectionType#TYPE_UDP}.
*/
public static ConnectionParameter newUdpConnection(int udpPort, @Nullable String udpPingReceiverIp, int udpPingReceiverPort,
byte[] udpPingPayload, long pingPeriod) {
Bundle paramsBundle = new Bundle();
paramsBundle.putInt(ConnectionType.EXTRA_UDP_SERVER_PORT, udpPort);

if (!TextUtils.isEmpty(udpPingReceiverIp)) {
paramsBundle.putString(ConnectionType.EXTRA_UDP_PING_RECEIVER_IP, udpPingReceiverIp);
paramsBundle.putInt(ConnectionType.EXTRA_UDP_PING_RECEIVER_PORT, udpPingReceiverPort);
paramsBundle.putByteArray(ConnectionType.EXTRA_UDP_PING_PAYLOAD, udpPingPayload);
paramsBundle.putLong(ConnectionType.EXTRA_UDP_PING_PERIOD, pingPeriod);
}

return new ConnectionParameter(ConnectionType.TYPE_UDP, paramsBundle);
}

/**
*
* @param tcpServerIp TCP server IP address.
*
* @return Returns {@link ConnectionParameter} with type {@link ConnectionType#TYPE_TCP}, using
* {@link ConnectionType#DEFAULT_TCP_SERVER_PORT}.
*/
public static ConnectionParameter newTcpConnection(String tcpServerIp) {
return newTcpConnection(tcpServerIp, ConnectionType.DEFAULT_TCP_SERVER_PORT);
}

/**
*
* @param tcpServerIp TCP server IP address.
* @param tcpServerPort TCP server port.
*
* @return Returns {@link ConnectionParameter} with type {@link ConnectionType#TYPE_TCP}.
*/
public static ConnectionParameter newTcpConnection(String tcpServerIp, int tcpServerPort) {
Bundle paramsBundle = new Bundle(2);
paramsBundle.putString(ConnectionType.EXTRA_TCP_SERVER_IP, tcpServerIp);
paramsBundle.putInt(ConnectionType.EXTRA_TCP_SERVER_PORT, tcpServerPort);

return new ConnectionParameter(ConnectionType.TYPE_TCP, paramsBundle);
}

/**
*
* @param bluetoothAddress Bluetooth address.
*
* @return Returns {@link ConnectionParameter} with type {@link ConnectionType#TYPE_BLUETOOTH}.
*/
public static ConnectionParameter newBluetoothConnection(String bluetoothAddress) {
Bundle paramsBundle = new Bundle(1);
paramsBundle.putString(ConnectionType.EXTRA_BLUETOOTH_ADDRESS, bluetoothAddress);

return new ConnectionParameter(ConnectionType.TYPE_BLUETOOTH, paramsBundle);
}

/**
*
* @param ssid Wifi SSID of the solo vehicle link. This will remove a leading and/or trailing quotation.
* @param password Password to access the solo wifi network. This value can be null as long as the wifi
* configuration has been set up and stored in the mobile device's system.
*
* @return Returns {@link ConnectionParameter} with type {@link ConnectionType#TYPE_SOLO}.
*/
public static ConnectionParameter newSoloConnection(String ssid, @Nullable String password) {
String ssidWithoutQuotes = ssid.replaceAll("^\"|\"$", "");

Bundle paramsBundle = new Bundle(2);
paramsBundle.putString(ConnectionType.EXTRA_SOLO_LINK_ID, ssidWithoutQuotes);
paramsBundle.putString(ConnectionType.EXTRA_SOLO_LINK_PASSWORD, password);

return new ConnectionParameter(ConnectionType.TYPE_SOLO, paramsBundle);
}

/**
* @deprecated Use one of specified static methods
*/
//TODO: make this private version 3.0
public ConnectionParameter(int connectionType, Bundle paramsBundle){
this.connectionType = connectionType;
this.paramsBundle = paramsBundle;
Expand Down Expand Up @@ -111,8 +255,8 @@ public int hashCode(){
@Override
public String toString() {
String toString = "ConnectionParameter{" +
"connectionType=" + connectionType +
", paramsBundle=[";
"connectionType=" + connectionType +
", paramsBundle=[";

if (paramsBundle != null && !paramsBundle.isEmpty()) {
boolean isFirst = true;
Expand Down Expand Up @@ -157,4 +301,4 @@ public ConnectionParameter[] newArray(int size) {
return new ConnectionParameter[size];
}
};
}
}
52 changes: 34 additions & 18 deletions ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError;
import com.o3dr.services.android.lib.drone.connection.ConnectionParameter;
import com.o3dr.services.android.lib.drone.connection.ConnectionResult;
import com.o3dr.services.android.lib.gcs.link.LinkConnectionStatus;
import com.o3dr.services.android.lib.drone.mission.Mission;
import com.o3dr.services.android.lib.drone.mission.action.MissionActions;
import com.o3dr.services.android.lib.drone.mission.item.MissionItem;
Expand All @@ -32,6 +31,7 @@
import com.o3dr.services.android.lib.drone.property.Parameter;
import com.o3dr.services.android.lib.drone.property.State;
import com.o3dr.services.android.lib.gcs.event.GCSEvent;
import com.o3dr.services.android.lib.gcs.link.LinkConnectionStatus;
import com.o3dr.services.android.lib.gcs.link.LinkEvent;
import com.o3dr.services.android.lib.gcs.link.LinkEventExtra;
import com.o3dr.services.android.lib.mavlink.MavlinkMessageWrapper;
Expand Down Expand Up @@ -189,8 +189,8 @@ private ConnectionParameter checkConnectionParameter(ConnectionParameter connPar
throw new ConnectionException("Invalid connection parameters");
}

if (SoloConnection.isSoloConnection(context, connParams)) {
ConnectionParameter update = SoloConnection.getSoloConnectionParameterIfPossible(context);
if (SoloConnection.isUdpSoloConnection(context, connParams)) {
ConnectionParameter update = SoloConnection.getSoloConnectionParameterFromUdp(context);
if (update != null) {
return update;
}
Expand All @@ -200,8 +200,19 @@ private ConnectionParameter checkConnectionParameter(ConnectionParameter connPar

public void connect(ConnectionParameter connParams) {
try {
this.connectionParams = checkConnectionParameter(connParams);
this.droneMgr = service.connectDroneManager(this.connectionParams, ownerId, this);
connParams = checkConnectionParameter(connParams);
if (!connParams.equals(this.connectionParams)) {
if (this.droneMgr != null) {
LinkConnectionStatus connectionStatus = LinkConnectionStatus
.newFailedConnectionStatus(LinkConnectionStatus.ADDRESS_IN_USE,
"Connection already started with different connection parameters");
onConnectionStatus(connectionStatus);
return;
}

this.connectionParams = connParams;
this.droneMgr = service.connectDroneManager(this.connectionParams, ownerId, this);
}
} catch (ConnectionException e) {
LinkConnectionStatus connectionStatus = LinkConnectionStatus
.newFailedConnectionStatus(LinkConnectionStatus.INVALID_CREDENTIALS, e.getMessage());
Expand All @@ -212,6 +223,7 @@ public void connect(ConnectionParameter connParams) {

public void disconnect() {
service.disconnectDroneManager(this.droneMgr, clientInfo);
this.connectionParams = null;
this.droneMgr = null;

}
Expand Down Expand Up @@ -660,21 +672,25 @@ public void onEndReceivingParameters() {
}

public void onConnectionStatus(LinkConnectionStatus connectionStatus) {
if (connectionStatus != null) {
switch (connectionStatus.getStatusCode()) {
case LinkConnectionStatus.FAILED:
checkForSelfRelease();

//This is to ensure backwards compatibility
// TODO: remove this in version 3.0
notifyConnectionFailed(connectionStatus);
break;
}
switch (connectionStatus.getStatusCode()) {
case LinkConnectionStatus.FAILED:
disconnect();
checkForSelfRelease();

Bundle extras = new Bundle();
extras.putParcelable(LinkEventExtra.EXTRA_CONNECTION_STATUS, connectionStatus);
notifyAttributeUpdate(LinkEvent.LINK_STATE_UPDATED, extras);
//This is to ensure backwards compatibility
// TODO: remove this in version 3.0
notifyConnectionFailed(connectionStatus);
break;
case LinkConnectionStatus.DISCONNECTED:
disconnect();
checkForSelfRelease();
break;
}

Bundle extras = new Bundle();
extras.putParcelable(LinkEventExtra.EXTRA_CONNECTION_STATUS, connectionStatus);
notifyAttributeUpdate(LinkEvent.LINK_STATE_UPDATED, extras);

}

private void notifyConnectionFailed(LinkConnectionStatus connectionStatus) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -118,15 +118,22 @@ public void onWifiConnecting() {
}

@Override
public void onWifiDisconnected() {
onConnectionStatus(new LinkConnectionStatus(LinkConnectionStatus.DISCONNECTED, null));
public void onWifiDisconnected(String prevSsid) {
if (prevSsid.equalsIgnoreCase(soloLinkId)) {
onConnectionStatus(new LinkConnectionStatus(LinkConnectionStatus.DISCONNECTED, null));
}
}

@Override
public void onWifiScanResultsAvailable(List<ScanResult> results) {
checkScanResults(results);
}

@Override
public void onWifiConnectionFailed(LinkConnectionStatus connectionStatus) {
onConnectionStatus(connectionStatus);
}

private void checkScanResults(List<ScanResult> results) {
if (!isConnecting())
return;
Expand All @@ -146,8 +153,9 @@ private void checkScanResults(List<ScanResult> results) {
try {
int connectionResult = wifiHandler.connectToWifi(targetResult, soloLinkPassword);
if (connectionResult != 0) {
@LinkConnectionStatus.FailureCode int failureCode = connectionResult;
LinkConnectionStatus connectionStatus = LinkConnectionStatus
.newFailedConnectionStatus(connectionResult, "Unable to connect to the target wifi " + soloLinkId);
.newFailedConnectionStatus(failureCode, "Unable to connect to the target wifi " + soloLinkId);
onConnectionStatus(connectionStatus);
}
} catch (IllegalArgumentException e) {
Expand All @@ -165,15 +173,12 @@ private boolean isConnecting() {
return getConnectionStatus() == MAVLINK_CONNECTING;
}

public static boolean isSoloConnection(Context context, ConnectionParameter connParam){
public static boolean isUdpSoloConnection(Context context, ConnectionParameter connParam){
if(connParam == null)
return false;

final int connectionType = connParam.getConnectionType();
switch(connectionType){
case ConnectionType.TYPE_SOLO:
return true;

case ConnectionType.TYPE_UDP:
Bundle paramsBundle = connParam.getParamsBundle();
if(paramsBundle == null)
Expand All @@ -188,15 +193,13 @@ public static boolean isSoloConnection(Context context, ConnectionParameter conn
}
}

public static ConnectionParameter getSoloConnectionParameterIfPossible(Context context){
public static ConnectionParameter getSoloConnectionParameterFromUdp(Context context){
if(context == null)
return null;

final String wifiSsid = WifiConnectionHandler.getCurrentWifiLink((WifiManager) context.getSystemService(Context.WIFI_SERVICE));
if(WifiConnectionHandler.isSoloWifi(wifiSsid)){
Bundle paramsBundle = new Bundle();
paramsBundle.putString(ConnectionType.EXTRA_SOLO_LINK_ID, wifiSsid);
return new ConnectionParameter(ConnectionType.TYPE_SOLO, paramsBundle);
return ConnectionParameter.newSoloConnection(wifiSsid, null);
}

return null;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,8 @@ public void onReceivePacket(final MAVLinkPacket packet) {

@Override
public void onConnectionStatus(final LinkConnectionStatus connectionStatus) {
listener.onConnectionStatus(connectionStatus);

switch (connectionStatus.getStatusCode()) {
case LinkConnectionStatus.DISCONNECTED:
closeConnection();
Expand All @@ -74,8 +76,6 @@ public void onConnectionStatus(final LinkConnectionStatus connectionStatus) {
}
break;
}

listener.onConnectionStatus(connectionStatus);
}
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ public void disconnect(DroneApi.ClientInfo clientInfo) {
}

protected void doDisconnect(String appId, DroneApi listener) {
if (listener != null) {
if (isConnected() && listener != null) {
listener.onDroneEvent(DroneInterfaces.DroneEventsType.DISCONNECTED, drone);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -184,8 +184,9 @@ protected void doDisconnect(String appId, DroneApi listener) {

if (listener != null) {
mavClient.removeLoggingFile(appId);

listener.onDroneEvent(DroneInterfaces.DroneEventsType.DISCONNECTED, drone);
if (isConnected()) {
listener.onDroneEvent(DroneInterfaces.DroneEventsType.DISCONNECTED, drone);
}
}

if (mavClient.isConnected() && connectedApps.isEmpty()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,10 @@ public static boolean isOnSololinkNetwork(Context context) {
return true;

final String connectedSSID = getCurrentWifiLink(context);
return connectedSSID != null && connectedSSID.startsWith(SoloComp.SOLO_LINK_WIFI_PREFIX);
return isSoloNetwork(connectedSSID);
}

public static boolean isSoloNetwork(String ssid) {
return ssid != null && ssid.startsWith(SoloComp.SOLO_LINK_WIFI_PREFIX);
}
}
Loading

0 comments on commit 9e75fff

Please sign in to comment.