android mavlink连接

android mavlink连接

  • dronekit-android 中 mavlink连接
    • 1. 总体框架图
    • 2. USB连接详细
      • 构造方法需要传入波特率
      • 连接分两种USB设备 (FTDI 和 CDCC)
      • 连接一:UsbFTDIConnection,利用 FT_Device 对象读写
      • 连接二:UsbCDCConnection,利用 UsbSerialDriver 对象读写
    • 3. TCP 连接
      • 构造方法需要传入 tcpServerIp 和 tcpServerPort
      • 连接的具体实现类 TcpConnection,利用 Socket 对象读写
    • 4. UDP 连接
      • 构造方法需要传入 udpServerPort
      • 连接的具体实现类 UdpConnection,利用 DatagramSocket 对象读写
    • 5. 蓝牙(Bluetooth)连接
      • 构造方法传入蓝牙地址(bluetoothAddress)
      • 连接主要创建BluetoothSocket,利用 BluetoothSocket 对象读写
    • 6. SoloConnection
      • 构造方法需要传入 soloLinkId 和 password
      • 根据 soloLinkId 和 password 先连接Wifi
      • wifi连接成功后建立UDP的 DatagramSocket 连接

dronekit-android 中 mavlink连接

dronekit-android github源码链接

1. 总体框架图

MavLinkConnection
AndroidMavLinkConnection
UsbConnection
AndroidIpConnection
BluetoothConnection
SoloConnection
UsbFTDIConnection
UsbCDCConnection
AndroidTcpConnection
AndroidUdpConnection

2. USB连接详细

构造方法需要传入波特率

public UsbConnection(Context parentContext, int baudRate) {
    super(parentContext);
    mBaudRate = baudRate;
}

连接分两种USB设备 (FTDI 和 CDCC)

判断是否是 FTDI 设备的方法

private static boolean isFTDIdevice(Context context) {
    UsbManager manager = (UsbManager) context.getSystemService(Context.USB_SERVICE);
    final HashMap<String, UsbDevice> deviceList = manager.getDeviceList();
    if (deviceList == null || deviceList.isEmpty()) {
        return false;
    }

    for (Entry<String, UsbDevice> device : deviceList.entrySet()) {
        if (device.getValue().getVendorId() == FTDI_DEVICE_VENDOR_ID) {
            return true;
        }
    }
    return false;
}

连接一:UsbFTDIConnection,利用 FT_Device 对象读写

有一个关键的jar包 d2xx.jar

protected void openUsbConnection(Bundle extras) throws IOException {
    D2xxManager ftD2xx = null;
	try {
		ftD2xx = D2xxManager.getInstance(mContext);
	} catch (D2xxManager.D2xxException ex) {
		mLogger.logErr(TAG, ex);
	}

	if (ftD2xx == null) {
		throw new IOException("Unable to retrieve D2xxManager instance.");
	}

	int DevCount = ftD2xx.createDeviceInfoList(mContext);
	Log.d(TAG, "Found " + DevCount + " ftdi devices.");
	if (DevCount < 1) {
		throw new IOException("No Devices found");
	}

    FT_Device ftDev = null;
	try {
		// FIXME: The NPE is coming from the library. Investigate if it's
		// possible to fix there.
		ftDev = ftD2xx.openByIndex(mContext, 0);
	} catch (NullPointerException e) {
		Log.e(TAG, e.getMessage(), e);
	} finally {
		if (ftDev == null) {
			throw new IOException("No Devices found");
		}
	}

	Log.d(TAG, "Opening using Baud rate " + mBaudRate);
	ftDev.setBitMode((byte) 0, D2xxManager.FT_BITMODE_RESET);
	ftDev.setBaudRate(mBaudRate);
	ftDev.setDataCharacteristics(D2xxManager.FT_DATA_BITS_8, D2xxManager.FT_STOP_BITS_1,
				D2xxManager.FT_PARITY_NONE);
	ftDev.setFlowControl(D2xxManager.FT_FLOW_NONE, (byte) 0x00, (byte) 0x00);
	ftDev.setLatencyTimer(LATENCY_TIMER);
	ftDev.purge((byte) (D2xxManager.FT_PURGE_TX | D2xxManager.FT_PURGE_RX));

	if (!ftDev.isOpen()) {
		throw new IOException("Unable to open usb device connection.");
	} else {
		Log.d(TAG, "COM open");
	}

    ftDevRef.set(ftDev);

    onUsbConnectionOpened(extras);
}

