Skip to content

Commit

Permalink
Added logic to request usb permission if it's not already available t…
Browse files Browse the repository at this point in the history
…o 3DR Services.

Added notification to notify the user of the ongoing connection.
  • Loading branch information
m4gr3d committed Feb 9, 2015
1 parent 51430d9 commit edae505
Show file tree
Hide file tree
Showing 18 changed files with 268 additions and 117 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
import com.o3dr.services.android.lib.drone.mission.MissionItemType;

/**
* Created by fhuya on 11/6/14.
* Mission command used to move a servo to a particular pwm value.
*/
public class SetServo extends MissionItem implements MissionItem.Command, android.os.Parcelable {

Expand All @@ -23,18 +23,31 @@ public SetServo(SetServo copy){
channel = copy.channel;
}

/**
* @return PWM value to output to the servo
*/
public int getPwm() {
return pwm;
}

/**
* Set PWM value to output to the servo
* @param pwm value to output to the servo
*/
public void setPwm(int pwm) {
this.pwm = pwm;
}

/**
* @return the output channel the servo is attached to
*/
public int getChannel() {
return channel;
}

/**
* @param channel the output channel the servo is attached to
*/
public void setChannel(int channel) {
this.channel = channel;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@ void connectMAVConnection(ConnectionParameter connParams, String listenerTag,
mavConnections.put(connParams, conn);
}

conn.addMavLinkConnectionListener(listenerTag, listener);
if (conn.getConnectionStatus() == MavLinkConnection.MAVLINK_DISCONNECTED) {
conn.connect();

Expand All @@ -137,8 +138,6 @@ void connectMAVConnection(ConnectionParameter connParams, String listenerTag,
.setAction("MavLink connect")
.setLabel(connParams.toString()));
}

conn.addMavLinkConnectionListener(listenerTag, listener);
}

void disconnectMAVConnection(ConnectionParameter connParams, String listenerTag) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1329,7 +1329,16 @@ public void onDroneEvent(DroneInterfaces.DroneEventsType event, Drone drone) {
case CONNECTING:
extrasBundle = new Bundle(2);
extrasBundle.putInt(AttributeEventExtra.EXTRA_AUTOPILOT_FAILSAFE_MESSAGE_LEVEL, Log.INFO);
extrasBundle.putString(AttributeEventExtra.EXTRA_AUTOPILOT_FAILSAFE_MESSAGE, "Connecting...");
extrasBundle.putString(AttributeEventExtra.EXTRA_AUTOPILOT_FAILSAFE_MESSAGE,
"Connecting...");
droneEvent = AttributeEvent.AUTOPILOT_FAILSAFE;
break;

case CHECKING_VEHICLE_LINK:
extrasBundle = new Bundle(2);
extrasBundle.putInt(AttributeEventExtra.EXTRA_AUTOPILOT_FAILSAFE_MESSAGE_LEVEL, Log.INFO);
extrasBundle.putString(AttributeEventExtra.EXTRA_AUTOPILOT_FAILSAFE_MESSAGE,
"Checking vehicle link...");
droneEvent = AttributeEvent.AUTOPILOT_FAILSAFE;
break;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,16 @@ protected String loadServerIP() {
protected Logger initLogger() {
return AndroidTcpConnection.this.initLogger();
}

@Override
protected void onConnectionOpened(){
AndroidTcpConnection.this.onConnectionOpened();
}

@Override
protected void onConnectionFailed(String errMsg){
AndroidTcpConnection.this.onConnectionFailed(errMsg);
}
};
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,16 @@ protected Logger initLogger() {
return AndroidUdpConnection.this.initLogger();
}

@Override
protected void onConnectionOpened(){
AndroidUdpConnection.this.onConnectionOpened();
}

@Override
protected void onConnectionFailed(String errMsg){
AndroidUdpConnection.this.onConnectionFailed(errMsg);
}

};
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,8 @@ protected void openConnection() throws IOException {
Log.d(BLUE, "## BT Connected ##");
out = bluetoothSocket.getOutputStream();
in = bluetoothSocket.getInputStream();

onConnectionOpened();
}

@SuppressLint("NewApi")
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
package org.droidplanner.services.android.communication.connection.usb;

import java.io.IOException;
import java.util.List;

import android.app.PendingIntent;
import android.content.BroadcastReceiver;
import android.content.Context;
Expand All @@ -15,81 +12,108 @@
import com.hoho.android.usbserial.driver.UsbSerialDriver;
import com.hoho.android.usbserial.driver.UsbSerialProber;

import java.io.IOException;
import java.util.List;
import java.util.concurrent.Executors;
import java.util.concurrent.ScheduledExecutorService;
import java.util.concurrent.TimeUnit;

class UsbCDCConnection extends UsbConnection.UsbConnectionImpl {
private static final String TAG = UsbCDCConnection.class.getSimpleName();
private static final String TAG = UsbCDCConnection.class.getSimpleName();
private static final String ACTION_USB_PERMISSION = "com.android.example.USB_PERMISSION";

private static final IntentFilter intentFilter = new IntentFilter(ACTION_USB_PERMISSION);

private static UsbSerialDriver sDriver = null;
private static UsbSerialDriver sDriver = null;

private final PendingIntent usbPermissionIntent;

private final BroadcastReceiver broadcastReceiver = new BroadcastReceiver() {
@Override
public void onReceive(Context context, Intent intent) {
final String action = intent.getAction();
if(ACTION_USB_PERMISSION.equals(action)){
synchronized(this){
UsbDevice device = intent.getParcelableExtra(UsbManager.EXTRA_DEVICE);

if (intent.getBooleanExtra(UsbManager.EXTRA_PERMISSION_GRANTED, false)) {
if(device != null){
//call method to set up device communication
try {
openUsbDevice(device);
} catch (IOException e) {
Log.e(TAG, e.getMessage(), e);
}
if (ACTION_USB_PERMISSION.equals(action)) {
removeWatchdog();
UsbDevice device = intent.getParcelableExtra(UsbManager.EXTRA_DEVICE);

if (intent.getBooleanExtra(UsbManager.EXTRA_PERMISSION_GRANTED, false)) {
if (device != null) {
//call method to set up device communication
try {
openUsbDevice(device);
} catch (IOException e) {
Log.e(TAG, e.getMessage(), e);
}
} else {
onUsbConnectionFailed("Unable to access usb device.");
}
else {
Log.d(TAG, "permission denied for device " + device);
}
} else {
Log.d(TAG, "permission denied for device " + device);
onUsbConnectionFailed("USB Permission denied.");
}
}
}
};

protected UsbCDCConnection(Context context, int baudRate) {
super(context, baudRate);
this.usbPermissionIntent = PendingIntent.getBroadcast(context, 0,
new Intent(ACTION_USB_PERMISSION), 0);
}
private final Runnable permissionWatchdog = new Runnable() {
@Override
public void run() {
Log.d(TAG, "Permission request timeout.");
onUsbConnectionFailed("Unable to get usb access.");

removeWatchdog();
}
};

private void registerUsbPermissionBroadcastReceiver(){
// mContext.registerReceiver(broadcastReceiver, intentFilter);
private ScheduledExecutorService scheduler;

protected UsbCDCConnection(Context context, UsbConnection parentConn, int baudRate) {
super(context, parentConn, baudRate);
this.usbPermissionIntent = PendingIntent.getBroadcast(context, 0, new Intent(ACTION_USB_PERMISSION), 0);
}

private void registerUsbPermissionBroadcastReceiver() {
mContext.registerReceiver(broadcastReceiver, intentFilter);
}

private void unregisterUsbPermissionBroadcastReceiver() {
mContext.unregisterReceiver(broadcastReceiver);
}

private void unregisterUsbPermissionBroadcastReceiver(){
// mContext.unregisterReceiver(broadcastReceiver);
private void removeWatchdog() {
if (scheduler != null) {
scheduler.shutdown();
scheduler = null;
}
}

@Override
protected void openUsbConnection() throws IOException {
@Override
protected void openUsbConnection() throws IOException {
registerUsbPermissionBroadcastReceiver();

// Get UsbManager from Android.
UsbManager manager = (UsbManager) mContext.getSystemService(Context.USB_SERVICE);
// Get UsbManager from Android.
UsbManager manager = (UsbManager) mContext.getSystemService(Context.USB_SERVICE);

//Get the list of available devices
List<UsbDevice> availableDevices = UsbSerialProber.getAvailableSupportedDevices(manager);
if(availableDevices.isEmpty()){
if (availableDevices.isEmpty()) {
Log.d("USB", "No Devices found");
throw new IOException("No Devices found");
}

//Pick the first device
UsbDevice device = availableDevices.get(0);
if(manager.hasPermission(device)){
if (manager.hasPermission(device)) {
openUsbDevice(device);
} else {
removeWatchdog();

scheduler = Executors.newSingleThreadScheduledExecutor();
scheduler.schedule(permissionWatchdog, 15, TimeUnit.SECONDS);
Log.d(TAG, "Requesting permission to access usb device " + device.getDeviceName());
manager.requestPermission(device, usbPermissionIntent);
}
else{
//TODO: complete implementation
// manager.requestPermission(device, usbPermissionIntent);
throw new IOException("No permission to access usb device " + device.getDeviceName());
}
}
}

private void openUsbDevice(UsbDevice device) throws IOException {
// Get UsbManager from Android.
Expand All @@ -105,8 +129,9 @@ private void openUsbDevice(UsbDevice device) throws IOException {
Log.d("USB", "Opening using Baud rate " + mBaudRate);
try {
sDriver.open();
sDriver.setParameters(mBaudRate, 8, UsbSerialDriver.STOPBITS_1,
UsbSerialDriver.PARITY_NONE);
sDriver.setParameters(mBaudRate, 8, UsbSerialDriver.STOPBITS_1, UsbSerialDriver.PARITY_NONE);

onUsbConnectionOpened();
} catch (IOException e) {
Log.e("USB", "Error setting up device: " + e.getMessage(), e);
try {
Expand All @@ -119,57 +144,57 @@ private void openUsbDevice(UsbDevice device) throws IOException {
}
}

@Override
protected int readDataBlock(byte[] readData) throws IOException {
// Read data from driver. This call will return upto readData.length
// bytes.
// If no data is received it will timeout after 200ms (as set by
// parameter 2)
int iavailable = 0;
try {
iavailable = sDriver.read(readData, 200);
} catch (NullPointerException e) {
final String errorMsg = "Error Reading: " + e.getMessage()
+ "\nAssuming inaccessible USB device. Closing connection.";
Log.e(TAG, errorMsg, e);
throw new IOException(errorMsg, e);
}

if (iavailable == 0)
iavailable = -1;
return iavailable;
}

@Override
protected void sendBuffer(byte[] buffer) {
// Write data to driver. This call should write buffer.length bytes
// if data cant be sent , then it will timeout in 500ms (as set by
// parameter 2)
if (sDriver != null) {
try {
sDriver.write(buffer, 500);
} catch (IOException e) {
Log.e("USB", "Error Sending: " + e.getMessage(), e);
}
}
}

@Override
protected void closeUsbConnection() throws IOException {
@Override
protected int readDataBlock(byte[] readData) throws IOException {
// Read data from driver. This call will return upto readData.length
// bytes.
// If no data is received it will timeout after 200ms (as set by
// parameter 2)
int iavailable = 0;
try {
iavailable = sDriver.read(readData, 200);
} catch (NullPointerException e) {
final String errorMsg = "Error Reading: " + e.getMessage()
+ "\nAssuming inaccessible USB device. Closing connection.";
Log.e(TAG, errorMsg, e);
throw new IOException(errorMsg, e);
}

if (iavailable == 0)
iavailable = -1;
return iavailable;
}

@Override
protected void sendBuffer(byte[] buffer) {
// Write data to driver. This call should write buffer.length bytes
// if data cant be sent , then it will timeout in 500ms (as set by
// parameter 2)
if (sDriver != null) {
try {
sDriver.write(buffer, 500);
} catch (IOException e) {
Log.e("USB", "Error Sending: " + e.getMessage(), e);
}
}
}

@Override
protected void closeUsbConnection() throws IOException {
unregisterUsbPermissionBroadcastReceiver();

if (sDriver != null) {
try {
sDriver.close();
} catch (IOException e) {
// Ignore.
}
sDriver = null;
}
}

@Override
public String toString() {
return TAG;
}
if (sDriver != null) {
try {
sDriver.close();
} catch (IOException e) {
// Ignore.
}
sDriver = null;
}
}

@Override
public String toString() {
return TAG;
}
}
Loading

0 comments on commit edae505

Please sign in to comment.