连接二:UsbCDCConnection,利用 UsbSerialDriver 对象读写

private void openUsbDevice(UsbDevice device, Bundle extras) throws IOException {
    // Get UsbManager from Android.
    UsbManager manager = (UsbManager) mContext.getSystemService(Context.USB_SERVICE);

    // Find the first available driver.
    final UsbSerialDriver serialDriver = UsbSerialProber.openUsbDevice(manager, device);

    if (serialDriver == null) {
        Log.d(TAG, "No Devices found");
        throw new IOException("No Devices found");
    } else {
        Log.d(TAG, "Opening using Baud rate " + mBaudRate);
        try {
            serialDriver.open();
            serialDriver.setParameters(mBaudRate, 8, UsbSerialDriver.STOPBITS_1, UsbSerialDriver.PARITY_NONE);

            serialDriverRef.set(serialDriver);

            onUsbConnectionOpened(extras);
        } catch (IOException e) {
            Log.e(TAG, "Error setting up device: " + e.getMessage(), e);
            try {
                serialDriver.close();
            } catch (IOException e2) {
                // Ignore.
            }
        }
    }
}

3. TCP 连接

构造方法需要传入 tcpServerIp 和 tcpServerPort

public AndroidTcpConnection(Context context, String tcpServerIp, int tcpServerPort, WifiConnectionHandler wifiHandler){
    super(context, wifiHandler);

    this.serverIp = tcpServerIp;
    this.serverPort = tcpServerPort;

    mConnectionImpl = new TcpConnection(context) {
        @Override
        protected int loadServerPort() {
            return serverPort;
        }

        @Override
        protected String loadServerIP() {
            return serverIp;
        }

            @Override
        protected Logger initLogger() {
            return AndroidTcpConnection.this.initLogger();
        }

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

            @Override
        protected void onConnectionStatus(LinkConnectionStatus connectionStatus) {
            AndroidTcpConnection.this.onConnectionStatus(connectionStatus);
        }
    };
}

连接的具体实现类 TcpConnection,利用 Socket 对象读写

private void getTCPStream(Bundle extras) throws IOException {
    InetAddress serverAddr = InetAddress.getByName(serverIP);
    socket = new Socket();
    NetworkUtils.bindSocketToNetwork(extras, socket);
    socket.connect(new InetSocketAddress(serverAddr, serverPort), CONNECTION_TIMEOUT);
    mavOut = new BufferedOutputStream((socket.getOutputStream()));
    mavIn = new BufferedInputStream(socket.getInputStream());
}

4. UDP 连接

构造方法需要传入 udpServerPort

public AndroidUdpConnection(Context context, int udpServerPort, WifiConnectionHandler wifiHandler) {
    super(context, wifiHandler);
    this.serverPort = udpServerPort;

    mConnectionImpl = new UdpConnection(context) {
        @Override
        protected int loadServerPort() {
            return serverPort;
        }

        @Override
        protected Logger initLogger() {
            return AndroidUdpConnection.this.initLogger();
        }

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

        @Override
        protected void onConnectionStatus(LinkConnectionStatus connectionStatus) {
            AndroidUdpConnection.this.onConnectionStatus(connectionStatus);
        }
    };
}

连接的具体实现类 UdpConnection,利用 DatagramSocket 对象读写

private void getUdpStream(Bundle extras) throws IOException {
    final DatagramSocket socket = new DatagramSocket(serverPort);
    socket.setBroadcast(true);
    socket.setReuseAddress(true);
    NetworkUtils.bindSocketToNetwork(extras, socket);
    socketRef.set(socket);
}

5. 蓝牙(Bluetooth)连接

构造方法传入蓝牙地址(bluetoothAddress)

public BluetoothConnection(Context parentContext, String btAddress) {
    super(parentContext);
    this.bluetoothAddress = btAddress;

    mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter();
    if (mBluetoothAdapter == null) {
        Log.d(BLUE, "Null adapters");
    }
}

连接主要创建BluetoothSocket,利用 BluetoothSocket 对象读写

protected void openConnection(Bundle connectionExtras) throws IOException {
    Log.d(BLUE, "Connect");

    // Reset the bluetooth connection
    resetConnection();

    // Retrieve the stored device
    BluetoothDevice device = null;
    try {
        device = mBluetoothAdapter.getRemoteDevice(bluetoothAddress);
    } catch (IllegalArgumentException ex) {
        // invalid configuration (device may have been removed)
        // NOP fall through to 'no device'
    }

    // no device
    if (device == null) {
        device = findSerialBluetoothBoard();
    }

    Log.d(BLUE, "Trying to connect to device with address " + device.getAddress());
    Log.d(BLUE, "BT Create Socket Call...");
    bluetoothSocket = device.createInsecureRfcommSocketToServiceRecord(UUID
            .fromString(UUID_SPP_DEVICE));

    Log.d(BLUE, "BT Cancel Discovery Call...");
    mBluetoothAdapter.cancelDiscovery();

    Log.d(BLUE, "BT Connect Call...");
    bluetoothSocket.connect(); // Here the IOException will rise on BT
    // protocol/handshake error.

    Log.d(BLUE, "## BT Connected ##");
    out = bluetoothSocket.getOutputStream();
    in = bluetoothSocket.getInputStream();

    onConnectionOpened(connectionExtras);
}

6. SoloConnection

Solo 是 3dr 公司的飞行器,针对飞行器单独写了 MavLink 连接,采用的是 Wifi 和 UDP 结合的方式建立连接。

构造方法需要传入 soloLinkId 和 password

public SoloConnection(Context applicationContext, String soloLinkId, String password) {
    super(applicationContext);
    this.wifiHandler = new WifiConnectionHandler(applicationContext);
    wifiHandler.setListener(this);

    this.soloLinkId = soloLinkId;
    this.soloLinkPassword = password;
    this.dataLink = new AndroidUdpConnection(applicationContext, SOLO_UDP_PORT) {
        @Override
        protected void onConnectionOpened(Bundle extras) {
            SoloConnection.this.onConnectionOpened(extras);
        }

        @Override
        protected void onConnectionStatus(LinkConnectionStatus connectionStatus) {
            SoloConnection.this.onConnectionStatus(connectionStatus);
        }
    };
}

根据 soloLinkId 和 password 先连接Wifi

// 先注册广播,再检测扫描结果
this.context.registerReceiver(broadcastReceiver, intentFilter);
checkScanResults(wifiHandler.getScanResults());

private void checkScanResults(List<ScanResult> results) {
    if (!isConnecting())
        return;

    //We're in the connection process, let's see if the wifi we want is available
    ScanResult targetResult = null;
    for (ScanResult result : results) {
        if (result.SSID.equalsIgnoreCase(this.soloLinkId)) {
            //bingo
            targetResult = result;
            break;
        }
    }

    if (targetResult != null) {
        //We're good to go
        try {
            Bundle connectInfo = new Bundle();
            Bundle extras = getConnectionExtras();
            if (extras != null && !extras.isEmpty()) {
                connectInfo.putAll(extras);
            }
            connectInfo.putParcelable(WifiConnectionHandler.EXTRA_SCAN_RESULT, targetResult);
            connectInfo.putString(WifiConnectionHandler.EXTRA_SSID_PASSWORD, soloLinkPassword);
            int connectionResult = wifiHandler.connectToWifi(connectInfo);
            if (connectionResult != 0) {
                @LinkConnectionStatus.FailureCode int failureCode = connectionResult;
                LinkConnectionStatus connectionStatus = LinkConnectionStatus
                    .newFailedConnectionStatus(failureCode, "Unable to connect to the target wifi " + soloLinkId);
                onConnectionStatus(connectionStatus);
            }
        } catch (IllegalArgumentException e) {
            Timber.e(e, e.getMessage());
            LinkConnectionStatus connectionStatus = LinkConnectionStatus.newFailedConnectionStatus(LinkConnectionStatus.UNKNOWN, e.getMessage());
            onConnectionStatus(connectionStatus);
        }
    } else {
        //Let's try again
        refreshWifiAps();
    }
}

wifi连接成功后建立UDP的 DatagramSocket 连接

dataLink 对象的实例化在构造方法中,SOLO_UDP_PORT 端口是 14550 。

private static final int SOLO_UDP_PORT = 14550;

public void onWifiConnected(String wifiSsid, Bundle extras) {
    if (isConnecting()) {
        //Let's see if we're connected to our target wifi
        if (wifiSsid.equalsIgnoreCase(soloLinkId)) {
            //We're good to go
            try {
                // dataLink 对象的实例化在构造方法中
                dataLink.openConnection(extras);
            } catch (IOException e) {
                reportIOException(e);
                Timber.e(e, e.getMessage());
            }
        }
    }
}

你可能感兴趣的:(dronekit,android)