diff --git a/QGCApplication.pro b/QGCApplication.pro
new file mode 100644
index 0000000000000000000000000000000000000000..f32186ca295398c22ae02db366304c2c95c6f3f1
--- /dev/null
+++ b/QGCApplication.pro
@@ -0,0 +1,661 @@
+# -------------------------------------------------
+# QGroundControl - Micro Air Vehicle Groundstation
+# Please see our website at
+# Maintainer:
+# Lorenz Meier
+# (c) 2009-2014 QGroundControl Developers
+# This file is part of the open groundstation project
+# QGroundControl is free software: you can redistribute it and/or modify
+# it under the terms of the GNU General Public License as published by
+# the Free Software Foundation, either version 3 of the License, or
+# (at your option) any later version.
+# QGroundControl is distributed in the hope that it will be useful,
+# but WITHOUT ANY WARRANTY; without even the implied warranty of
+# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+# GNU General Public License for more details.
+# You should have received a copy of the GNU General Public License
+# along with QGroundControl. If not, see .
+# -------------------------------------------------
+
+include(QGCCommon.pri)
+
+TARGET = qgroundcontrol
+
+# Load additional config flags from user_config.pri
+exists(user_config.pri):infile(user_config.pri, CONFIG) {
+ CONFIG += $$fromfile(user_config.pri, CONFIG)
+ message($$sprintf("Using user-supplied additional config: '%1' specified in user_config.pri", $$fromfile(user_config.pri, CONFIG)))
+}
+
+LinuxBuild {
+ CONFIG += link_pkgconfig
+}
+
+message(BASEDIR $$BASEDIR DESTDIR $$DESTDIR TARGET $$TARGET)
+
+# QGC QtLocation plugin
+
+LIBS += -L$${LOCATION_PLUGIN_DESTDIR}
+LIBS += -l$${LOCATION_PLUGIN_NAME}
+
+LinuxBuild|MacBuild|AndroidBuild {
+ PRE_TARGETDEPS += $${LOCATION_PLUGIN_DESTDIR}/lib$${LOCATION_PLUGIN_NAME}.a
+}
+
+WindowsBuild {
+ PRE_TARGETDEPS += $${LOCATION_PLUGIN_DESTDIR}/$${LOCATION_PLUGIN_NAME}.lib
+}
+
+# Qt configuration
+
+CONFIG += qt \
+ thread
+
+QT += network \
+ concurrent \
+ gui \
+ location \
+ opengl \
+ positioning \
+ printsupport \
+ qml \
+ quick \
+ quickwidgets \
+ sql \
+ svg \
+ widgets \
+ xml \
+
+!AndroidBuild {
+ QT += serialport
+}
+
+contains(DEFINES, QGC_NOTIFY_TUNES_ENABLED) {
+ QT += multimedia
+}
+
+# testlib is needed even in release flavor for QSignalSpy support
+QT += testlib
+
+#
+# OS Specific settings
+#
+
+MacBuild {
+ QMAKE_INFO_PLIST = Custom-Info.plist
+ ICON = $$BASEDIR/resources/icons/macx.icns
+ QT += quickwidgets
+}
+
+LinuxBuild {
+ CONFIG += qesp_linux_udev
+}
+
+WindowsBuild {
+ RC_FILE = $$BASEDIR/qgroundcontrol.rc
+}
+
+#
+# Build-specific settings
+#
+
+DebugBuild {
+ CONFIG += console
+}
+
+!AndroidBuild {
+# qextserialport should not be used by general QGroundControl code. Use QSerialPort instead. This is only
+# here to support special case Firmware Upgrade code.
+include(libs/qextserialport/src/qextserialport.pri)
+}
+
+#
+# External library configuration
+#
+
+include(QGCExternalLibs.pri)
+
+#
+# Post link configuration
+#
+
+include(QGCSetup.pri)
+
+#
+# Installer targets
+#
+
+include(QGCInstaller.pri)
+
+#
+# Main QGroundControl portion of project file
+#
+
+RESOURCES += qgroundcontrol.qrc
+
+DEPENDPATH += \
+ . \
+ plugins
+
+INCLUDEPATH += .
+
+INCLUDEPATH += \
+ include/ui \
+ src \
+ src/audio \
+ src/AutoPilotPlugins \
+ src/comm \
+ src/input \
+ src/lib/qmapcontrol \
+ src/QmlControls \
+ src/uas \
+ src/ui \
+ src/ui/configuration \
+ src/ui/flightdisplay \
+ src/ui/linechart \
+ src/ui/map \
+ src/ui/mapdisplay \
+ src/ui/mavlink \
+ src/ui/mission \
+ src/ui/px4_configuration \
+ src/ui/toolbar \
+ src/ui/uas \
+ src/VehicleSetup \
+ src/ViewWidgets \
+
+FORMS += \
+ src/QGCQmlWidgetHolder.ui \
+ src/ui/configuration/SerialSettingsDialog.ui \
+ src/ui/configuration/terminalconsole.ui \
+ src/ui/DebugConsole.ui \
+ src/ui/HDDisplay.ui \
+ src/ui/Linechart.ui \
+ src/ui/MainWindow.ui \
+ src/ui/map/QGCMapTool.ui \
+ src/ui/map/QGCMapToolBar.ui \
+ src/ui/mavlink/QGCMAVLinkMessageSender.ui \
+ src/ui/MAVLinkSettingsWidget.ui \
+ src/ui/mission/QGCMissionConditionDelay.ui \
+ src/ui/mission/QGCMissionDoFinishSearch.ui \
+ src/ui/mission/QGCMissionDoJump.ui \
+ src/ui/mission/QGCMissionDoStartSearch.ui \
+ src/ui/mission/QGCMissionNavLand.ui \
+ src/ui/mission/QGCMissionNavLoiterTime.ui \
+ src/ui/mission/QGCMissionNavLoiterTurns.ui \
+ src/ui/mission/QGCMissionNavLoiterUnlim.ui \
+ src/ui/mission/QGCMissionNavReturnToLaunch.ui \
+ src/ui/mission/QGCMissionNavSweep.ui \
+ src/ui/mission/QGCMissionNavTakeoff.ui \
+ src/ui/mission/QGCMissionNavWaypoint.ui \
+ src/ui/mission/QGCMissionOther.ui \
+ src/ui/px4_configuration/PX4RCCalibration.ui \
+ src/ui/QGCCommConfiguration.ui \
+ src/ui/QGCDataPlot2D.ui \
+ src/ui/QGCHilConfiguration.ui \
+ src/ui/QGCHilFlightGearConfiguration.ui \
+ src/ui/QGCHilJSBSimConfiguration.ui \
+ src/ui/QGCHilXPlaneConfiguration.ui \
+ src/ui/QGCLinkConfiguration.ui \
+ src/ui/QGCMapRCToParamDialog.ui \
+ src/ui/QGCMAVLinkInspector.ui \
+ src/ui/QGCMAVLinkLogPlayer.ui \
+ src/ui/QGCPluginHost.ui \
+ src/ui/QGCTabbedInfoView.ui \
+ src/ui/QGCTCPLinkConfiguration.ui \
+ src/ui/QGCUASFileView.ui \
+ src/ui/QGCUASFileViewMulti.ui \
+ src/ui/QGCUDPLinkConfiguration.ui \
+ src/ui/QGCWaypointListMulti.ui \
+ src/ui/SerialSettings.ui \
+ src/ui/SettingsDialog.ui \
+ src/ui/uas/QGCUnconnectedInfoWidget.ui \
+ src/ui/uas/UASMessageView.ui \
+ src/ui/uas/UASQuickView.ui \
+ src/ui/uas/UASQuickViewItemSelect.ui \
+ src/ui/UASControl.ui \
+ src/ui/UASInfo.ui \
+ src/ui/UASList.ui \
+ src/ui/UASRawStatusView.ui \
+ src/ui/UASView.ui \
+ src/ui/WaypointEditableView.ui \
+ src/ui/WaypointList.ui \
+ src/ui/WaypointViewOnlyView.ui \
+
+!AndroidBuild {
+FORMS += \
+ src/ui/JoystickButton.ui \
+ src/ui/JoystickAxis.ui \
+ src/ui/JoystickWidget.ui
+}
+
+HEADERS += \
+ src/audio/QGCAudioWorker.h \
+ src/CmdLineOptParser.h \
+ src/comm/LinkConfiguration.h \
+ src/comm/LinkInterface.h \
+ src/comm/LinkManager.h \
+ src/comm/MAVLinkProtocol.h \
+ src/comm/MockLink.h \
+ src/comm/MockLinkMissionItemHandler.h \
+ src/comm/ProtocolInterface.h \
+ src/comm/QGCFlightGearLink.h \
+ src/comm/QGCHilLink.h \
+ src/comm/QGCJSBSimLink.h \
+ src/comm/QGCMAVLink.h \
+ src/comm/QGCXPlaneLink.h \
+ src/comm/SerialLink.h \
+ src/comm/TCPLink.h \
+ src/comm/UDPLink.h \
+ src/GAudioOutput.h \
+ src/LogCompressor.h \
+ src/MG.h \
+ src/QGC.h \
+ src/QGCApplication.h \
+ src/QGCComboBox.h \
+ src/QGCConfig.h \
+ src/QGCDockWidget.h \
+ src/QGCFileDialog.h \
+ src/QGCGeo.h \
+ src/QGCLoggingCategory.h \
+ src/QGCMessageBox.h \
+ src/QGCPalette.h \
+ src/QGCQmlWidgetHolder.h \
+ src/QGCQuickWidget.h \
+ src/QGCSingleton.h \
+ src/QGCTemporaryFile.h \
+ src/QmlControls/ParameterEditorController.h \
+ src/QmlControls/ScreenTools.h \
+ src/uas/QGCMAVLinkUASFactory.h \
+ src/uas/QGCUASFileManager.h \
+ src/uas/UAS.h \
+ src/uas/UASInterface.h \
+ src/uas/UASManager.h \
+ src/uas/UASManagerInterface.h \
+ src/uas/UASMessageHandler.h \
+ src/uas/UASWaypointManager.h \
+ src/ui/configuration/ApmHighlighter.h \
+ src/ui/configuration/console.h \
+ src/ui/configuration/SerialSettingsDialog.h \
+ src/ui/configuration/terminalconsole.h \
+ src/ui/DebugConsole.h \
+ src/ui/flightdisplay/QGCFlightDisplay.h \
+ src/ui/HDDisplay.h \
+ src/ui/HSIDisplay.h \
+ src/ui/HUD.h \
+ src/ui/linechart/ChartPlot.h \
+ src/ui/linechart/IncrementalPlot.h \
+ src/ui/linechart/LinechartPlot.h \
+ src/ui/linechart/Linecharts.h \
+ src/ui/linechart/LinechartWidget.h \
+ src/ui/linechart/Scrollbar.h \
+ src/ui/linechart/ScrollZoomer.h \
+ src/ui/MainWindow.h \
+ src/ui/map/MAV2DIcon.h \
+ src/ui/map/QGCMapTool.h \
+ src/ui/map/QGCMapToolBar.h \
+ src/ui/map/QGCMapWidget.h \
+ src/ui/map/Waypoint2DIcon.h \
+ src/ui/mapdisplay/QGCMapDisplay.h \
+ src/ui/mavlink/QGCMAVLinkMessageSender.h \
+ src/ui/MAVLinkDecoder.h \
+ src/ui/MAVLinkSettingsWidget.h \
+ src/ui/mission/QGCMissionConditionDelay.h \
+ src/ui/mission/QGCMissionDoFinishSearch.h \
+ src/ui/mission/QGCMissionDoJump.h \
+ src/ui/mission/QGCMissionDoStartSearch.h \
+ src/ui/mission/QGCMissionNavLand.h \
+ src/ui/mission/QGCMissionNavLoiterTime.h \
+ src/ui/mission/QGCMissionNavLoiterTurns.h \
+ src/ui/mission/QGCMissionNavLoiterUnlim.h \
+ src/ui/mission/QGCMissionNavReturnToLaunch.h \
+ src/ui/mission/QGCMissionNavSweep.h \
+ src/ui/mission/QGCMissionNavTakeoff.h \
+ src/ui/mission/QGCMissionNavWaypoint.h \
+ src/ui/mission/QGCMissionOther.h \
+ src/ui/px4_configuration/PX4RCCalibration.h \
+ src/ui/px4_configuration/RCValueWidget.h \
+ src/ui/QGCCommConfiguration.h \
+ src/ui/QGCDataPlot2D.h \
+ src/ui/QGCHilConfiguration.h \
+ src/ui/QGCHilFlightGearConfiguration.h \
+ src/ui/QGCHilJSBSimConfiguration.h \
+ src/ui/QGCHilXPlaneConfiguration.h \
+ src/ui/QGCLinkConfiguration.h \
+ src/ui/QGCMainWindowAPConfigurator.h \
+ src/ui/QGCMapRCToParamDialog.h \
+ src/ui/QGCMAVLinkInspector.h \
+ src/ui/QGCMAVLinkLogPlayer.h \
+ src/ui/QGCPluginHost.h \
+ src/ui/QGCRGBDView.h \
+ src/ui/QGCTabbedInfoView.h \
+ src/ui/QGCTCPLinkConfiguration.h \
+ src/ui/QGCUASFileView.h \
+ src/ui/QGCUASFileViewMulti.h \
+ src/ui/QGCUDPLinkConfiguration.h \
+ src/ui/QGCWaypointListMulti.h \
+ src/ui/SerialConfigurationWindow.h \
+ src/ui/SettingsDialog.h \
+ src/ui/toolbar/MainToolBar.h \
+ src/ui/uas/QGCUnconnectedInfoWidget.h \
+ src/ui/uas/UASControlWidget.h \
+ src/ui/uas/UASInfoWidget.h \
+ src/ui/uas/UASListWidget.h \
+ src/ui/uas/UASMessageView.h \
+ src/ui/uas/UASQuickView.h \
+ src/ui/uas/UASQuickViewGaugeItem.h \
+ src/ui/uas/UASQuickViewItem.h \
+ src/ui/uas/UASQuickViewItemSelect.h \
+ src/ui/uas/UASQuickViewTextItem.h \
+ src/ui/uas/UASView.h \
+ src/ui/UASRawStatusView.h \
+ src/ui/WaypointEditableView.h \
+ src/ui/WaypointList.h \
+ src/ui/WaypointViewOnlyView.h \
+ src/ViewWidgets/ParameterEditorWidget.h \
+ src/ViewWidgets/ViewWidgetController.h \
+ src/Waypoint.h \
+
+!AndroidBuild {
+HEADERS += \
+ src/input/JoystickInput.h \
+ src/ui/JoystickAxis.h \
+ src/ui/JoystickButton.h \
+ src/ui/JoystickWidget.h \
+ src/ui/CameraView.h \
+}
+
+SOURCES += \
+ src/audio/QGCAudioWorker.cpp \
+ src/CmdLineOptParser.cc \
+ src/comm/LinkConfiguration.cc \
+ src/comm/LinkManager.cc \
+ src/comm/MAVLinkProtocol.cc \
+ src/comm/MockLink.cc \
+ src/comm/MockLinkMissionItemHandler.cc \
+ src/comm/QGCFlightGearLink.cc \
+ src/comm/QGCJSBSimLink.cc \
+ src/comm/QGCXPlaneLink.cc \
+ src/comm/SerialLink.cc \
+ src/comm/TCPLink.cc \
+ src/comm/UDPLink.cc \
+ src/GAudioOutput.cc \
+ src/LogCompressor.cc \
+ src/main.cc \
+ src/QGC.cc \
+ src/QGCApplication.cc \
+ src/QGCComboBox.cc \
+ src/QGCDockWidget.cc \
+ src/QGCFileDialog.cc \
+ src/QGCLoggingCategory.cc \
+ src/QGCPalette.cc \
+ src/QGCQmlWidgetHolder.cpp \
+ src/QGCQuickWidget.cc \
+ src/QGCSingleton.cc \
+ src/QGCTemporaryFile.cc \
+ src/QmlControls/ParameterEditorController.cc \
+ src/QmlControls/ScreenTools.cc \
+ src/uas/QGCMAVLinkUASFactory.cc \
+ src/uas/QGCUASFileManager.cc \
+ src/uas/UAS.cc \
+ src/uas/UASManager.cc \
+ src/uas/UASMessageHandler.cc \
+ src/uas/UASWaypointManager.cc \
+ src/ui/configuration/ApmHighlighter.cc \
+ src/ui/configuration/console.cpp \
+ src/ui/configuration/SerialSettingsDialog.cc \
+ src/ui/configuration/terminalconsole.cpp \
+ src/ui/DebugConsole.cc \
+ src/ui/flightdisplay/QGCFlightDisplay.cc \
+ src/ui/HDDisplay.cc \
+ src/ui/HSIDisplay.cc \
+ src/ui/HUD.cc \
+ src/ui/linechart/ChartPlot.cc \
+ src/ui/linechart/IncrementalPlot.cc \
+ src/ui/linechart/LinechartPlot.cc \
+ src/ui/linechart/Linecharts.cc \
+ src/ui/linechart/LinechartWidget.cc \
+ src/ui/linechart/Scrollbar.cc \
+ src/ui/linechart/ScrollZoomer.cc \
+ src/ui/MainWindow.cc \
+ src/ui/map/MAV2DIcon.cc \
+ src/ui/map/QGCMapTool.cc \
+ src/ui/map/QGCMapToolBar.cc \
+ src/ui/map/QGCMapWidget.cc \
+ src/ui/map/Waypoint2DIcon.cc \
+ src/ui/mapdisplay/QGCMapDisplay.cc \
+ src/ui/mavlink/QGCMAVLinkMessageSender.cc \
+ src/ui/MAVLinkDecoder.cc \
+ src/ui/MAVLinkSettingsWidget.cc \
+ src/ui/mission/QGCMissionConditionDelay.cc \
+ src/ui/mission/QGCMissionDoFinishSearch.cc \
+ src/ui/mission/QGCMissionDoJump.cc \
+ src/ui/mission/QGCMissionDoStartSearch.cc \
+ src/ui/mission/QGCMissionNavLand.cc \
+ src/ui/mission/QGCMissionNavLoiterTime.cc \
+ src/ui/mission/QGCMissionNavLoiterTurns.cc \
+ src/ui/mission/QGCMissionNavLoiterUnlim.cc \
+ src/ui/mission/QGCMissionNavReturnToLaunch.cc \
+ src/ui/mission/QGCMissionNavSweep.cc \
+ src/ui/mission/QGCMissionNavTakeoff.cc \
+ src/ui/mission/QGCMissionNavWaypoint.cc \
+ src/ui/mission/QGCMissionOther.cc \
+ src/ui/px4_configuration/PX4RCCalibration.cc \
+ src/ui/px4_configuration/RCValueWidget.cc \
+ src/ui/QGCCommConfiguration.cc \
+ src/ui/QGCDataPlot2D.cc \
+ src/ui/QGCHilConfiguration.cc \
+ src/ui/QGCHilFlightGearConfiguration.cc \
+ src/ui/QGCHilJSBSimConfiguration.cc \
+ src/ui/QGCHilXPlaneConfiguration.cc \
+ src/ui/QGCLinkConfiguration.cc \
+ src/ui/QGCMainWindowAPConfigurator.cc \
+ src/ui/QGCMapRCToParamDialog.cpp \
+ src/ui/QGCMAVLinkInspector.cc \
+ src/ui/QGCMAVLinkLogPlayer.cc \
+ src/ui/QGCPluginHost.cc \
+ src/ui/QGCRGBDView.cc \
+ src/ui/QGCTabbedInfoView.cpp \
+ src/ui/QGCTCPLinkConfiguration.cc \
+ src/ui/QGCUASFileView.cc \
+ src/ui/QGCUASFileViewMulti.cc \
+ src/ui/QGCUDPLinkConfiguration.cc \
+ src/ui/QGCWaypointListMulti.cc \
+ src/ui/SerialConfigurationWindow.cc \
+ src/ui/SettingsDialog.cc \
+ src/ui/toolbar/MainToolBar.cc \
+ src/ui/uas/QGCUnconnectedInfoWidget.cc \
+ src/ui/uas/UASControlWidget.cc \
+ src/ui/uas/UASInfoWidget.cc \
+ src/ui/uas/UASListWidget.cc \
+ src/ui/uas/UASMessageView.cc \
+ src/ui/uas/UASQuickView.cc \
+ src/ui/uas/UASQuickViewGaugeItem.cc \
+ src/ui/uas/UASQuickViewItem.cc \
+ src/ui/uas/UASQuickViewItemSelect.cc \
+ src/ui/uas/UASQuickViewTextItem.cc \
+ src/ui/uas/UASView.cc \
+ src/ui/UASRawStatusView.cpp \
+ src/ui/WaypointEditableView.cc \
+ src/ui/WaypointList.cc \
+ src/ui/WaypointViewOnlyView.cc \
+ src/ViewWidgets/ParameterEditorWidget.cc \
+ src/ViewWidgets/ViewWidgetController.cc \
+ src/Waypoint.cc \
+
+!AndroidBuild {
+SOURCES += \
+ src/input/JoystickInput.cc \
+ src/ui/JoystickAxis.cc \
+ src/ui/JoystickButton.cc \
+ src/ui/JoystickWidget.cc \
+ src/ui/CameraView.cc
+}
+
+#
+# Unit Test specific configuration goes here
+#
+# We have to special case Windows debug_and_release builds because you can't have files
+# which are only in the debug variant [QTBUG-40351]. So in this case we include unit tests
+# even in the release variant. If you want a Windows release build with no unit tests run
+# qmake with CONFIG-=debug_and_release CONFIG+=release.
+#
+
+DebugBuild|WindowsDebugAndRelease {
+
+HEADERS += src/QmlControls/QmlTestWidget.h
+SOURCES += src/QmlControls/QmlTestWidget.cc
+
+!AndroidBuild {
+
+INCLUDEPATH += \
+ src/qgcunittest
+
+HEADERS += \
+ src/qgcunittest/FlightGearTest.h \
+ src/qgcunittest/MockMavlinkFileServer.h \
+ src/qgcunittest/MockMavlinkInterface.h \
+ src/qgcunittest/MultiSignalSpy.h \
+ src/qgcunittest/TCPLinkTest.h \
+ src/qgcunittest/TCPLoopBackServer.h \
+ src/FactSystem/FactSystemTestBase.h \
+ src/FactSystem/FactSystemTestGeneric.h \
+ src/FactSystem/FactSystemTestPX4.h \
+ src/qgcunittest/FileDialogTest.h \
+ src/qgcunittest/LinkManagerTest.h \
+ src/qgcunittest/MainWindowTest.h \
+ src/qgcunittest/MavlinkLogTest.h \
+ src/qgcunittest/MessageBoxTest.h \
+ src/qgcunittest/PX4RCCalibrationTest.h \
+ src/qgcunittest/UnitTest.h \
+ src/VehicleSetup/SetupViewTest.h \
+
+SOURCES += \
+ src/qgcunittest/FlightGearTest.cc \
+ src/qgcunittest/MockMavlinkFileServer.cc \
+ src/qgcunittest/MultiSignalSpy.cc \
+ src/qgcunittest/TCPLinkTest.cc \
+ src/qgcunittest/TCPLoopBackServer.cc \
+ src/FactSystem/FactSystemTestBase.cc \
+ src/FactSystem/FactSystemTestGeneric.cc \
+ src/FactSystem/FactSystemTestPX4.cc \
+ src/qgcunittest/FileDialogTest.cc \
+ src/qgcunittest/LinkManagerTest.cc \
+ src/qgcunittest/MainWindowTest.cc \
+ src/qgcunittest/MavlinkLogTest.cc \
+ src/qgcunittest/MessageBoxTest.cc \
+ src/qgcunittest/PX4RCCalibrationTest.cc \
+ src/qgcunittest/UnitTest.cc \
+ src/VehicleSetup/SetupViewTest.cc \
+
+} # DebugBuild|WindowsDebugAndRelease
+} # AndroidBuild
+
+#
+# AutoPilot Plugin Support
+#
+
+INCLUDEPATH += \
+ src/VehicleSetup
+
+FORMS += \
+ src/VehicleSetup/SetupView.ui \
+
+HEADERS+= \
+ src/AutoPilotPlugins/AutoPilotPlugin.h \
+ src/AutoPilotPlugins/AutoPilotPluginManager.h \
+ src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h \
+ src/AutoPilotPlugins/Generic/GenericParameterFacts.h \
+ src/AutoPilotPlugins/PX4/AirframeComponent.h \
+ src/AutoPilotPlugins/PX4/AirframeComponentAirframes.h \
+ src/AutoPilotPlugins/PX4/AirframeComponentController.h \
+ src/AutoPilotPlugins/PX4/FlightModesComponent.h \
+ src/AutoPilotPlugins/PX4/FlightModesComponentController.h \
+ src/AutoPilotPlugins/PX4/PowerComponent.h \
+ src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h \
+ src/AutoPilotPlugins/PX4/PX4Component.h \
+ src/AutoPilotPlugins/PX4/PX4ParameterLoader.h \
+ src/AutoPilotPlugins/PX4/RadioComponent.h \
+ src/AutoPilotPlugins/PX4/SafetyComponent.h \
+ src/AutoPilotPlugins/PX4/SensorsComponent.h \
+ src/AutoPilotPlugins/PX4/SensorsComponentController.h \
+ src/VehicleSetup/SetupView.h \
+ src/VehicleSetup/VehicleComponent.h \
+
+!AndroidBuild {
+HEADERS += \
+ src/VehicleSetup/FirmwareUpgradeController.h \
+ src/VehicleSetup/PX4Bootloader.h \
+ src/VehicleSetup/PX4FirmwareUpgradeThread.h
+}
+
+SOURCES += \
+ src/AutoPilotPlugins/AutoPilotPlugin.cc \
+ src/AutoPilotPlugins/AutoPilotPluginManager.cc \
+ src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc \
+ src/AutoPilotPlugins/Generic/GenericParameterFacts.cc \
+ src/AutoPilotPlugins/PX4/AirframeComponent.cc \
+ src/AutoPilotPlugins/PX4/AirframeComponentAirframes.cc \
+ src/AutoPilotPlugins/PX4/AirframeComponentController.cc \
+ src/AutoPilotPlugins/PX4/FlightModesComponent.cc \
+ src/AutoPilotPlugins/PX4/FlightModesComponentController.cc \
+ src/AutoPilotPlugins/PX4/PowerComponent.cc \
+ src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc \
+ src/AutoPilotPlugins/PX4/PX4Component.cc \
+ src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc \
+ src/AutoPilotPlugins/PX4/RadioComponent.cc \
+ src/AutoPilotPlugins/PX4/SafetyComponent.cc \
+ src/AutoPilotPlugins/PX4/SensorsComponent.cc \
+ src/AutoPilotPlugins/PX4/SensorsComponentController.cc \
+ src/VehicleSetup/SetupView.cc \
+ src/VehicleSetup/VehicleComponent.cc \
+
+!AndroidBuild {
+SOURCES += \
+ src/VehicleSetup/FirmwareUpgradeController.cc \
+ src/VehicleSetup/PX4Bootloader.cc \
+ src/VehicleSetup/PX4FirmwareUpgradeThread.cc
+}
+
+# Fact System code
+
+INCLUDEPATH += \
+ src/FactSystem
+
+HEADERS += \
+ src/FactSystem/Fact.h \
+ src/FactSystem/FactBinder.h \
+ src/FactSystem/FactMetaData.h \
+ src/FactSystem/FactSystem.h \
+ src/FactSystem/FactValidator.h \
+ src/FactSystem/ParameterLoader.h \
+
+SOURCES += \
+ src/FactSystem/Fact.cc \
+ src/FactSystem/FactBinder.cc \
+ src/FactSystem/FactMetaData.cc \
+ src/FactSystem/FactSystem.cc \
+ src/FactSystem/FactValidator.cc \
+ src/FactSystem/ParameterLoader.cc \
+
+# Android
+
+AndroidBuild {
+ include($$PWD/libs/qtandroidserialport/src/qtandroidserialport.pri)
+ message("Adding Serial Java Classes")
+ QT += androidextras
+ ANDROID_PACKAGE_SOURCE_DIR = $$PWD/android
+ OTHER_FILES += \
+ $$PWD/android/AndroidManifest.xml \
+ $$PWD/android/res/xml/device_filter.xml \
+ $$PWD/android/src/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java \
+ $$PWD/android/src/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java \
+ $$PWD/android/src/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java \
+ $$PWD/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java \
+ $$PWD/android/src/com/hoho/android/usbserial/driver/ProlificSerialDriver.java \
+ $$PWD/android/src/com/hoho/android/usbserial/driver/UsbId.java \
+ $$PWD/android/src/com/hoho/android/usbserial/driver/UsbSerialDriver.java \
+ $$PWD/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java \
+ $$PWD/android/src/com/hoho/android/usbserial/driver/UsbSerialRuntimeException.java \
+ $$PWD/android/src/org/qgroundcontrol/qgchelper/UsbDeviceJNI.java \
+ $$PWD/android/src/org/qgroundcontrol/qgchelper/UsbIoManager.java
+}
diff --git a/QGCCommon.pri b/QGCCommon.pri
new file mode 100644
index 0000000000000000000000000000000000000000..85510004bfb161df693a9ef1131d1d006fbda476
--- /dev/null
+++ b/QGCCommon.pri
@@ -0,0 +1,195 @@
+# -------------------------------------------------
+# QGroundControl - Micro Air Vehicle Groundstation
+# Please see our website at
+# Maintainer:
+# Lorenz Meier
+# (c) 2009-2014 QGroundControl Developers
+# This file is part of the open groundstation project
+# QGroundControl is free software: you can redistribute it and/or modify
+# it under the terms of the GNU General Public License as published by
+# the Free Software Foundation, either version 3 of the License, or
+# (at your option) any later version.
+# QGroundControl is distributed in the hope that it will be useful,
+# but WITHOUT ANY WARRANTY; without even the implied warranty of
+# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+# GNU General Public License for more details.
+# You should have received a copy of the GNU General Public License
+# along with QGroundControl. If not, see .
+# -------------------------------------------------
+
+#
+# This file contains configuration settings which are common to both the QGC Application and
+# the Location Plugin. It should mainly contains intial CONFIG tag setup and compiler settings.
+#
+
+# Setup our supported build types. We do this once here and then use the defined config scopes
+# to allow us to easily modify suported build types in one place instead of duplicated throughout
+# the project file.
+
+linux {
+ linux-g++ | linux-g++-64 {
+ message("Linux build")
+ CONFIG += LinuxBuild
+ } else : android-g++ {
+ message("Android build")
+ CONFIG += AndroidBuild
+ DEFINES += __mobile__
+ DEFINES += __android__
+ warning("Android build is experimental and not fully functional")
+ } else {
+ error("Unsuported Linux toolchain, only GCC 32- or 64-bit is supported")
+ }
+} else : win32 {
+ win32-msvc2010 | win32-msvc2012 | win32-msvc2013 {
+ message("Windows build")
+ CONFIG += WindowsBuild
+ } else {
+ error("Unsupported Windows toolchain, only Visual Studio 2010, 2012, and 2013 are supported")
+ }
+} else : macx {
+ macx-clang | macx-llvm {
+ message("Mac build")
+ CONFIG += MacBuild
+ QMAKE_CXXFLAGS += -fvisibility=hidden
+ } else {
+ error("Unsupported Mac toolchain, only 64-bit LLVM+clang is supported")
+ }
+} else {
+ error("Unsupported build platform, only Linux, Windows, and Mac are supported")
+}
+
+# Installer configuration
+
+installer {
+ CONFIG -= debug
+ CONFIG -= debug_and_release
+ CONFIG += release
+ message(Build Installer)
+}
+
+# Setup our supported build flavors
+
+CONFIG(debug, debug|release) {
+ message(Debug flavor)
+ CONFIG += DebugBuild
+} else:CONFIG(release, debug|release) {
+ message(Release flavor)
+ CONFIG += ReleaseBuild
+} else {
+ error(Unsupported build flavor)
+}
+
+# Need to special case Windows debug_and_release since VS Project creation in this case does strange things [QTBUG-40351]
+win32:debug_and_release {
+ CONFIG += WindowsDebugAndRelease
+}
+
+# Setup our build directories
+
+BASEDIR = $${IN_PWD}
+
+DebugBuild {
+ DESTDIR = $${OUT_PWD}/debug
+ BUILDDIR = $${OUT_PWD}/build-debug
+}
+
+ReleaseBuild {
+ DESTDIR = $${OUT_PWD}/release
+ BUILDDIR = $${OUT_PWD}/build-release
+}
+
+OBJECTS_DIR = $${BUILDDIR}/obj
+MOC_DIR = $${BUILDDIR}/moc
+UI_DIR = $${BUILDDIR}/ui
+RCC_DIR = $${BUILDDIR}/rcc
+LANGUAGE = C++
+
+# We place the created plugin lib into the objects dir so that make clean will clean it as well
+LOCATION_PLUGIN_DESTDIR = $${OBJECTS_DIR}
+LOCATION_PLUGIN_NAME = QGeoServiceProviderFactoryQGC
+
+message(BASEDIR $$BASEDIR DESTDIR $$DESTDIR TARGET $$TARGET)
+
+# Turn off serial port warnings
+DEFINES += _TTY_NOWARN_
+
+#
+# OS Specific settings
+#
+
+AndroidBuild {
+ DEFINES += __STDC_LIMIT_MACROS
+}
+
+MacBuild {
+ CONFIG += x86_64
+ CONFIG -= x86
+ QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6
+ QMAKE_MAC_SDK = macosx10.9
+}
+
+LinuxBuild {
+ DEFINES += __STDC_LIMIT_MACROS
+}
+
+WindowsBuild {
+ DEFINES += __STDC_LIMIT_MACROS
+
+ # Specify multi-process compilation within Visual Studio.
+ # (drastically improves compilation times for multi-core computers)
+ QMAKE_CXXFLAGS_DEBUG += -MP
+ QMAKE_CXXFLAGS_RELEASE += -MP
+}
+
+#
+# By default warnings as errors are turned off. Even so, in order for a pull request
+# to be accepted you must compile cleanly with warnings as errors turned on the default
+# set of OS builds. See http://www.qgroundcontrol.org/dev/contribute for more details.
+# You can use the WarningsAsErrorsOn CONFIG switch to turn warnings as errors on for your
+# own builds.
+#
+
+MacBuild | LinuxBuild {
+ QMAKE_CXXFLAGS_WARN_ON += -Wall
+ WarningsAsErrorsOn {
+ QMAKE_CXXFLAGS_WARN_ON += -Werror
+ }
+}
+
+WindowsBuild {
+ QMAKE_CXXFLAGS_WARN_ON += /W3 \
+ /wd4996 \ # silence warnings about deprecated strcpy and whatnot
+ /wd4005 \ # silence warnings about macro redefinition
+ /wd4290 \ # ignore exception specifications
+ /Zc:strictStrings- # work around win 8.1 sdk sapi.h problem
+ WarningsAsErrorsOn {
+ QMAKE_CXXFLAGS_WARN_ON += /WX
+ }
+}
+
+#
+# Build-specific settings
+#
+
+ReleaseBuild {
+ DEFINES += QT_NO_DEBUG
+
+ WindowsBuild {
+ # Use link time code generation for better optimization (I believe this is supported in MSVC Express, but not 100% sure)
+ QMAKE_LFLAGS_LTCG = /LTCG
+ QMAKE_CFLAGS_LTCG = -GL
+ }
+}
+
+#
+# Unit Test specific configuration goes here
+#
+# We have to special case Windows debug_and_release builds because you can't have files
+# which are only in the debug variant [QTBUG-40351]. So in this case we include unit tests
+# even in the release variant. If you want a Windows release build with no unit tests run
+# qmake with CONFIG-=debug_and_release CONFIG+=release.
+#
+
+DebugBuild|WindowsDebugAndRelease {
+ DEFINES += UNITTEST_BUILD
+}
diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri
index dcda60c9a4fdbb2a6bf16c16738303a1cc1edfc9..03ae6cf709151af0462ced13d53a9cff23010ae6 100644
--- a/QGCExternalLibs.pri
+++ b/QGCExternalLibs.pri
@@ -55,153 +55,6 @@ exists($$MAVLINKPATH/common) {
error($$sprintf("MAVLink folder does not exist at '%1'! Run 'git submodule init && git submodule update' on the command line.",$$MAVLINKPATH_REL))
}
-#
-# [OPTIONAL] OpenSceneGraph
-# Allow the user to override OpenSceneGraph compilation through a DISABLE_OPEN_SCENE_GRAPH
-# define like: `qmake DEFINES=DISABLE_OPEN_SCENE_GRAPH`
-contains(DEFINES, DISABLE_OPEN_SCENE_GRAPH) {
- message("Skipping support for OpenSceneGraph (manual override from command line)")
- DEFINES -= DISABLE_OPEN_SCENE_GRAPH
-}
-# Otherwise the user can still disable this feature in the user_config.pri file.
-else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_OPEN_SCENE_GRAPH) {
- message("Skipping support for OpenSceneGraph (manual override from user_config.pri)")
-}
-else:MacBuild {
- # GLUT and OpenSceneGraph are part of standard install on Mac
- message("Including support for OpenSceneGraph")
- CONFIG += OSGDependency
-
- INCLUDEPATH += \
- $$BASEDIR/libs/lib/mac64/include
-
- LIBS += \
- -L$$BASEDIR/libs/lib/mac64/lib \
- -losgWidget
-} else:LinuxBuild {
- exists(/usr/include/osg) | exists(/usr/local/include/osg) {
- message("Including support for OpenSceneGraph")
- CONFIG += OSGDependency
- } else {
- warning("Skipping support for OpenSceneGraph (missing libraries, see README)")
- }
-} else:WindowsBuild {
- exists($$BASEDIR/libs/lib/osg123) {
- message("Including support for OpenSceneGraph")
- CONFIG += OSGDependency
-
- INCLUDEPATH += \
- $$BASEDIR/libs/lib/osgEarth/win32/include \
- $$BASEDIR/libs/lib/osgEarth_3rdparty/win32/OpenSceneGraph-2.8.2/include
-
- LIBS += -L$$BASEDIR/libs/lib/osgEarth_3rdparty/win32/OpenSceneGraph-2.8.2/lib
- } else {
- warning("Skipping support for OpenSceneGraph (missing libraries, see README)")
- }
-} else {
- message("Skipping support for OpenSceneGraph (unsupported platform)")
-}
-
-OSGDependency {
- DEFINES += QGC_OSG_ENABLED
-
- LIBS += \
- -losg \
- -losgViewer \
- -losgGA \
- -losgDB \
- -losgText \
- -lOpenThreads
-
- HEADERS += \
- src/ui/map3D/gpl.h \
- src/ui/map3D/CameraParams.h \
- src/ui/map3D/ViewParamWidget.h \
- src/ui/map3D/SystemContainer.h \
- src/ui/map3D/SystemViewParams.h \
- src/ui/map3D/GlobalViewParams.h \
- src/ui/map3D/SystemGroupNode.h \
- src/ui/map3D/Q3DWidget.h \
- src/ui/map3D/GCManipulator.h \
- src/ui/map3D/ImageWindowGeode.h \
- src/ui/map3D/PixhawkCheetahNode.h \
- src/ui/map3D/Pixhawk3DWidget.h \
- src/ui/map3D/Q3DWidgetFactory.h \
- src/ui/map3D/WebImageCache.h \
- src/ui/map3D/WebImage.h \
- src/ui/map3D/TextureCache.h \
- src/ui/map3D/Texture.h \
- src/ui/map3D/Imagery.h \
- src/ui/map3D/HUDScaleGeode.h \
- src/ui/map3D/WaypointGroupNode.h \
- src/ui/map3D/TerrainParamDialog.h \
- src/ui/map3D/ImageryParamDialog.h
-
- SOURCES += \
- src/ui/map3D/gpl.cc \
- src/ui/map3D/CameraParams.cc \
- src/ui/map3D/ViewParamWidget.cc \
- src/ui/map3D/SystemContainer.cc \
- src/ui/map3D/SystemViewParams.cc \
- src/ui/map3D/GlobalViewParams.cc \
- src/ui/map3D/SystemGroupNode.cc \
- src/ui/map3D/Q3DWidget.cc \
- src/ui/map3D/ImageWindowGeode.cc \
- src/ui/map3D/GCManipulator.cc \
- src/ui/map3D/PixhawkCheetahNode.cc \
- src/ui/map3D/Pixhawk3DWidget.cc \
- src/ui/map3D/Q3DWidgetFactory.cc \
- src/ui/map3D/WebImageCache.cc \
- src/ui/map3D/WebImage.cc \
- src/ui/map3D/TextureCache.cc \
- src/ui/map3D/Texture.cc \
- src/ui/map3D/Imagery.cc \
- src/ui/map3D/HUDScaleGeode.cc \
- src/ui/map3D/WaypointGroupNode.cc \
- src/ui/map3D/TerrainParamDialog.cc \
- src/ui/map3D/ImageryParamDialog.cc
-}
-
-#
-# [OPTIONAL] Google Earth dependency. Provides Google Earth view to supplement 2D map view.
-# Only supported on Mac and Windows where Google Earth can be installed.
-#
-GoogleEarthDisableOverride {
- contains(DEFINES, DISABLE_GOOGLE_EARTH) {
- message("Skipping support for Google Earth view (manual override from command line)")
- DEFINES -= DISABLE_GOOGLE_EARTH
- }
- # Otherwise the user can still disable this feature in the user_config.pri file.
- else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_GOOGLE_EARTH) {
- message("Skipping support for Google Earth view (manual override from user_config.pri)")
- } else:MacBuild {
- message("Including support for Google Earth view")
- DEFINES += QGC_GOOGLE_EARTH_ENABLED
- HEADERS += src/ui/map3D/QGCGoogleEarthView.h \
- src/ui/map3D/QGCWebPage.h \
- src/ui/QGCWebView.h
- SOURCES += src/ui/map3D/QGCGoogleEarthView.cc \
- src/ui/map3D/QGCWebPage.cc \
- src/ui/QGCWebView.cc
- FORMS += src/ui/QGCWebView.ui
- } else:WindowsBuild {
- message("Including support for Google Earth view")
- DEFINES += QGC_GOOGLE_EARTH_ENABLED
- HEADERS += src/ui/map3D/QGCGoogleEarthView.h \
- src/ui/map3D/QGCWebPage.h \
- src/ui/QGCWebView.h
- SOURCES += src/ui/map3D/QGCGoogleEarthView.cc \
- src/ui/map3D/QGCWebPage.cc \
- src/ui/QGCWebView.cc
- FORMS += src/ui/QGCWebView.ui
- QT += axcontainer
- } else {
- message("Skipping support for Google Earth view (unsupported platform)")
- }
-} else {
- message("Skipping support for Google Earth due to Issue 1157")
-}
-
#
# [REQUIRED] EIGEN matrix library
# NOMINMAX constant required to make internal min/max work.
@@ -416,11 +269,12 @@ contains (DEFINES, DISABLE_SPEECH) {
}
# Mac support is built into OS 10.6+.
else:MacBuild {
- message("Including support for speech output")
- DEFINES += QGC_SPEECH_ENABLED
+ message("Including support for speech output")
+ DEFINES += QGC_SPEECH_ENABLED
}
# Windows supports speech through native API.
else:WindowsBuild {
- message("Including support for speech output")
- DEFINES += QGC_SPEECH_ENABLED
+ message("Including support for speech output")
+ DEFINES += QGC_SPEECH_ENABLED
+ LIBS += -lOle32
}
diff --git a/QGCLocationPlugin.pro b/QGCLocationPlugin.pro
new file mode 100644
index 0000000000000000000000000000000000000000..e2da91af333e2ad38abeb5ba0ceffb5e401c3c95
--- /dev/null
+++ b/QGCLocationPlugin.pro
@@ -0,0 +1,33 @@
+include(QGCCommon.pri)
+
+TEMPLATE = lib
+TARGET = QGeoServiceProviderFactoryQGC
+CONFIG += plugin static
+QT += location-private positioning-private network
+PLUGIN_TYPE = geoservices
+
+DESTDIR = $${LOCATION_PLUGIN_DESTDIR}
+
+INCLUDEPATH += $$QT.location.includes
+
+HEADERS += \
+ src/QtLocationPlugin/qgeoserviceproviderpluginqgc.h \
+ src/QtLocationPlugin/qgeotiledmappingmanagerengineqgc.h \
+ src/QtLocationPlugin/qgeotilefetcherqgc.h \
+ src/QtLocationPlugin/qgeomapreplyqgc.h \
+ src/QtLocationPlugin/qgeocodingmanagerengineqgc.h \
+ src/QtLocationPlugin/qgeocodereplyqgc.h \
+ src/QtLocationPlugin/OpenPilotMaps.h
+
+SOURCES += \
+ src/QtLocationPlugin/qgeoserviceproviderpluginqgc.cpp \
+ src/QtLocationPlugin/qgeotiledmappingmanagerengineqgc.cpp \
+ src/QtLocationPlugin/qgeotilefetcherqgc.cpp \
+ src/QtLocationPlugin/qgeomapreplyqgc.cpp \
+ src/QtLocationPlugin/qgeocodingmanagerengineqgc.cpp \
+ src/QtLocationPlugin/qgeocodereplyqgc.cpp \
+ src/QtLocationPlugin/OpenPilotMaps.cc
+
+OTHER_FILES += \
+ src/QtLocationPlugin/qgc_maps_plugin.json
+
diff --git a/QGCSetup.pri b/QGCSetup.pri
index 08dd8f8b716cdca65857644aa0ede36df4686e5e..cce994557c81bf9a1832c27e47c7a425323283be 100644
--- a/QGCSetup.pri
+++ b/QGCSetup.pri
@@ -19,6 +19,10 @@
QMAKE_POST_LINK += echo "Copying files"
+AndroidBuild {
+ INSTALLS += $$DESTDIR
+}
+
#
# Copy the application resources to the associated place alongside the application
#
@@ -36,14 +40,14 @@ MacBuild {
# in the target.
WindowsBuild {
# Make sure to keep both side of this if using the same set of directories
- DESTDIR_COPY_RESOURCE_LIST = $$replace(DESTDIR,"/","\\")
- BASEDIR_COPY_RESOURCE_LIST = $$replace(BASEDIR,"/","\\")
- QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$BASEDIR_COPY_RESOURCE_LIST\\files\" \"$$DESTDIR_COPY_RESOURCE_LIST\\files\"
- QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$BASEDIR_COPY_RESOURCE_LIST\\data\" \"$$DESTDIR_COPY_RESOURCE_LIST\\data\"
+ DESTDIR_COPY_RESOURCE_LIST = $$replace(DESTDIR,"/","\\")
+ BASEDIR_COPY_RESOURCE_LIST = $$replace(BASEDIR,"/","\\")
+ QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$BASEDIR_COPY_RESOURCE_LIST\\flightgear\" \"$$DESTDIR_COPY_RESOURCE_LIST\\flightgear\"
} else {
- # Make sure to keep both side of this if using the same set of directories
- QMAKE_POST_LINK += && $$QMAKE_COPY_DIR $$BASEDIR/files $$DESTDIR_COPY_RESOURCE_LIST
- QMAKE_POST_LINK += && $$QMAKE_COPY_DIR $$BASEDIR/data $$DESTDIR_COPY_RESOURCE_LIST
+ !AndroidBuild {
+ # Make sure to keep both sides of this if using the same set of directories
+ QMAKE_POST_LINK += && $$QMAKE_COPY_DIR $$BASEDIR/flightgear $$DESTDIR_COPY_RESOURCE_LIST
+ }
}
#
@@ -153,13 +157,13 @@ MacBuild {
}
WindowsBuild {
- BASEDIR_WIN = $$replace(BASEDIR, "/", "\\")
- DESTDIR_WIN = $$replace(DESTDIR, "/", "\\")
- D_DIR = $$[QT_INSTALL_LIBEXECS]
- DLL_DIR = $$replace(D_DIR, "/", "\\")
+ BASEDIR_WIN = $$replace(BASEDIR, "/", "\\")
+ DESTDIR_WIN = $$replace(DESTDIR, "/", "\\")
+ D_DIR = $$[QT_INSTALL_LIBEXECS]
+ DLL_DIR = $$replace(D_DIR, "/", "\\")
- # Copy dependencies
- DebugBuild: DLL_QT_DEBUGCHAR = "d"
+ # Copy dependencies
+ DebugBuild: DLL_QT_DEBUGCHAR = "d"
ReleaseBuild: DLL_QT_DEBUGCHAR = ""
COPY_FILE_LIST = \
$$BASEDIR\\libs\\lib\\sdl\\win32\\SDL.dll \
@@ -167,6 +171,7 @@ WindowsBuild {
$$DLL_DIR\\icu*.dll \
$$DLL_DIR\\Qt5Core$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5Gui$${DLL_QT_DEBUGCHAR}.dll \
+ $$DLL_DIR\\Qt5Location$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5Multimedia$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5MultimediaWidgets$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5Network$${DLL_QT_DEBUGCHAR}.dll \
@@ -178,7 +183,6 @@ WindowsBuild {
$$DLL_DIR\\Qt5QuickWidgets$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5Sensors$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5SerialPort$${DLL_QT_DEBUGCHAR}.dll \
- $$DLL_DIR\\Qt5OpenGL$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5Sql$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5Svg$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5Test$${DLL_QT_DEBUGCHAR}.dll \
@@ -190,17 +194,18 @@ WindowsBuild {
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$COPY_FILE\" \"$$DESTDIR_WIN\"
}
- # Copy platform plugins
- P_DIR = $$[QT_INSTALL_PLUGINS]
- PLUGINS_DIR_WIN = $$replace(P_DIR, "/", "\\")
- QMAKE_POST_LINK += $$escape_expand(\\n) mkdir release\\platforms
- QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$PLUGINS_DIR_WIN\\platforms\\qwindows$${DLL_QT_DEBUGCHAR}.dll\" \"$$DESTDIR_WIN\\platforms\\qwindows$${DLL_QT_DEBUGCHAR}.dll\"
- QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$PLUGINS_DIR_WIN\\imageformats\" \"$$DESTDIR_WIN\\imageformats\"
+ # Copy platform plugins
+ P_DIR = $$[QT_INSTALL_PLUGINS]
+ PLUGINS_DIR_WIN = $$replace(P_DIR, "/", "\\")
+ QMAKE_POST_LINK += $$escape_expand(\\n) mkdir "$$DESTDIR_WIN\\platforms"
+ QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$PLUGINS_DIR_WIN\\platforms\\qwindows$${DLL_QT_DEBUGCHAR}.dll\" \"$$DESTDIR_WIN\\platforms\\qwindows$${DLL_QT_DEBUGCHAR}.dll\"
+ QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$PLUGINS_DIR_WIN\\imageformats\" \"$$DESTDIR_WIN\\imageformats\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$PLUGINS_DIR_WIN\\sqldrivers\" \"$$DESTDIR_WIN\\sqldrivers\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$PLUGINS_DIR_WIN\\bearer\" \"$$DESTDIR_WIN\\bearer\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$PLUGINS_DIR_WIN\\iconengines\" \"$$DESTDIR_WIN\\iconengines\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$PLUGINS_DIR_WIN\\printsupport\" \"$$DESTDIR_WIN\\printsupport\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$PLUGINS_DIR_WIN\\qmltooling\" \"$$DESTDIR_WIN\\qmltooling\"
+ QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$PLUGINS_DIR_WIN\\geoservices\" \"$$DESTDIR_WIN\\geoservices\"
# Copy Qml libraries
Q_DIR = $$[QT_INSTALL_QML]
@@ -208,6 +213,8 @@ WindowsBuild {
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$QML_DIR_WIN\\QtGraphicalEffects\" \"$$DESTDIR_WIN\\QtGraphicalEffects\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$QML_DIR_WIN\\QtQuick\" \"$$DESTDIR_WIN\\QtQuick\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$QML_DIR_WIN\\QtQuick.2\" \"$$DESTDIR_WIN\\QtQuick.2\"
+ QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$QML_DIR_WIN\\QtLocation\" \"$$DESTDIR_WIN\\QtLocation\"
+ QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$QML_DIR_WIN\\QtPositioning\" \"$$DESTDIR_WIN\\QtPositioning\"
ReleaseBuild {
# Copy Visual Studio DLLs
diff --git a/README.md b/README.md
index dd28e016560017aac5fcab821f5f2385741fe50e..f2d3becd1a67262440bb6aebd667da131573b09d 100644
--- a/README.md
+++ b/README.md
@@ -50,7 +50,7 @@ QGroundControl builds are supported for OSX, Linux and Windows. See the individu
Supported builds are 64 bit, built using the clang compiler.
#### Install QT
-- - -
+
1. Download Qt 5.4 from:
2. Double click the package installer and follow instructions.
@@ -66,12 +66,14 @@ Supported builds for Linux are 32 or 64-bit, built using gcc.
* For Fedora: `sudo yum install qt-creator qt5-qtbase-devel qt5-qtdeclarative-devel qt5-qtserialport-devel qt5-qtsvg-devel qt5-qtwebkit-devel SDL-devel SDL-static systemd-devel qt5-qtgraphicaleffects qt5-qtquickcontrols`
* For Arch Linux: `pacman -Sy qtcreator qt5-base qt5-declarative qt5-serialport qt5-svg qt5-webkit`
* For Ubuntu: Please be aware that the time of writing, Qt5.4 is unavailable in the official repositories Ubuntu 14.04/Mint 17
- * Add this PPA to your sources.list: `ppa:beineri/opt-qt541-trusty`
+ * Add this PPA for Qt5.4: `sudo add-apt-repository ppa:beineri/opt-qt541-trusty`
* If you get a 404 error from "apt-get update" below, open System Settings:Software & Updates:Other Software and edit the entry for opt-qt541-trusty to reference Distribution: trusty.
- * Run the following in your terminal: `sudo apt-get update && sudo apt-get install qt54tools qt54base qt54declarative qt54serialport qt54svg qt54webkit qt54quickcontrols qt54xmlpatterns qt54x11extras qt54websockets qt54sensors qt54script qt54quick1 qt54qbs qt54multimedia qt54location qt54imageformats qt54graphicaleffects qt54creator qt54connectivity`
+ * Run the following in your terminal: `sudo apt-get update && sudo apt-get install qt54tools qt54base qt54declarative qt54serialport qt54svg qt54webkit qt54quickcontrols qt54xmlpatterns qt54x11extras qt54websockets qt54sensors qt54script qt54quick1 qt54qbs qt54multimedia qt54location qt54imageformats qt54graphicaleffects qt54creator qt54connectivity libsdl1.2-dev libudev-dev`
* Next, set the environment variables by executing in the terminal: `source /opt/qt54/bin/qt54-env.sh` or copy and paste the contents to your `~/.profile` file to set them on login.
* Verify that the variables have been set: `echo $PATH && echo $QTDIR`. The output should read `/opt/qt54/bin:...` and `/opt/qt54`.
+If you get this error when running qgroundcontrol: /usr/lib/x86_64-linux-gnu/libstdc++.so.6: version 'GLIBCXX_3.4.20' not found. You need to either update to the latest gcc, or install the latest libstdc++.6 using: sudo apt-get install libstdc++6.
+
#### [Optional] Install additional libraries
* For text-to-speech (espeak)
* For Ubuntu: `sudo apt-get install espeak libespeak-dev`
@@ -84,12 +86,15 @@ Supported builds for Linux are 32 or 64-bit, built using gcc.
#### Build QGroundControl
1. Change directory to you `qgroundcontrol` source directory.
-2. Run `qmake`
+2. Run `qmake -r qgroundcontrol.pro`
3. Run `make`
### Build on Windows
Supported builds for Windows are 32 bit only built using Visual Studio 2013 or higher.
+#### Install Windows USB driver to connect to Pixhawk/PX4Flow/3DR Radio
+Install from here: http://www.pixhawk.org/firmware/downloads
+
#### Install Visual Studio Express 2013
Only compilation using Visual Studio 2013 is supported. Download and install Visual Studio Express Edition (free) from here: . Make sure you install the Windows Desktop version.
@@ -100,9 +105,30 @@ Download Qt 5.4 from here:
+ * On Ubuntu, you have to set the file to executable:`chmod +x ~/Downloads/qt-opensource-linux-x64-1.6.0-8-online.run\`
+* Run the installer and follow the installation steps.
+ * Select the directory you want to install Qt, which is handy if you don't want to install system wide or don't have root access.
+ * Select the components you want to install. *Tools* will be selected by default. You also want to install the Qt 5.4 module along with the targets you are interested in (i.e. 32-Bit OpenGL for Windows, etc.). On Ubuntu, *Android armv7* will be selected by default as well. You may or may not want to install that, depending on your desire to target that platform. Same idea for OS X. It will have *iOS* Kits selected as well.
+ * Accept the license and the installer will download all the necessary modules and install where you told it to install.
+* Go to the Qt Creator directory:
+ * `~/local/Qt/Tools/QtCreator/bin` for Ubuntu (if that's where you installed it)
+ * `~/local/Qt/Qt Creator.app` for OS X (if that's where you installed it)
+ * `C:/local/Qt/Tools/QtCreator/bin` for Windows (if that's where you installed it)
+* Launch Qt Creator and open the `qgroundcontrol.pro` project.
+
+When you open a project in Qt Creator for the first time, it will ask what targets (*Kits*) you want to target. The options will depend on what modules you downloaded above. For instance, on Mac OS X you would select *Desktop Qt 5.4.1 clang 64bit*.
+It's also a good idea to go into *Projects/Build Steps* (side tool bar) and select Make's *Details*. For *Make Arguments*, add `-jx` (`/J x` on Windows) where `x` is at least the numbers of cores you have. That is, if you are running on a Mac Pro with 24 cores, you would use `-j24`. That will run 24 concurrent compiler instances at a time and run the build a whole lot faster. Your mileage may vary depending on your disk IO throughput. Note that for Windows, this method will build QGC x many times faster than when using Visual Studio as described above. Visual Studio allocates one process per *Project*. As QGroundControl is one very large project, it will still compile one file at a time within that one process. When you build from within Qt Creator (and give the ```/J x``` option to make), it will use x number of concurrent compiler processes.
+
+Qt Creator is a full-blown development IDE. You can even debug right from within it and it provides the full Qt API documentation. Just place the mouse cursor over a Qt class/element and hit the F1 key.
### Additional build notes for all supported OS
@@ -114,7 +140,6 @@ Download Qt 5.4 from here: ). Since logging is on by default, an example qtlogging.ini file is included at the root of the repository which disables logging. Follow the instructions from Qt as to why and where to put this file. You can then edit the file to get a logging level that suits your needs.
## Additional functionality
diff --git a/android/AndroidManifest.xml b/android/AndroidManifest.xml
new file mode 100644
index 0000000000000000000000000000000000000000..21fcc18846fe7a5d125916d7b18a4e8044627469
--- /dev/null
+++ b/android/AndroidManifest.xml
@@ -0,0 +1,67 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/files/images/icons/v2/t256.png b/android/res/drawable-ldpi/icon.png
similarity index 100%
rename from files/images/icons/v2/t256.png
rename to android/res/drawable-ldpi/icon.png
diff --git a/android/res/xml/device_filter.xml b/android/res/xml/device_filter.xml
new file mode 100644
index 0000000000000000000000000000000000000000..a149a80b508d8f8978a9fdd66bfedd4b78ca4046
--- /dev/null
+++ b/android/res/xml/device_filter.xml
@@ -0,0 +1,40 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/android/src/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java
new file mode 100644
index 0000000000000000000000000000000000000000..3dec53a9a78daf83393b11a77147bcc3a21abe86
--- /dev/null
+++ b/android/src/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java
@@ -0,0 +1,252 @@
+package com.hoho.android.usbserial.driver;
+
+import android.hardware.usb.UsbConstants;
+import android.hardware.usb.UsbDevice;
+import android.hardware.usb.UsbDeviceConnection;
+import android.hardware.usb.UsbEndpoint;
+import android.hardware.usb.UsbInterface;
+import android.util.Log;
+
+import java.io.IOException;
+import java.util.LinkedHashMap;
+import java.util.Map;
+
+/**
+ * USB CDC/ACM serial driver implementation.
+ *
+ * @author mike wakerly (opensource@hoho.com)
+ * @see Universal
+ * Serial Bus Class Definitions for Communication Devices, v1.1
+ */
+public class CdcAcmSerialDriver extends CommonUsbSerialDriver {
+
+ private final String TAG = CdcAcmSerialDriver.class.getSimpleName();
+
+ private UsbInterface mControlInterface;
+ private UsbInterface mDataInterface;
+
+ private UsbEndpoint mControlEndpoint;
+ private UsbEndpoint mReadEndpoint;
+ private UsbEndpoint mWriteEndpoint;
+
+ private boolean mRts = false;
+ private boolean mDtr = false;
+
+ private static final int USB_RECIP_INTERFACE = 0x01;
+ private static final int USB_RT_ACM = UsbConstants.USB_TYPE_CLASS | USB_RECIP_INTERFACE;
+
+ private static final int SET_LINE_CODING = 0x20; // USB CDC 1.1 section 6.2
+ private static final int GET_LINE_CODING = 0x21;
+ private static final int SET_CONTROL_LINE_STATE = 0x22;
+ private static final int SEND_BREAK = 0x23;
+
+ public CdcAcmSerialDriver(UsbDevice device, UsbDeviceConnection connection) {
+ super(device, connection);
+ }
+
+ @Override
+ public void open() throws IOException {
+ Log.d(TAG, "claiming interfaces, count=" + mDevice.getInterfaceCount());
+
+ Log.d(TAG, "Claiming control interface.");
+ mControlInterface = mDevice.getInterface(0);
+ Log.d(TAG, "Control iface=" + mControlInterface);
+ // class should be USB_CLASS_COMM
+
+ if (!mConnection.claimInterface(mControlInterface, true)) {
+ throw new IOException("Could not claim control interface.");
+ }
+ mControlEndpoint = mControlInterface.getEndpoint(0);
+ Log.d(TAG, "Control endpoint direction: " + mControlEndpoint.getDirection());
+
+ Log.d(TAG, "Claiming data interface.");
+ mDataInterface = mDevice.getInterface(1);
+ Log.d(TAG, "data iface=" + mDataInterface);
+ // class should be USB_CLASS_CDC_DATA
+
+ if (!mConnection.claimInterface(mDataInterface, true)) {
+ throw new IOException("Could not claim data interface.");
+ }
+ mReadEndpoint = mDataInterface.getEndpoint(1);
+ Log.d(TAG, "Read endpoint direction: " + mReadEndpoint.getDirection());
+ mWriteEndpoint = mDataInterface.getEndpoint(0);
+ Log.d(TAG, "Write endpoint direction: " + mWriteEndpoint.getDirection());
+ }
+
+ private int sendAcmControlMessage(int request, int value, byte[] buf) {
+ return mConnection.controlTransfer(
+ USB_RT_ACM, request, value, 0, buf, buf != null ? buf.length : 0, 5000);
+ }
+
+ @Override
+ public void close() throws IOException {
+ mConnection.close();
+ }
+
+ @Override
+ public int read(byte[] dest, int timeoutMillis) throws IOException {
+ final int numBytesRead;
+ synchronized (mReadBufferLock) {
+ int readAmt = Math.min(dest.length, mReadBuffer.length);
+ numBytesRead = mConnection.bulkTransfer(mReadEndpoint, mReadBuffer, readAmt,
+ timeoutMillis);
+ if (numBytesRead < 0) {
+ // This sucks: we get -1 on timeout, not 0 as preferred.
+ // We *should* use UsbRequest, except it has a bug/api oversight
+ // where there is no way to determine the number of bytes read
+ // in response :\ -- http://b.android.com/28023
+ return 0;
+ }
+ System.arraycopy(mReadBuffer, 0, dest, 0, numBytesRead);
+ }
+ return numBytesRead;
+ }
+
+ @Override
+ public int write(byte[] src, int timeoutMillis) throws IOException {
+ // TODO(mikey): Nearly identical to FtdiSerial write. Refactor.
+ int offset = 0;
+
+ while (offset < src.length) {
+ final int writeLength;
+ final int amtWritten;
+
+ synchronized (mWriteBufferLock) {
+ final byte[] writeBuffer;
+
+ writeLength = Math.min(src.length - offset, mWriteBuffer.length);
+ if (offset == 0) {
+ writeBuffer = src;
+ } else {
+ // bulkTransfer does not support offsets, make a copy.
+ System.arraycopy(src, offset, mWriteBuffer, 0, writeLength);
+ writeBuffer = mWriteBuffer;
+ }
+
+ amtWritten = mConnection.bulkTransfer(mWriteEndpoint, writeBuffer, writeLength,
+ timeoutMillis);
+ }
+ if (amtWritten <= 0) {
+ throw new IOException("Error writing " + writeLength
+ + " bytes at offset " + offset + " length=" + src.length);
+ }
+
+ //Log.d(TAG, "Wrote amt=" + amtWritten + " attempted=" + writeLength);
+ offset += amtWritten;
+ }
+ return offset;
+ }
+
+ @Override
+ public void setParameters(int baudRate, int dataBits, int stopBits, int parity) {
+ byte stopBitsByte;
+ switch (stopBits) {
+ case STOPBITS_1: stopBitsByte = 0; break;
+ case STOPBITS_1_5: stopBitsByte = 1; break;
+ case STOPBITS_2: stopBitsByte = 2; break;
+ default: throw new IllegalArgumentException("Bad value for stopBits: " + stopBits);
+ }
+
+ byte parityBitesByte;
+ switch (parity) {
+ case PARITY_NONE: parityBitesByte = 0; break;
+ case PARITY_ODD: parityBitesByte = 1; break;
+ case PARITY_EVEN: parityBitesByte = 2; break;
+ case PARITY_MARK: parityBitesByte = 3; break;
+ case PARITY_SPACE: parityBitesByte = 4; break;
+ default: throw new IllegalArgumentException("Bad value for parity: " + parity);
+ }
+
+ byte[] msg = {
+ (byte) ( baudRate & 0xff),
+ (byte) ((baudRate >> 8 ) & 0xff),
+ (byte) ((baudRate >> 16) & 0xff),
+ (byte) ((baudRate >> 24) & 0xff),
+ stopBitsByte,
+ parityBitesByte,
+ (byte) dataBits};
+ sendAcmControlMessage(SET_LINE_CODING, 0, msg);
+ }
+
+ @Override
+ public boolean getCD() throws IOException {
+ return false; // TODO
+ }
+
+ @Override
+ public boolean getCTS() throws IOException {
+ return false; // TODO
+ }
+
+ @Override
+ public boolean getDSR() throws IOException {
+ return false; // TODO
+ }
+
+ @Override
+ public boolean getDTR() throws IOException {
+ return mDtr;
+ }
+
+ @Override
+ public void setDTR(boolean value) throws IOException {
+ mDtr = value;
+ setDtrRts();
+ }
+
+ @Override
+ public boolean getRI() throws IOException {
+ return false; // TODO
+ }
+
+ @Override
+ public boolean getRTS() throws IOException {
+ return mRts;
+ }
+
+ @Override
+ public void setRTS(boolean value) throws IOException {
+ mRts = value;
+ setDtrRts();
+ }
+
+ private void setDtrRts() {
+ int value = (mRts ? 0x2 : 0) | (mDtr ? 0x1 : 0);
+ sendAcmControlMessage(SET_CONTROL_LINE_STATE, value, null);
+ }
+
+ public static Map getSupportedDevices() {
+ final Map supportedDevices = new LinkedHashMap();
+ supportedDevices.put(Integer.valueOf(UsbId.VENDOR_ARDUINO),
+ new int[] {
+ UsbId.ARDUINO_UNO,
+ UsbId.ARDUINO_UNO_R3,
+ UsbId.ARDUINO_MEGA_2560,
+ UsbId.ARDUINO_MEGA_2560_R3,
+ UsbId.ARDUINO_SERIAL_ADAPTER,
+ UsbId.ARDUINO_SERIAL_ADAPTER_R3,
+ UsbId.ARDUINO_MEGA_ADK,
+ UsbId.ARDUINO_MEGA_ADK_R3,
+ UsbId.ARDUINO_LEONARDO,
+ });
+ supportedDevices.put(Integer.valueOf(UsbId.VENDOR_VAN_OOIJEN_TECH),
+ new int[] {
+ UsbId.VAN_OOIJEN_TECH_TEENSYDUINO_SERIAL,
+ });
+ supportedDevices.put(Integer.valueOf(UsbId.VENDOR_ATMEL),
+ new int[] {
+ UsbId.ATMEL_LUFA_CDC_DEMO_APP,
+ });
+ supportedDevices.put(Integer.valueOf(UsbId.VENDOR_LEAFLABS),
+ new int[] {
+ UsbId.LEAFLABS_MAPLE,
+ });
+ supportedDevices.put(Integer.valueOf(UsbId.VENDOR_PX4),
+ new int[] {
+ UsbId.DEVICE_PX4FMU,
+ });
+ return supportedDevices;
+ }
+
+}
diff --git a/android/src/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java
new file mode 100644
index 0000000000000000000000000000000000000000..734933a22238264aa766ab39ec4365b3b4b0f50e
--- /dev/null
+++ b/android/src/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java
@@ -0,0 +1,156 @@
+/* Copyright 2013 Google Inc.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301,
+ * USA.
+ *
+ * Project home page: http://code.google.com/p/usb-serial-for-android/
+ */
+
+package com.hoho.android.usbserial.driver;
+
+import android.hardware.usb.UsbDevice;
+import android.hardware.usb.UsbDeviceConnection;
+
+import java.io.IOException;
+
+/**
+ * A base class shared by several driver implementations.
+ *
+ * @author mike wakerly (opensource@hoho.com)
+ */
+abstract class CommonUsbSerialDriver implements UsbSerialDriver {
+
+ public static final int DEFAULT_READ_BUFFER_SIZE = 16 * 1024;
+ public static final int DEFAULT_WRITE_BUFFER_SIZE = 16 * 1024;
+
+ protected final UsbDevice mDevice;
+ protected final UsbDeviceConnection mConnection;
+
+ protected final Object mReadBufferLock = new Object();
+ protected final Object mWriteBufferLock = new Object();
+
+ /** Internal read buffer. Guarded by {@link #mReadBufferLock}. */
+ protected byte[] mReadBuffer;
+
+ /** Internal write buffer. Guarded by {@link #mWriteBufferLock}. */
+ protected byte[] mWriteBuffer;
+
+ public CommonUsbSerialDriver(UsbDevice device, UsbDeviceConnection connection) {
+ mDevice = device;
+ mConnection = connection;
+
+ mReadBuffer = new byte[DEFAULT_READ_BUFFER_SIZE];
+ mWriteBuffer = new byte[DEFAULT_WRITE_BUFFER_SIZE];
+ }
+
+ /**
+ * Returns the currently-bound USB device.
+ *
+ * @return the device
+ */
+ @Override
+ public final UsbDevice getDevice() {
+ return mDevice;
+ }
+
+ /**
+ * Returns the currently-bound USB device connection.
+ *
+ * @return the device connection
+ */
+ @Override
+ public final UsbDeviceConnection getDeviceConnection() {
+ return mConnection;
+ }
+
+
+
+ /**
+ * Sets the size of the internal buffer used to exchange data with the USB
+ * stack for read operations. Most users should not need to change this.
+ *
+ * @param bufferSize the size in bytes
+ */
+ public final void setReadBufferSize(int bufferSize) {
+ synchronized (mReadBufferLock) {
+ if (bufferSize == mReadBuffer.length) {
+ return;
+ }
+ mReadBuffer = new byte[bufferSize];
+ }
+ }
+
+ /**
+ * Sets the size of the internal buffer used to exchange data with the USB
+ * stack for write operations. Most users should not need to change this.
+ *
+ * @param bufferSize the size in bytes
+ */
+ public final void setWriteBufferSize(int bufferSize) {
+ synchronized (mWriteBufferLock) {
+ if (bufferSize == mWriteBuffer.length) {
+ return;
+ }
+ mWriteBuffer = new byte[bufferSize];
+ }
+ }
+
+ @Override
+ public abstract void open() throws IOException;
+
+ @Override
+ public abstract void close() throws IOException;
+
+ @Override
+ public abstract int read(final byte[] dest, final int timeoutMillis) throws IOException;
+
+ @Override
+ public abstract int write(final byte[] src, final int timeoutMillis) throws IOException;
+
+ @Override
+ public abstract void setParameters(
+ int baudRate, int dataBits, int stopBits, int parity) throws IOException;
+
+ @Override
+ public abstract boolean getCD() throws IOException;
+
+ @Override
+ public abstract boolean getCTS() throws IOException;
+
+ @Override
+ public abstract boolean getDSR() throws IOException;
+
+ @Override
+ public abstract boolean getDTR() throws IOException;
+
+ @Override
+ public abstract void setDTR(boolean value) throws IOException;
+
+ @Override
+ public abstract boolean getRI() throws IOException;
+
+ @Override
+ public abstract boolean getRTS() throws IOException;
+
+ @Override
+ public abstract void setRTS(boolean value) throws IOException;
+
+ @Override
+ public boolean purgeHwBuffers(boolean flushReadBuffers, boolean flushWriteBuffers) throws IOException {
+ return !flushReadBuffers && !flushWriteBuffers;
+ }
+
+}
+
diff --git a/android/src/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java b/android/src/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java
new file mode 100644
index 0000000000000000000000000000000000000000..aa151ba1a0e6887ea4b7985a43044dd4eb6fcbd2
--- /dev/null
+++ b/android/src/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java
@@ -0,0 +1,292 @@
+package com.hoho.android.usbserial.driver;
+
+import android.hardware.usb.UsbConstants;
+import android.hardware.usb.UsbDevice;
+import android.hardware.usb.UsbDeviceConnection;
+import android.hardware.usb.UsbEndpoint;
+import android.hardware.usb.UsbInterface;
+import android.util.Log;
+
+import java.io.IOException;
+import java.util.LinkedHashMap;
+import java.util.Map;
+
+public class Cp2102SerialDriver extends CommonUsbSerialDriver {
+
+ private static final String TAG = Cp2102SerialDriver.class.getSimpleName();
+
+ private static final int DEFAULT_BAUD_RATE = 9600;
+
+ private static final int USB_WRITE_TIMEOUT_MILLIS = 5000;
+
+ /*
+ * Configuration Request Types
+ */
+ private static final int REQTYPE_HOST_TO_DEVICE = 0x41;
+
+ /*
+ * Configuration Request Codes
+ */
+ private static final int SILABSER_IFC_ENABLE_REQUEST_CODE = 0x00;
+ private static final int SILABSER_SET_BAUDDIV_REQUEST_CODE = 0x01;
+ private static final int SILABSER_SET_LINE_CTL_REQUEST_CODE = 0x03;
+ private static final int SILABSER_SET_MHS_REQUEST_CODE = 0x07;
+ private static final int SILABSER_SET_BAUDRATE = 0x1E;
+ private static final int SILABSER_FLUSH_REQUEST_CODE = 0x12;
+
+ private static final int FLUSH_READ_CODE = 0x0a;
+ private static final int FLUSH_WRITE_CODE = 0x05;
+
+ /*
+ * SILABSER_IFC_ENABLE_REQUEST_CODE
+ */
+ private static final int UART_ENABLE = 0x0001;
+ private static final int UART_DISABLE = 0x0000;
+
+ /*
+ * SILABSER_SET_BAUDDIV_REQUEST_CODE
+ */
+ private static final int BAUD_RATE_GEN_FREQ = 0x384000;
+
+ /*
+ * SILABSER_SET_MHS_REQUEST_CODE
+ */
+ private static final int MCR_DTR = 0x0001;
+ private static final int MCR_RTS = 0x0002;
+ private static final int MCR_ALL = 0x0003;
+
+ private static final int CONTROL_WRITE_DTR = 0x0100;
+ private static final int CONTROL_WRITE_RTS = 0x0200;
+
+ private UsbEndpoint mReadEndpoint;
+ private UsbEndpoint mWriteEndpoint;
+
+ public Cp2102SerialDriver(UsbDevice device, UsbDeviceConnection connection) {
+ super(device, connection);
+ }
+
+ private int setConfigSingle(int request, int value) {
+ return mConnection.controlTransfer(REQTYPE_HOST_TO_DEVICE, request, value,
+ 0, null, 0, USB_WRITE_TIMEOUT_MILLIS);
+ }
+
+ @Override
+ public void open() throws IOException {
+ boolean opened = false;
+ try {
+ for (int i = 0; i < mDevice.getInterfaceCount(); i++) {
+ UsbInterface usbIface = mDevice.getInterface(i);
+ if (mConnection.claimInterface(usbIface, true)) {
+ Log.d(TAG, "claimInterface " + i + " SUCCESS");
+ } else {
+ Log.d(TAG, "claimInterface " + i + " FAIL");
+ }
+ }
+
+ UsbInterface dataIface = mDevice.getInterface(mDevice.getInterfaceCount() - 1);
+ for (int i = 0; i < dataIface.getEndpointCount(); i++) {
+ UsbEndpoint ep = dataIface.getEndpoint(i);
+ if (ep.getType() == UsbConstants.USB_ENDPOINT_XFER_BULK) {
+ if (ep.getDirection() == UsbConstants.USB_DIR_IN) {
+ mReadEndpoint = ep;
+ } else {
+ mWriteEndpoint = ep;
+ }
+ }
+ }
+
+ setConfigSingle(SILABSER_IFC_ENABLE_REQUEST_CODE, UART_ENABLE);
+ setConfigSingle(SILABSER_SET_MHS_REQUEST_CODE, MCR_ALL | CONTROL_WRITE_DTR | CONTROL_WRITE_RTS);
+ setConfigSingle(SILABSER_SET_BAUDDIV_REQUEST_CODE, BAUD_RATE_GEN_FREQ / DEFAULT_BAUD_RATE);
+// setParameters(DEFAULT_BAUD_RATE, DEFAULT_DATA_BITS, DEFAULT_STOP_BITS, DEFAULT_PARITY);
+ opened = true;
+ } finally {
+ if (!opened) {
+ close();
+ }
+ }
+ }
+
+ @Override
+ public void close() throws IOException {
+ setConfigSingle(SILABSER_IFC_ENABLE_REQUEST_CODE, UART_DISABLE);
+ mConnection.close();
+ }
+
+ @Override
+ public int read(byte[] dest, int timeoutMillis) throws IOException {
+ final int numBytesRead;
+ synchronized (mReadBufferLock) {
+ int readAmt = Math.min(dest.length, mReadBuffer.length);
+ numBytesRead = mConnection.bulkTransfer(mReadEndpoint, mReadBuffer, readAmt,
+ timeoutMillis);
+ if (numBytesRead < 0) {
+ // This sucks: we get -1 on timeout, not 0 as preferred.
+ // We *should* use UsbRequest, except it has a bug/api oversight
+ // where there is no way to determine the number of bytes read
+ // in response :\ -- http://b.android.com/28023
+ return 0;
+ }
+ System.arraycopy(mReadBuffer, 0, dest, 0, numBytesRead);
+ }
+ return numBytesRead;
+ }
+
+ @Override
+ public int write(byte[] src, int timeoutMillis) throws IOException {
+ int offset = 0;
+
+ while (offset < src.length) {
+ final int writeLength;
+ final int amtWritten;
+
+ synchronized (mWriteBufferLock) {
+ final byte[] writeBuffer;
+
+ writeLength = Math.min(src.length - offset, mWriteBuffer.length);
+ if (offset == 0) {
+ writeBuffer = src;
+ } else {
+ // bulkTransfer does not support offsets, make a copy.
+ System.arraycopy(src, offset, mWriteBuffer, 0, writeLength);
+ writeBuffer = mWriteBuffer;
+ }
+
+ amtWritten = mConnection.bulkTransfer(mWriteEndpoint, writeBuffer, writeLength,
+ timeoutMillis);
+ }
+ if (amtWritten <= 0) {
+ throw new IOException("Error writing " + writeLength
+ + " bytes at offset " + offset + " length=" + src.length);
+ }
+
+ //Log.d(TAG, "Wrote amt=" + amtWritten + " attempted=" + writeLength);
+ offset += amtWritten;
+ }
+ return offset;
+ }
+
+ private void setBaudRate(int baudRate) throws IOException {
+ byte[] data = new byte[] {
+ (byte) ( baudRate & 0xff),
+ (byte) ((baudRate >> 8 ) & 0xff),
+ (byte) ((baudRate >> 16) & 0xff),
+ (byte) ((baudRate >> 24) & 0xff)
+ };
+ int ret = mConnection.controlTransfer(REQTYPE_HOST_TO_DEVICE, SILABSER_SET_BAUDRATE,
+ 0, 0, data, 4, USB_WRITE_TIMEOUT_MILLIS);
+ if (ret < 0) {
+ throw new IOException("Error setting baud rate.");
+ }
+ }
+
+ @Override
+ public void setParameters(int baudRate, int dataBits, int stopBits, int parity)
+ throws IOException {
+ setBaudRate(baudRate);
+
+ int configDataBits = 0;
+ switch (dataBits) {
+ case DATABITS_5:
+ configDataBits |= 0x0500;
+ break;
+ case DATABITS_6:
+ configDataBits |= 0x0600;
+ break;
+ case DATABITS_7:
+ configDataBits |= 0x0700;
+ break;
+ case DATABITS_8:
+ configDataBits |= 0x0800;
+ break;
+ default:
+ configDataBits |= 0x0800;
+ break;
+ }
+ setConfigSingle(SILABSER_SET_LINE_CTL_REQUEST_CODE, configDataBits);
+
+ int configParityBits = 0; // PARITY_NONE
+ switch (parity) {
+ case PARITY_ODD:
+ configParityBits |= 0x0010;
+ break;
+ case PARITY_EVEN:
+ configParityBits |= 0x0020;
+ break;
+ }
+ setConfigSingle(SILABSER_SET_LINE_CTL_REQUEST_CODE, configParityBits);
+
+ int configStopBits = 0;
+ switch (stopBits) {
+ case STOPBITS_1:
+ configStopBits |= 0;
+ break;
+ case STOPBITS_2:
+ configStopBits |= 2;
+ break;
+ }
+ setConfigSingle(SILABSER_SET_LINE_CTL_REQUEST_CODE, configStopBits);
+ }
+
+ @Override
+ public boolean getCD() throws IOException {
+ return false;
+ }
+
+ @Override
+ public boolean getCTS() throws IOException {
+ return false;
+ }
+
+ @Override
+ public boolean getDSR() throws IOException {
+ return false;
+ }
+
+ @Override
+ public boolean getDTR() throws IOException {
+ return true;
+ }
+
+ @Override
+ public void setDTR(boolean value) throws IOException {
+ }
+
+ @Override
+ public boolean getRI() throws IOException {
+ return false;
+ }
+
+ @Override
+ public boolean getRTS() throws IOException {
+ return true;
+ }
+
+ @Override
+ public boolean purgeHwBuffers(boolean purgeReadBuffers,
+ boolean purgeWriteBuffers) throws IOException {
+ int value = (purgeReadBuffers ? FLUSH_READ_CODE : 0)
+ | (purgeWriteBuffers ? FLUSH_WRITE_CODE : 0);
+
+ if (value != 0) {
+ setConfigSingle(SILABSER_FLUSH_REQUEST_CODE, value);
+ }
+
+ return true;
+ }
+
+ @Override
+ public void setRTS(boolean value) throws IOException {
+ }
+
+ public static Map getSupportedDevices() {
+ final Map supportedDevices = new LinkedHashMap();
+ supportedDevices.put(Integer.valueOf(UsbId.VENDOR_SILAB),
+ new int[] {
+ UsbId.SILAB_CP2102
+ });
+ return supportedDevices;
+ }
+
+
+}
diff --git a/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java
new file mode 100644
index 0000000000000000000000000000000000000000..ad3627ff38a75a50b71167ddf50f50b4ee5b1b51
--- /dev/null
+++ b/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java
@@ -0,0 +1,552 @@
+/* Copyright 2011 Google Inc.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301,
+ * USA.
+ *
+ * Project home page: http://code.google.com/p/usb-serial-for-android/
+ */
+
+package com.hoho.android.usbserial.driver;
+
+import android.hardware.usb.UsbConstants;
+import android.hardware.usb.UsbDevice;
+import android.hardware.usb.UsbDeviceConnection;
+import android.hardware.usb.UsbEndpoint;
+import android.hardware.usb.UsbRequest;
+import android.util.Log;
+
+
+import java.io.IOException;
+import java.nio.ByteBuffer;
+import java.util.LinkedHashMap;
+import java.util.Map;
+
+/**
+ * A {@link CommonUsbSerialDriver} implementation for a variety of FTDI devices
+ *
+ * This driver is based on
+ * libftdi, and is
+ * copyright and subject to the following terms:
+ *
+ *
+ * Copyright (C) 2003 by Intra2net AG
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License
+ * version 2.1 as published by the Free Software Foundation;
+ *
+ * opensource@intra2net.com
+ * http://www.intra2net.com/en/developer/libftdi
+ *
+ *
+ *
+ *
+ * Some FTDI devices have not been tested; see later listing of supported and
+ * unsupported devices. Devices listed as "supported" support the following
+ * features:
+ *
+ *
Read and write of serial data (see {@link #read(byte[], int)} and
+ * {@link #write(byte[], int)}.
+ *
Setting baud rate (see {@link #setBaudRate(int)}).
+ *
+ *
+ *
+ * Supported and tested devices:
+ *
+ *
{@value DeviceType#TYPE_R}
+ *
+ *
+ *
+ * Unsupported but possibly working devices (please contact the author with
+ * feedback or patches):
+ *
+ *
{@value DeviceType#TYPE_2232C}
+ *
{@value DeviceType#TYPE_2232H}
+ *
{@value DeviceType#TYPE_4232H}
+ *
{@value DeviceType#TYPE_AM}
+ *
{@value DeviceType#TYPE_BM}
+ *
+ *
+ *
+ * @author mike wakerly (opensource@hoho.com)
+ * @see USB Serial
+ * for Android project page
+ * @see FTDI Homepage
+ * @see libftdi
+ */
+public class FtdiSerialDriver extends CommonUsbSerialDriver {
+
+ public static final int USB_TYPE_STANDARD = 0x00 << 5;
+ public static final int USB_TYPE_CLASS = 0x00 << 5;
+ public static final int USB_TYPE_VENDOR = 0x00 << 5;
+ public static final int USB_TYPE_RESERVED = 0x00 << 5;
+
+ public static final int USB_RECIP_DEVICE = 0x00;
+ public static final int USB_RECIP_INTERFACE = 0x01;
+ public static final int USB_RECIP_ENDPOINT = 0x02;
+ public static final int USB_RECIP_OTHER = 0x03;
+
+ public static final int USB_ENDPOINT_IN = 0x80;
+ public static final int USB_ENDPOINT_OUT = 0x00;
+
+ public static final int USB_WRITE_TIMEOUT_MILLIS = 5000;
+ public static final int USB_READ_TIMEOUT_MILLIS = 5000;
+
+ // From ftdi.h
+ /**
+ * Reset the port.
+ */
+ private static final int SIO_RESET_REQUEST = 0;
+
+ /**
+ * Set the modem control register.
+ */
+ private static final int SIO_MODEM_CTRL_REQUEST = 1;
+
+ /**
+ * Set flow control register.
+ */
+ private static final int SIO_SET_FLOW_CTRL_REQUEST = 2;
+
+ /**
+ * Set baud rate.
+ */
+ private static final int SIO_SET_BAUD_RATE_REQUEST = 3;
+
+ /**
+ * Set the data characteristics of the port.
+ */
+ private static final int SIO_SET_DATA_REQUEST = 4;
+
+ private static final int SIO_RESET_SIO = 0;
+ private static final int SIO_RESET_PURGE_RX = 1;
+ private static final int SIO_RESET_PURGE_TX = 2;
+
+ public static final int FTDI_DEVICE_OUT_REQTYPE =
+ UsbConstants.USB_TYPE_VENDOR | USB_RECIP_DEVICE | USB_ENDPOINT_OUT;
+
+ public static final int FTDI_DEVICE_IN_REQTYPE =
+ UsbConstants.USB_TYPE_VENDOR | USB_RECIP_DEVICE | USB_ENDPOINT_IN;
+
+ /**
+ * Length of the modem status header, transmitted with every read.
+ */
+ private static final int MODEM_STATUS_HEADER_LENGTH = 2;
+
+ private final String TAG = FtdiSerialDriver.class.getSimpleName();
+
+ private DeviceType mType;
+
+ /**
+ * FTDI chip types.
+ */
+ private static enum DeviceType {
+ TYPE_BM, TYPE_AM, TYPE_2232C, TYPE_R, TYPE_2232H, TYPE_4232H;
+ }
+
+ private int mInterface = 0; /* INTERFACE_ANY */
+
+ private int mMaxPacketSize = 64; // TODO(mikey): detect
+
+ /**
+ * Due to http://b.android.com/28023 , we cannot use UsbRequest async reads
+ * since it gives no indication of number of bytes read. Set this to
+ * {@code true} on platforms where it is fixed.
+ */
+ private static final boolean ENABLE_ASYNC_READS = false;
+
+ /**
+ * Filter FTDI status bytes from buffer
+ * @param src The source buffer (which contains status bytes)
+ * @param dest The destination buffer to write the status bytes into (can be src)
+ * @param totalBytesRead Number of bytes read to src
+ * @param maxPacketSize The USB endpoint max packet size
+ * @return The number of payload bytes
+ */
+ private final int filterStatusBytes(byte[] src, byte[] dest, int totalBytesRead, int maxPacketSize) {
+ final int packetsCount = totalBytesRead / maxPacketSize + 1;
+ for (int packetIdx = 0; packetIdx < packetsCount; ++packetIdx) {
+ final int count = (packetIdx == (packetsCount - 1))
+ ? (totalBytesRead % maxPacketSize) - MODEM_STATUS_HEADER_LENGTH
+ : maxPacketSize - MODEM_STATUS_HEADER_LENGTH;
+ if (count > 0) {
+ System.arraycopy(src,
+ packetIdx * maxPacketSize + MODEM_STATUS_HEADER_LENGTH,
+ dest,
+ packetIdx * (maxPacketSize - MODEM_STATUS_HEADER_LENGTH),
+ count);
+ }
+ }
+
+ return totalBytesRead - (packetsCount * 2);
+ }
+
+ /**
+ * Constructor.
+ *
+ * @param usbDevice the {@link UsbDevice} to use
+ * @param usbConnection the {@link UsbDeviceConnection} to use
+ * @throws UsbSerialRuntimeException if the given device is incompatible
+ * with this driver
+ */
+ public FtdiSerialDriver(UsbDevice usbDevice, UsbDeviceConnection usbConnection) {
+ super(usbDevice, usbConnection);
+ mType = null;
+ }
+
+ public void reset() throws IOException {
+ int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE, SIO_RESET_REQUEST,
+ SIO_RESET_SIO, 0 /* index */, null, 0, USB_WRITE_TIMEOUT_MILLIS);
+ if (result != 0) {
+ throw new IOException("Reset failed: result=" + result);
+ }
+
+ // TODO(mikey): autodetect.
+ mType = DeviceType.TYPE_R;
+ }
+
+ @Override
+ public void open() throws IOException {
+ boolean opened = false;
+ try {
+ for (int i = 0; i < mDevice.getInterfaceCount(); i++) {
+ if (mConnection.claimInterface(mDevice.getInterface(i), true)) {
+ Log.d(TAG, "claimInterface " + i + " SUCCESS");
+ } else {
+ throw new IOException("Error claiming interface " + i);
+ }
+ }
+ reset();
+ opened = true;
+ } finally {
+ if (!opened) {
+ close();
+ }
+ }
+ }
+
+ @Override
+ public void close() {
+ mConnection.close();
+ }
+
+ @Override
+ public int read(byte[] dest, int timeoutMillis) throws IOException {
+ final UsbEndpoint endpoint = mDevice.getInterface(0).getEndpoint(0);
+
+ if (ENABLE_ASYNC_READS) {
+ final int readAmt;
+ synchronized (mReadBufferLock) {
+ // mReadBuffer is only used for maximum read size.
+ readAmt = Math.min(dest.length, mReadBuffer.length);
+ }
+
+ final UsbRequest request = new UsbRequest();
+ request.initialize(mConnection, endpoint);
+
+ final ByteBuffer buf = ByteBuffer.wrap(dest);
+ if (!request.queue(buf, readAmt)) {
+ throw new IOException("Error queueing request.");
+ }
+
+ final UsbRequest response = mConnection.requestWait();
+ if (response == null) {
+ throw new IOException("Null response");
+ }
+
+ final int payloadBytesRead = buf.position() - MODEM_STATUS_HEADER_LENGTH;
+ if (payloadBytesRead > 0) {
+ return payloadBytesRead;
+ } else {
+ return 0;
+ }
+ } else {
+ final int totalBytesRead;
+
+ synchronized (mReadBufferLock) {
+ final int readAmt = Math.min(dest.length, mReadBuffer.length);
+ totalBytesRead = mConnection.bulkTransfer(endpoint, mReadBuffer,
+ readAmt, timeoutMillis);
+
+ if (totalBytesRead < MODEM_STATUS_HEADER_LENGTH) {
+ throw new IOException("Expected at least " + MODEM_STATUS_HEADER_LENGTH + " bytes");
+ }
+
+ return filterStatusBytes(mReadBuffer, dest, totalBytesRead, endpoint.getMaxPacketSize());
+ }
+ }
+ }
+
+ @Override
+ public int write(byte[] src, int timeoutMillis) throws IOException {
+ final UsbEndpoint endpoint = mDevice.getInterface(0).getEndpoint(1);
+ int offset = 0;
+
+ while (offset < src.length) {
+ final int writeLength;
+ final int amtWritten;
+
+ synchronized (mWriteBufferLock) {
+ final byte[] writeBuffer;
+
+ writeLength = Math.min(src.length - offset, mWriteBuffer.length);
+ if (offset == 0) {
+ writeBuffer = src;
+ } else {
+ // bulkTransfer does not support offsets, make a copy.
+ System.arraycopy(src, offset, mWriteBuffer, 0, writeLength);
+ writeBuffer = mWriteBuffer;
+ }
+
+ amtWritten = mConnection.bulkTransfer(endpoint, writeBuffer, writeLength,
+ timeoutMillis);
+ }
+
+ if (amtWritten <= 0) {
+ throw new IOException("Error writing " + writeLength
+ + " bytes at offset " + offset + " length=" + src.length);
+ }
+
+ //Log.d(TAG, "Wrote amtWritten=" + amtWritten + " attempted=" + writeLength);
+ offset += amtWritten;
+ }
+ return offset;
+ }
+
+ private int setBaudRate(int baudRate) throws IOException {
+ long[] vals = convertBaudrate(baudRate);
+ long actualBaudrate = vals[0];
+ long index = vals[1];
+ long value = vals[2];
+ int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE,
+ SIO_SET_BAUD_RATE_REQUEST, (int) value, (int) index,
+ null, 0, USB_WRITE_TIMEOUT_MILLIS);
+ if (result != 0) {
+ throw new IOException("Setting baudrate failed: result=" + result);
+ }
+ return (int) actualBaudrate;
+ }
+
+ @Override
+ public void setParameters(int baudRate, int dataBits, int stopBits, int parity)
+ throws IOException {
+ setBaudRate(baudRate);
+
+ int config = dataBits;
+
+ switch (parity) {
+ case PARITY_NONE:
+ config |= (0x00 << 8);
+ break;
+ case PARITY_ODD:
+ config |= (0x01 << 8);
+ break;
+ case PARITY_EVEN:
+ config |= (0x02 << 8);
+ break;
+ case PARITY_MARK:
+ config |= (0x03 << 8);
+ break;
+ case PARITY_SPACE:
+ config |= (0x04 << 8);
+ break;
+ default:
+ throw new IllegalArgumentException("Unknown parity value: " + parity);
+ }
+
+ switch (stopBits) {
+ case STOPBITS_1:
+ config |= (0x00 << 11);
+ break;
+ case STOPBITS_1_5:
+ config |= (0x01 << 11);
+ break;
+ case STOPBITS_2:
+ config |= (0x02 << 11);
+ break;
+ default:
+ throw new IllegalArgumentException("Unknown stopBits value: " + stopBits);
+ }
+
+ int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE,
+ SIO_SET_DATA_REQUEST, config, 0 /* index */,
+ null, 0, USB_WRITE_TIMEOUT_MILLIS);
+ if (result != 0) {
+ throw new IOException("Setting parameters failed: result=" + result);
+ }
+ }
+
+ private long[] convertBaudrate(int baudrate) {
+ // TODO(mikey): Braindead transcription of libfti method. Clean up,
+ // using more idiomatic Java where possible.
+ int divisor = 24000000 / baudrate;
+ int bestDivisor = 0;
+ int bestBaud = 0;
+ int bestBaudDiff = 0;
+ int fracCode[] = {
+ 0, 3, 2, 4, 1, 5, 6, 7
+ };
+
+ for (int i = 0; i < 2; i++) {
+ int tryDivisor = divisor + i;
+ int baudEstimate;
+ int baudDiff;
+
+ if (tryDivisor <= 8) {
+ // Round up to minimum supported divisor
+ tryDivisor = 8;
+ } else if (mType != DeviceType.TYPE_AM && tryDivisor < 12) {
+ // BM doesn't support divisors 9 through 11 inclusive
+ tryDivisor = 12;
+ } else if (divisor < 16) {
+ // AM doesn't support divisors 9 through 15 inclusive
+ tryDivisor = 16;
+ } else {
+ if (mType == DeviceType.TYPE_AM) {
+ // TODO
+ } else {
+ if (tryDivisor > 0x1FFFF) {
+ // Round down to maximum supported divisor value (for
+ // BM)
+ tryDivisor = 0x1FFFF;
+ }
+ }
+ }
+
+ // Get estimated baud rate (to nearest integer)
+ baudEstimate = (24000000 + (tryDivisor / 2)) / tryDivisor;
+
+ // Get absolute difference from requested baud rate
+ if (baudEstimate < baudrate) {
+ baudDiff = baudrate - baudEstimate;
+ } else {
+ baudDiff = baudEstimate - baudrate;
+ }
+
+ if (i == 0 || baudDiff < bestBaudDiff) {
+ // Closest to requested baud rate so far
+ bestDivisor = tryDivisor;
+ bestBaud = baudEstimate;
+ bestBaudDiff = baudDiff;
+ if (baudDiff == 0) {
+ // Spot on! No point trying
+ break;
+ }
+ }
+ }
+
+ // Encode the best divisor value
+ long encodedDivisor = (bestDivisor >> 3) | (fracCode[bestDivisor & 7] << 14);
+ // Deal with special cases for encoded value
+ if (encodedDivisor == 1) {
+ encodedDivisor = 0; // 3000000 baud
+ } else if (encodedDivisor == 0x4001) {
+ encodedDivisor = 1; // 2000000 baud (BM only)
+ }
+
+ // Split into "value" and "index" values
+ long value = encodedDivisor & 0xFFFF;
+ long index;
+ if (mType == DeviceType.TYPE_2232C || mType == DeviceType.TYPE_2232H
+ || mType == DeviceType.TYPE_4232H) {
+ index = (encodedDivisor >> 8) & 0xffff;
+ index &= 0xFF00;
+ index |= 0 /* TODO mIndex */;
+ } else {
+ index = (encodedDivisor >> 16) & 0xffff;
+ }
+
+ // Return the nearest baud rate
+ return new long[] {
+ bestBaud, index, value
+ };
+ }
+
+ @Override
+ public boolean getCD() throws IOException {
+ return false;
+ }
+
+ @Override
+ public boolean getCTS() throws IOException {
+ return false;
+ }
+
+ @Override
+ public boolean getDSR() throws IOException {
+ return false;
+ }
+
+ @Override
+ public boolean getDTR() throws IOException {
+ return false;
+ }
+
+ @Override
+ public void setDTR(boolean value) throws IOException {
+ }
+
+ @Override
+ public boolean getRI() throws IOException {
+ return false;
+ }
+
+ @Override
+ public boolean getRTS() throws IOException {
+ return false;
+ }
+
+ @Override
+ public void setRTS(boolean value) throws IOException {
+ }
+
+ @Override
+ public boolean purgeHwBuffers(boolean purgeReadBuffers, boolean purgeWriteBuffers) throws IOException {
+ if (purgeReadBuffers) {
+ int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE, SIO_RESET_REQUEST,
+ SIO_RESET_PURGE_RX, 0 /* index */, null, 0, USB_WRITE_TIMEOUT_MILLIS);
+ if (result != 0) {
+ throw new IOException("Flushing RX failed: result=" + result);
+ }
+ }
+
+ if (purgeWriteBuffers) {
+ int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE, SIO_RESET_REQUEST,
+ SIO_RESET_PURGE_TX, 0 /* index */, null, 0, USB_WRITE_TIMEOUT_MILLIS);
+ if (result != 0) {
+ throw new IOException("Flushing RX failed: result=" + result);
+ }
+ }
+
+ return true;
+ }
+
+ public static Map getSupportedDevices() {
+ final Map supportedDevices = new LinkedHashMap();
+ supportedDevices.put(Integer.valueOf(UsbId.VENDOR_FTDI),
+ new int[] {
+ UsbId.FTDI_FT232R,
+ UsbId.FTDI_FT231X,
+ });
+ /*
+ supportedDevices.put(Integer.valueOf(UsbId.VENDOR_PX4),
+ new int[] {
+ UsbId.DEVICE_PX4FMU
+ });
+ */
+ return supportedDevices;
+ }
+
+}
diff --git a/android/src/com/hoho/android/usbserial/driver/ProlificSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/ProlificSerialDriver.java
new file mode 100644
index 0000000000000000000000000000000000000000..d6e2d1338d1a1f08051b5f13d2303a526c7a3639
--- /dev/null
+++ b/android/src/com/hoho/android/usbserial/driver/ProlificSerialDriver.java
@@ -0,0 +1,523 @@
+/* This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301,
+ * USA.
+ *
+ * Project home page: http://code.google.com/p/usb-serial-for-android/
+ */
+
+/*
+ * Ported to usb-serial-for-android
+ * by Felix Hädicke
+ *
+ * Based on the pyprolific driver written
+ * by Emmanuel Blot
+ * See https://github.com/eblot/pyftdi
+ */
+
+package com.hoho.android.usbserial.driver;
+
+import android.hardware.usb.UsbConstants;
+import android.hardware.usb.UsbDevice;
+import android.hardware.usb.UsbDeviceConnection;
+import android.hardware.usb.UsbEndpoint;
+import android.hardware.usb.UsbInterface;
+import android.util.Log;
+
+import java.io.IOException;
+import java.lang.reflect.Method;
+import java.util.LinkedHashMap;
+import java.util.Map;
+
+public class ProlificSerialDriver extends CommonUsbSerialDriver {
+ private static final int USB_READ_TIMEOUT_MILLIS = 1000;
+ private static final int USB_WRITE_TIMEOUT_MILLIS = 5000;
+
+ private static final int USB_RECIP_INTERFACE = 0x01;
+
+ private static final int PROLIFIC_VENDOR_READ_REQUEST = 0x01;
+ private static final int PROLIFIC_VENDOR_WRITE_REQUEST = 0x01;
+
+ private static final int PROLIFIC_VENDOR_OUT_REQTYPE = UsbConstants.USB_DIR_OUT
+ | UsbConstants.USB_TYPE_VENDOR;
+
+ private static final int PROLIFIC_VENDOR_IN_REQTYPE = UsbConstants.USB_DIR_IN
+ | UsbConstants.USB_TYPE_VENDOR;
+
+ private static final int PROLIFIC_CTRL_OUT_REQTYPE = UsbConstants.USB_DIR_OUT
+ | UsbConstants.USB_TYPE_CLASS | USB_RECIP_INTERFACE;
+
+ private static final int WRITE_ENDPOINT = 0x02;
+ private static final int READ_ENDPOINT = 0x83;
+ private static final int INTERRUPT_ENDPOINT = 0x81;
+
+ private static final int FLUSH_RX_REQUEST = 0x08;
+ private static final int FLUSH_TX_REQUEST = 0x09;
+
+ private static final int SET_LINE_REQUEST = 0x20;
+ private static final int SET_CONTROL_REQUEST = 0x22;
+
+ private static final int CONTROL_DTR = 0x01;
+ private static final int CONTROL_RTS = 0x02;
+
+ private static final int STATUS_FLAG_CD = 0x01;
+ private static final int STATUS_FLAG_DSR = 0x02;
+ private static final int STATUS_FLAG_RI = 0x08;
+ private static final int STATUS_FLAG_CTS = 0x80;
+
+ private static final int STATUS_BUFFER_SIZE = 10;
+ private static final int STATUS_BYTE_IDX = 8;
+
+ private static final int DEVICE_TYPE_HX = 0;
+ private static final int DEVICE_TYPE_0 = 1;
+ private static final int DEVICE_TYPE_1 = 2;
+
+ private int mDeviceType = DEVICE_TYPE_HX;
+
+ private UsbEndpoint mReadEndpoint;
+ private UsbEndpoint mWriteEndpoint;
+ private UsbEndpoint mInterruptEndpoint;
+
+ private int mControlLinesValue = 0;
+
+ private int mBaudRate = -1, mDataBits = -1, mStopBits = -1, mParity = -1;
+
+ private int mStatus = 0;
+ private volatile Thread mReadStatusThread = null;
+ private final Object mReadStatusThreadLock = new Object();
+ boolean mStopReadStatusThread = false;
+ private IOException mReadStatusException = null;
+
+ private final String TAG = ProlificSerialDriver.class.getSimpleName();
+
+ private final byte[] inControlTransfer(int requestType, int request,
+ int value, int index, int length) throws IOException {
+ byte[] buffer = new byte[length];
+ int result = mConnection.controlTransfer(requestType, request, value,
+ index, buffer, length, USB_READ_TIMEOUT_MILLIS);
+ if (result != length) {
+ throw new IOException(
+ String.format("ControlTransfer with value 0x%x failed: %d",
+ value, result));
+ }
+ return buffer;
+ }
+
+ private final void outControlTransfer(int requestType, int request,
+ int value, int index, byte[] data) throws IOException {
+ int length = (data == null) ? 0 : data.length;
+ int result = mConnection.controlTransfer(requestType, request, value,
+ index, data, length, USB_WRITE_TIMEOUT_MILLIS);
+ if (result != length) {
+ throw new IOException(
+ String.format("ControlTransfer with value 0x%x failed: %d",
+ value, result));
+ }
+ }
+
+ private final byte[] vendorIn(int value, int index, int length)
+ throws IOException {
+ return inControlTransfer(PROLIFIC_VENDOR_IN_REQTYPE,
+ PROLIFIC_VENDOR_READ_REQUEST, value, index, length);
+ }
+
+ private final void vendorOut(int value, int index, byte[] data)
+ throws IOException {
+ outControlTransfer(PROLIFIC_VENDOR_OUT_REQTYPE,
+ PROLIFIC_VENDOR_WRITE_REQUEST, value, index, data);
+ }
+
+ private final void ctrlOut(int request, int value, int index, byte[] data)
+ throws IOException {
+ outControlTransfer(PROLIFIC_CTRL_OUT_REQTYPE, request, value, index,
+ data);
+ }
+
+ private void doBlackMagic() throws IOException {
+ vendorIn(0x8484, 0, 1);
+ vendorOut(0x0404, 0, null);
+ vendorIn(0x8484, 0, 1);
+ vendorIn(0x8383, 0, 1);
+ vendorIn(0x8484, 0, 1);
+ vendorOut(0x0404, 1, null);
+ vendorIn(0x8484, 0, 1);
+ vendorIn(0x8383, 0, 1);
+ vendorOut(0, 1, null);
+ vendorOut(1, 0, null);
+ vendorOut(2, (mDeviceType == DEVICE_TYPE_HX) ? 0x44 : 0x24, null);
+ }
+
+ private void resetDevice() throws IOException {
+ purgeHwBuffers(true, true);
+ }
+
+ private void setControlLines(int newControlLinesValue) throws IOException {
+ ctrlOut(SET_CONTROL_REQUEST, newControlLinesValue, 0, null);
+ mControlLinesValue = newControlLinesValue;
+ }
+
+ private final void readStatusThreadFunction() {
+ try {
+ while (!mStopReadStatusThread) {
+ byte[] buffer = new byte[STATUS_BUFFER_SIZE];
+ int readBytesCount = mConnection.bulkTransfer(mInterruptEndpoint,
+ buffer,
+ STATUS_BUFFER_SIZE,
+ 500);
+ if (readBytesCount > 0) {
+ if (readBytesCount == STATUS_BUFFER_SIZE) {
+ mStatus = buffer[STATUS_BYTE_IDX] & 0xff;
+ } else {
+ throw new IOException(
+ String.format("Invalid CTS / DSR / CD / RI status buffer received, expected %d bytes, but received %d",
+ STATUS_BUFFER_SIZE,
+ readBytesCount));
+ }
+ }
+ }
+ } catch (IOException e) {
+ mReadStatusException = e;
+ }
+ }
+
+ private final int getStatus() throws IOException {
+ if ((mReadStatusThread == null) && (mReadStatusException == null)) {
+ synchronized (mReadStatusThreadLock) {
+ if (mReadStatusThread == null) {
+ byte[] buffer = new byte[STATUS_BUFFER_SIZE];
+ int readBytes = mConnection.bulkTransfer(mInterruptEndpoint,
+ buffer,
+ STATUS_BUFFER_SIZE,
+ 100);
+ if (readBytes != STATUS_BUFFER_SIZE) {
+ Log.w(TAG, "Could not read initial CTS / DSR / CD / RI status");
+ } else {
+ mStatus = buffer[STATUS_BYTE_IDX] & 0xff;
+ }
+
+ mReadStatusThread = new Thread(new Runnable() {
+ @Override
+ public void run() {
+ readStatusThreadFunction();
+ }
+ });
+ mReadStatusThread.setDaemon(true);
+ mReadStatusThread.start();
+ }
+ }
+ }
+
+ /* throw and clear an exception which occured in the status read thread */
+ IOException readStatusException = mReadStatusException;
+ if (mReadStatusException != null) {
+ mReadStatusException = null;
+ throw readStatusException;
+ }
+
+ return mStatus;
+ }
+
+ private final boolean testStatusFlag(int flag) throws IOException {
+ return ((getStatus() & flag) == flag);
+ }
+
+ public ProlificSerialDriver(UsbDevice device, UsbDeviceConnection connection) {
+ super(device, connection);
+ }
+
+ @Override
+ public void open() throws IOException {
+ UsbInterface usbInterface = mDevice.getInterface(0);
+
+ if (!mConnection.claimInterface(usbInterface, true)) {
+ throw new IOException("Error claiming Prolific interface 0");
+ }
+
+ boolean openSuccessful = false;
+ try {
+ for (int i = 0; i < usbInterface.getEndpointCount(); ++i) {
+ UsbEndpoint currentEndpoint = usbInterface.getEndpoint(i);
+
+ switch (currentEndpoint.getAddress()) {
+ case READ_ENDPOINT:
+ mReadEndpoint = currentEndpoint;
+ break;
+
+ case WRITE_ENDPOINT:
+ mWriteEndpoint = currentEndpoint;
+ break;
+
+ case INTERRUPT_ENDPOINT:
+ mInterruptEndpoint = currentEndpoint;
+ break;
+ }
+ }
+
+ if (mDevice.getDeviceClass() == 0x02) {
+ mDeviceType = DEVICE_TYPE_0;
+ } else {
+ try {
+ Method getRawDescriptorsMethod
+ = mConnection.getClass().getMethod("getRawDescriptors");
+ byte[] rawDescriptors
+ = (byte[]) getRawDescriptorsMethod.invoke(mConnection);
+ byte maxPacketSize0 = rawDescriptors[7];
+ if (maxPacketSize0 == 64) {
+ mDeviceType = DEVICE_TYPE_HX;
+ } else if ((mDevice.getDeviceClass() == 0x00)
+ || (mDevice.getDeviceClass() == 0xff)) {
+ mDeviceType = DEVICE_TYPE_1;
+ } else {
+ Log.w(TAG, "Could not detect PL2303 subtype, "
+ + "Assuming that it is a HX device");
+ mDeviceType = DEVICE_TYPE_HX;
+ }
+ } catch (NoSuchMethodException e) {
+ Log.w(TAG, "Method UsbDeviceConnection.getRawDescriptors, "
+ + "required for PL2303 subtype detection, not "
+ + "available! Assuming that it is a HX device");
+ mDeviceType = DEVICE_TYPE_HX;
+ } catch (Exception e) {
+ Log.e(TAG, "An unexpected exception occured while trying "
+ + "to detect PL2303 subtype", e);
+ }
+ }
+
+ setControlLines(mControlLinesValue);
+ resetDevice();
+
+ doBlackMagic();
+ openSuccessful = true;
+ } finally {
+ if (!openSuccessful) {
+ try {
+ mConnection.releaseInterface(usbInterface);
+ } catch (Exception ingored) {
+ // Do not cover possible exceptions
+ }
+ }
+ }
+ }
+
+ @Override
+ public void close() throws IOException {
+ try {
+ mStopReadStatusThread = true;
+ synchronized (mReadStatusThreadLock) {
+ if (mReadStatusThread != null) {
+ try {
+ mReadStatusThread.join();
+ } catch (Exception e) {
+ Log.w(TAG, "An error occured while waiting for status read thread", e);
+ }
+ }
+ }
+
+ resetDevice();
+ } finally {
+ mConnection.releaseInterface(mDevice.getInterface(0));
+ }
+ }
+
+ @Override
+ public int read(byte[] dest, int timeoutMillis) throws IOException {
+ synchronized (mReadBufferLock) {
+ int readAmt = Math.min(dest.length, mReadBuffer.length);
+ int numBytesRead = mConnection.bulkTransfer(mReadEndpoint, mReadBuffer,
+ readAmt, timeoutMillis);
+ if (numBytesRead < 0) {
+ return 0;
+ }
+ System.arraycopy(mReadBuffer, 0, dest, 0, numBytesRead);
+ return numBytesRead;
+ }
+ }
+
+ @Override
+ public int write(byte[] src, int timeoutMillis) throws IOException {
+ int offset = 0;
+
+ while (offset < src.length) {
+ final int writeLength;
+ final int amtWritten;
+
+ synchronized (mWriteBufferLock) {
+ final byte[] writeBuffer;
+
+ writeLength = Math.min(src.length - offset, mWriteBuffer.length);
+ if (offset == 0) {
+ writeBuffer = src;
+ } else {
+ // bulkTransfer does not support offsets, make a copy.
+ System.arraycopy(src, offset, mWriteBuffer, 0, writeLength);
+ writeBuffer = mWriteBuffer;
+ }
+
+ amtWritten = mConnection.bulkTransfer(mWriteEndpoint,
+ writeBuffer, writeLength, timeoutMillis);
+ }
+
+ if (amtWritten <= 0) {
+ throw new IOException("Error writing " + writeLength
+ + " bytes at offset " + offset + " length="
+ + src.length);
+ }
+
+ offset += amtWritten;
+ }
+ return offset;
+ }
+
+ @Override
+ public void setParameters(int baudRate, int dataBits, int stopBits,
+ int parity) throws IOException {
+ if ((mBaudRate == baudRate) && (mDataBits == dataBits)
+ && (mStopBits == stopBits) && (mParity == parity)) {
+ // Make sure no action is performed if there is nothing to change
+ return;
+ }
+
+ byte[] lineRequestData = new byte[7];
+
+ lineRequestData[0] = (byte) (baudRate & 0xff);
+ lineRequestData[1] = (byte) ((baudRate >> 8) & 0xff);
+ lineRequestData[2] = (byte) ((baudRate >> 16) & 0xff);
+ lineRequestData[3] = (byte) ((baudRate >> 24) & 0xff);
+
+ switch (stopBits) {
+ case STOPBITS_1:
+ lineRequestData[4] = 0;
+ break;
+
+ case STOPBITS_1_5:
+ lineRequestData[4] = 1;
+ break;
+
+ case STOPBITS_2:
+ lineRequestData[4] = 2;
+ break;
+
+ default:
+ throw new IllegalArgumentException("Unknown stopBits value: " + stopBits);
+ }
+
+ switch (parity) {
+ case PARITY_NONE:
+ lineRequestData[5] = 0;
+ break;
+
+ case PARITY_ODD:
+ lineRequestData[5] = 1;
+ break;
+
+ case PARITY_EVEN:
+ lineRequestData[5] = 2;
+ break;
+
+ case PARITY_MARK:
+ lineRequestData[5] = 3;
+ break;
+
+ case PARITY_SPACE:
+ lineRequestData[5] = 4;
+ break;
+
+ default:
+ throw new IllegalArgumentException("Unknown parity value: " + parity);
+ }
+
+ lineRequestData[6] = (byte) dataBits;
+
+ ctrlOut(SET_LINE_REQUEST, 0, 0, lineRequestData);
+
+ resetDevice();
+
+ mBaudRate = baudRate;
+ mDataBits = dataBits;
+ mStopBits = stopBits;
+ mParity = parity;
+ }
+
+ @Override
+ public boolean getCD() throws IOException {
+ return testStatusFlag(STATUS_FLAG_CD);
+ }
+
+ @Override
+ public boolean getCTS() throws IOException {
+ return testStatusFlag(STATUS_FLAG_CTS);
+ }
+
+ @Override
+ public boolean getDSR() throws IOException {
+ return testStatusFlag(STATUS_FLAG_DSR);
+ }
+
+ @Override
+ public boolean getDTR() throws IOException {
+ return ((mControlLinesValue & CONTROL_DTR) == CONTROL_DTR);
+ }
+
+ @Override
+ public void setDTR(boolean value) throws IOException {
+ int newControlLinesValue;
+ if (value) {
+ newControlLinesValue = mControlLinesValue | CONTROL_DTR;
+ } else {
+ newControlLinesValue = mControlLinesValue & ~CONTROL_DTR;
+ }
+ setControlLines(newControlLinesValue);
+ }
+
+ @Override
+ public boolean getRI() throws IOException {
+ return testStatusFlag(STATUS_FLAG_RI);
+ }
+
+ @Override
+ public boolean getRTS() throws IOException {
+ return ((mControlLinesValue & CONTROL_RTS) == CONTROL_RTS);
+ }
+
+ @Override
+ public void setRTS(boolean value) throws IOException {
+ int newControlLinesValue;
+ if (value) {
+ newControlLinesValue = mControlLinesValue | CONTROL_RTS;
+ } else {
+ newControlLinesValue = mControlLinesValue & ~CONTROL_RTS;
+ }
+ setControlLines(newControlLinesValue);
+ }
+
+ @Override
+ public boolean purgeHwBuffers(boolean purgeReadBuffers, boolean purgeWriteBuffers) throws IOException {
+ if (purgeReadBuffers) {
+ vendorOut(FLUSH_RX_REQUEST, 0, null);
+ }
+
+ if (purgeWriteBuffers) {
+ vendorOut(FLUSH_TX_REQUEST, 0, null);
+ }
+
+ return true;
+ }
+
+ public static Map getSupportedDevices() {
+ final Map supportedDevices = new LinkedHashMap();
+ supportedDevices.put(Integer.valueOf(UsbId.VENDOR_PROLIFIC),
+ new int[] { UsbId.PROLIFIC_PL2303, });
+ return supportedDevices;
+ }
+}
+
diff --git a/android/src/com/hoho/android/usbserial/driver/UsbId.java b/android/src/com/hoho/android/usbserial/driver/UsbId.java
new file mode 100644
index 0000000000000000000000000000000000000000..618fbc844b398d5179c566933761188a2553e810
--- /dev/null
+++ b/android/src/com/hoho/android/usbserial/driver/UsbId.java
@@ -0,0 +1,69 @@
+/* Copyright 2012 Google Inc.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301,
+ * USA.
+ *
+ * Project home page: http://code.google.com/p/usb-serial-for-android/
+ */
+package com.hoho.android.usbserial.driver;
+
+/**
+ * Registry of USB vendor/product ID constants.
+ *
+ * Culled from various sources; see
+ * usb.ids for one listing.
+ *
+ * @author mike wakerly (opensource@hoho.com)
+ */
+public final class UsbId {
+
+ public static final int VENDOR_FTDI = 0x0403;
+ public static final int FTDI_FT232R = 0x6001;
+ public static final int FTDI_FT231X = 0x6015;
+
+ public static final int VENDOR_PX4 = 0x26AC;
+ public static final int DEVICE_PX4FMU = 0x11;
+
+ public static final int VENDOR_ATMEL = 0x03EB;
+ public static final int ATMEL_LUFA_CDC_DEMO_APP = 0x2044;
+
+ public static final int VENDOR_ARDUINO = 0x2341;
+ public static final int ARDUINO_UNO = 0x0001;
+ public static final int ARDUINO_MEGA_2560 = 0x0010;
+ public static final int ARDUINO_SERIAL_ADAPTER = 0x003b;
+ public static final int ARDUINO_MEGA_ADK = 0x003f;
+ public static final int ARDUINO_MEGA_2560_R3 = 0x0042;
+ public static final int ARDUINO_UNO_R3 = 0x0043;
+ public static final int ARDUINO_MEGA_ADK_R3 = 0x0044;
+ public static final int ARDUINO_SERIAL_ADAPTER_R3 = 0x0044;
+ public static final int ARDUINO_LEONARDO = 0x8036;
+
+ public static final int VENDOR_VAN_OOIJEN_TECH = 0x16c0;
+ public static final int VAN_OOIJEN_TECH_TEENSYDUINO_SERIAL = 0x0483;
+
+ public static final int VENDOR_LEAFLABS = 0x1eaf;
+ public static final int LEAFLABS_MAPLE = 0x0004;
+
+ public static final int VENDOR_SILAB = 0x10c4;
+ public static final int SILAB_CP2102 = 0xea60;
+
+ public static final int VENDOR_PROLIFIC = 0x067b;
+ public static final int PROLIFIC_PL2303 = 0x2303;
+
+ private UsbId() {
+ throw new IllegalAccessError("Non-instantiable class.");
+ }
+
+}
diff --git a/android/src/com/hoho/android/usbserial/driver/UsbSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/UsbSerialDriver.java
new file mode 100644
index 0000000000000000000000000000000000000000..ed4426fc4d540238fc2cae9706adb41602a3a7a4
--- /dev/null
+++ b/android/src/com/hoho/android/usbserial/driver/UsbSerialDriver.java
@@ -0,0 +1,228 @@
+/* Copyright 2011 Google Inc.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301,
+ * USA.
+ *
+ * Project home page: http://code.google.com/p/usb-serial-for-android/
+ */
+
+package com.hoho.android.usbserial.driver;
+
+import java.io.IOException;
+
+import android.hardware.usb.UsbDevice;
+import android.hardware.usb.UsbDeviceConnection;
+
+/**
+ * Driver interface for a USB serial device.
+ *
+ * @author mike wakerly (opensource@hoho.com)
+ */
+public interface UsbSerialDriver {
+
+ /** 5 data bits. */
+ public static final int DATABITS_5 = 5;
+
+ /** 6 data bits. */
+ public static final int DATABITS_6 = 6;
+
+ /** 7 data bits. */
+ public static final int DATABITS_7 = 7;
+
+ /** 8 data bits. */
+ public static final int DATABITS_8 = 8;
+
+ /** No flow control. */
+ public static final int FLOWCONTROL_NONE = 0;
+
+ /** RTS/CTS input flow control. */
+ public static final int FLOWCONTROL_RTSCTS_IN = 1;
+
+ /** RTS/CTS output flow control. */
+ public static final int FLOWCONTROL_RTSCTS_OUT = 2;
+
+ /** XON/XOFF input flow control. */
+ public static final int FLOWCONTROL_XONXOFF_IN = 4;
+
+ /** XON/XOFF output flow control. */
+ public static final int FLOWCONTROL_XONXOFF_OUT = 8;
+
+ /** No parity. */
+ public static final int PARITY_NONE = 0;
+
+ /** Odd parity. */
+ public static final int PARITY_ODD = 1;
+
+ /** Even parity. */
+ public static final int PARITY_EVEN = 2;
+
+ /** Mark parity. */
+ public static final int PARITY_MARK = 3;
+
+ /** Space parity. */
+ public static final int PARITY_SPACE = 4;
+
+ /** 1 stop bit. */
+ public static final int STOPBITS_1 = 1;
+
+ /** 1.5 stop bits. */
+ public static final int STOPBITS_1_5 = 3;
+
+ /** 2 stop bits. */
+ public static final int STOPBITS_2 = 2;
+
+ /**
+ * Returns the currently-bound USB device.
+ *
+ * @return the device
+ */
+ public UsbDevice getDevice();
+
+
+ /**
+ * Returns the currently-bound USB device.
+ *
+ * @return the device
+ */
+ public UsbDeviceConnection getDeviceConnection();
+
+ /**
+ * Opens and initializes the device as a USB serial device. Upon success,
+ * caller must ensure that {@link #close()} is eventually called.
+ *
+ * @throws IOException on error opening or initializing the device.
+ */
+ public void open() throws IOException;
+
+ /**
+ * Closes the serial device.
+ *
+ * @throws IOException on error closing the device.
+ */
+ public void close() throws IOException;
+
+ /**
+ * Reads as many bytes as possible into the destination buffer.
+ *
+ * @param dest the destination byte buffer
+ * @param timeoutMillis the timeout for reading
+ * @return the actual number of bytes read
+ * @throws IOException if an error occurred during reading
+ */
+ public int read(final byte[] dest, final int timeoutMillis) throws IOException;
+
+ /**
+ * Writes as many bytes as possible from the source buffer.
+ *
+ * @param src the source byte buffer
+ * @param timeoutMillis the timeout for writing
+ * @return the actual number of bytes written
+ * @throws IOException if an error occurred during writing
+ */
+ public int write(final byte[] src, final int timeoutMillis) throws IOException;
+
+ /**
+ * Sets various serial port parameters.
+ *
+ * @param baudRate baud rate as an integer, for example {@code 115200}.
+ * @param dataBits one of {@link #DATABITS_5}, {@link #DATABITS_6},
+ * {@link #DATABITS_7}, or {@link #DATABITS_8}.
+ * @param stopBits one of {@link #STOPBITS_1}, {@link #STOPBITS_1_5}, or
+ * {@link #STOPBITS_2}.
+ * @param parity one of {@link #PARITY_NONE}, {@link #PARITY_ODD},
+ * {@link #PARITY_EVEN}, {@link #PARITY_MARK}, or
+ * {@link #PARITY_SPACE}.
+ * @throws IOException on error setting the port parameters
+ */
+ public void setParameters(
+ int baudRate, int dataBits, int stopBits, int parity) throws IOException;
+
+ /**
+ * Gets the CD (Carrier Detect) bit from the underlying UART.
+ *
+ * @return the current state, or {@code false} if not supported.
+ * @throws IOException if an error occurred during reading
+ */
+ public boolean getCD() throws IOException;
+
+ /**
+ * Gets the CTS (Clear To Send) bit from the underlying UART.
+ *
+ * @return the current state, or {@code false} if not supported.
+ * @throws IOException if an error occurred during reading
+ */
+ public boolean getCTS() throws IOException;
+
+ /**
+ * Gets the DSR (Data Set Ready) bit from the underlying UART.
+ *
+ * @return the current state, or {@code false} if not supported.
+ * @throws IOException if an error occurred during reading
+ */
+ public boolean getDSR() throws IOException;
+
+ /**
+ * Gets the DTR (Data Terminal Ready) bit from the underlying UART.
+ *
+ * @return the current state, or {@code false} if not supported.
+ * @throws IOException if an error occurred during reading
+ */
+ public boolean getDTR() throws IOException;
+
+ /**
+ * Sets the DTR (Data Terminal Ready) bit on the underlying UART, if
+ * supported.
+ *
+ * @param value the value to set
+ * @throws IOException if an error occurred during writing
+ */
+ public void setDTR(boolean value) throws IOException;
+
+ /**
+ * Gets the RI (Ring Indicator) bit from the underlying UART.
+ *
+ * @return the current state, or {@code false} if not supported.
+ * @throws IOException if an error occurred during reading
+ */
+ public boolean getRI() throws IOException;
+
+ /**
+ * Gets the RTS (Request To Send) bit from the underlying UART.
+ *
+ * @return the current state, or {@code false} if not supported.
+ * @throws IOException if an error occurred during reading
+ */
+ public boolean getRTS() throws IOException;
+
+ /**
+ * Sets the RTS (Request To Send) bit on the underlying UART, if
+ * supported.
+ *
+ * @param value the value to set
+ * @throws IOException if an error occurred during writing
+ */
+ public void setRTS(boolean value) throws IOException;
+
+ /**
+ * Flush non-transmitted output data and / or non-read input data
+ * @param flushRX {@code true} to flush non-transmitted output data
+ * @param flushTX {@code true} to flush non-read input data
+ * @return {@code true} if the operation was successful, or
+ * {@code false} if the operation is not supported by the driver or device
+ * @throws IOException if an error occurred during flush
+ */
+ public boolean purgeHwBuffers(boolean flushRX, boolean flushTX) throws IOException;
+
+}
diff --git a/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java b/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java
new file mode 100644
index 0000000000000000000000000000000000000000..2e25a761e9c27488479ce383a7ee48bb6227413a
--- /dev/null
+++ b/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java
@@ -0,0 +1,250 @@
+/* Copyright 2011 Google Inc.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301,
+ * USA.
+ *
+ * Project home page: http://code.google.com/p/usb-serial-for-android/
+ */
+
+package com.hoho.android.usbserial.driver;
+
+import android.hardware.usb.UsbDevice;
+import android.hardware.usb.UsbDeviceConnection;
+import android.hardware.usb.UsbManager;
+import android.util.Log;
+
+import java.util.ArrayList;
+import java.util.Collections;
+import java.util.List;
+import java.util.Map;
+
+/**
+ * Helper class which finds compatible {@link UsbDevice}s and creates
+ * {@link UsbSerialDriver} instances.
+ *
+ *
+ * You don't need a Prober to use the rest of the library: it is perfectly
+ * acceptable to instantiate driver instances manually. The Prober simply
+ * provides convenience functions.
+ *
+ *
+ * For most drivers, the corresponding {@link #probe(UsbManager, UsbDevice)}
+ * method will either return an empty list (device unknown / unsupported) or a
+ * singleton list. However, multi-port drivers may return multiple instances.
+ *
+ * @author mike wakerly (opensource@hoho.com)
+ */
+public enum UsbSerialProber {
+
+ // TODO(mikey): Too much boilerplate.
+
+ /**
+ * Prober for {@link FtdiSerialDriver}.
+ *
+ * @see FtdiSerialDriver
+ */
+ FTDI_SERIAL {
+ @Override
+ public List probe(final UsbManager manager, final UsbDevice usbDevice) {
+ if (!testIfSupported(usbDevice, FtdiSerialDriver.getSupportedDevices())) {
+ return Collections.emptyList();
+ }
+ final UsbDeviceConnection connection = manager.openDevice(usbDevice);
+ if (connection == null) {
+ return Collections.emptyList();
+ }
+ final UsbSerialDriver driver = new FtdiSerialDriver(usbDevice, connection);
+ return Collections.singletonList(driver);
+ }
+ },
+
+ CDC_ACM_SERIAL {
+ @Override
+ public List probe(UsbManager manager, UsbDevice usbDevice) {
+ if (!testIfSupported(usbDevice, CdcAcmSerialDriver.getSupportedDevices())) {
+ return Collections.emptyList();
+ }
+ final UsbDeviceConnection connection = manager.openDevice(usbDevice);
+ if (connection == null) {
+ return Collections.emptyList();
+ }
+ final UsbSerialDriver driver = new CdcAcmSerialDriver(usbDevice, connection);
+ return Collections.singletonList(driver);
+ }
+ },
+
+ SILAB_SERIAL {
+ @Override
+ public List probe(final UsbManager manager, final UsbDevice usbDevice) {
+ if (!testIfSupported(usbDevice, Cp2102SerialDriver.getSupportedDevices())) {
+ return Collections.emptyList();
+ }
+ final UsbDeviceConnection connection = manager.openDevice(usbDevice);
+ if (connection == null) {
+ return Collections.emptyList();
+ }
+ final UsbSerialDriver driver = new Cp2102SerialDriver(usbDevice, connection);
+ return Collections.singletonList(driver);
+ }
+ },
+
+ PROLIFIC_SERIAL {
+ @Override
+ public List probe(final UsbManager manager, final UsbDevice usbDevice) {
+ if (!testIfSupported(usbDevice, ProlificSerialDriver.getSupportedDevices())) {
+ return Collections.emptyList();
+ }
+ final UsbDeviceConnection connection = manager.openDevice(usbDevice);
+ if (connection == null) {
+ return Collections.emptyList();
+ }
+ final UsbSerialDriver driver = new ProlificSerialDriver(usbDevice, connection);
+ return Collections.singletonList(driver);
+ }
+ };
+
+ /**
+ * Tests the supplied {@link UsbDevice} for compatibility with this enum
+ * member, returning one or more driver instances if compatible.
+ *
+ * @param manager the {@link UsbManager} to use
+ * @param usbDevice the raw {@link UsbDevice} to use
+ * @return zero or more {@link UsbSerialDriver}, depending on compatibility
+ * (never {@code null}).
+ */
+ protected abstract List probe(final UsbManager manager, final UsbDevice usbDevice);
+
+ /**
+ * Creates and returns a new {@link UsbSerialDriver} instance for the first
+ * compatible {@link UsbDevice} found on the bus. If none are found,
+ * returns {@code null}.
+ *
+ *
+ * The order of devices is undefined, therefore if there are multiple
+ * devices on the bus, the chosen device may not be predictable (clients
+ * should use {@link #findAllDevices(UsbManager)} instead).
+ *
+ * @param usbManager the {@link UsbManager} to use.
+ * @return the first available {@link UsbSerialDriver}, or {@code null} if
+ * none are available.
+ */
+ public static UsbSerialDriver findFirstDevice(final UsbManager usbManager) {
+ for (final UsbDevice usbDevice : usbManager.getDeviceList().values()) {
+ for (final UsbSerialProber prober : values()) {
+ final List probedDevices = prober.probe(usbManager, usbDevice);
+ if (!probedDevices.isEmpty()) {
+ return probedDevices.get(0);
+ }
+ }
+ }
+ return null;
+ }
+
+ /**
+ * Creates a new {@link UsbSerialDriver} instance for all compatible
+ * {@link UsbDevice}s found on the bus. If no compatible devices are found,
+ * the list will be empty.
+ *
+ * @param usbManager
+ * @return
+ */
+ public static List findAllDevices(final UsbManager usbManager) {
+ final List result = new ArrayList();
+ //Log.i("QGC_UsbSerialProber", "Looking for USB devices");
+ // For each UsbDevice, call probe() for each prober.
+ for (final UsbDevice usbDevice : usbManager.getDeviceList().values()) {
+ //Log.i("QGC_UsbSerialProber", "Probing device: " + usbDevice.getDeviceName() + " mid: " + usbDevice.getVendorId() + " pid: " + usbDevice.getDeviceId());
+ result.addAll(probeSingleDevice(usbManager, usbDevice));
+ }
+ return result;
+ }
+
+ /**
+ * Special method for testing a specific device for driver support,
+ * returning any compatible driver(s).
+ *
+ *
+ * Clients should ordinarily use {@link #findAllDevices(UsbManager)}, which
+ * operates against the entire bus of devices. This method is useful when
+ * testing against only a single target is desired.
+ *
+ * @param usbManager the {@link UsbManager} to use.
+ * @param usbDevice the device to test against.
+ * @return a list containing zero or more {@link UsbSerialDriver} instances.
+ */
+ public static List probeSingleDevice(final UsbManager usbManager,
+ UsbDevice usbDevice)
+ {
+ final List result = new ArrayList();
+ for (final UsbSerialProber prober : values()) {
+ final List probedDevices = prober.probe(usbManager, usbDevice);
+ result.addAll(probedDevices);
+ }
+ return result;
+ }
+
+ /**
+ * Deprecated; Use {@link #findFirstDevice(UsbManager)}.
+ *
+ * @param usbManager
+ * @return
+ */
+ @Deprecated
+ public static UsbSerialDriver acquire(final UsbManager usbManager) {
+ return findFirstDevice(usbManager);
+ }
+
+ /**
+ * Deprecated; use {@link #probeSingleDevice(UsbManager, UsbDevice)}.
+ *
+ * @param usbManager
+ * @param usbDevice
+ * @return
+ */
+ @Deprecated
+ public static UsbSerialDriver acquire(final UsbManager usbManager, final UsbDevice usbDevice) {
+ final List probedDevices = probeSingleDevice(usbManager, usbDevice);
+ if (!probedDevices.isEmpty()) {
+ return probedDevices.get(0);
+ }
+ return null;
+ }
+
+ /**
+ * Returns {@code true} if the given device is found in the driver's
+ * vendor/product map.
+ *
+ * @param usbDevice the device to test
+ * @param supportedDevices map of vendor IDs to product ID(s)
+ * @return {@code true} if supported
+ */
+ private static boolean testIfSupported(final UsbDevice usbDevice,
+ final Map supportedDevices) {
+ final int[] supportedProducts = supportedDevices.get(
+ Integer.valueOf(usbDevice.getVendorId()));
+ if (supportedProducts == null) {
+ return false;
+ }
+
+ final int productId = usbDevice.getProductId();
+ for (int supportedProductId : supportedProducts) {
+ if (productId == supportedProductId) {
+ return true;
+ }
+ }
+ return false;
+ }
+
+}
diff --git a/android/src/com/hoho/android/usbserial/driver/UsbSerialRuntimeException.java b/android/src/com/hoho/android/usbserial/driver/UsbSerialRuntimeException.java
new file mode 100644
index 0000000000000000000000000000000000000000..b48607c59da80c203031a252bcf1ee09d3a9b160
--- /dev/null
+++ b/android/src/com/hoho/android/usbserial/driver/UsbSerialRuntimeException.java
@@ -0,0 +1,46 @@
+/*
+ * Copyright 2011 Google Inc.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301,
+ * USA.
+ */
+
+package com.hoho.android.usbserial.driver;
+
+/**
+ * Generic unchecked exception for the usbserial package.
+ *
+ * @author mike wakerly (opensource@hoho.com)
+ */
+@SuppressWarnings("serial")
+public class UsbSerialRuntimeException extends RuntimeException {
+
+ public UsbSerialRuntimeException() {
+ super();
+ }
+
+ public UsbSerialRuntimeException(String detailMessage, Throwable throwable) {
+ super(detailMessage, throwable);
+ }
+
+ public UsbSerialRuntimeException(String detailMessage) {
+ super(detailMessage);
+ }
+
+ public UsbSerialRuntimeException(Throwable throwable) {
+ super(throwable);
+ }
+
+}
diff --git a/android/src/org/qgroundcontrol/qgchelper/UsbDeviceJNI.java b/android/src/org/qgroundcontrol/qgchelper/UsbDeviceJNI.java
new file mode 100644
index 0000000000000000000000000000000000000000..f9bad7086d1b6fc065ebb9751d7d3651d6ab6846
--- /dev/null
+++ b/android/src/org/qgroundcontrol/qgchelper/UsbDeviceJNI.java
@@ -0,0 +1,631 @@
+package org.qgroundcontrol.qgchelper;
+
+/* Copyright 2013 Google Inc.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 2.1 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301,
+ * USA.
+ *
+ * Project home page: http://code.google.com/p/usb-serial-for-android/
+ */
+///////////////////////////////////////////////////////////////////////////////////////////
+// Written by: Mike Goza April 2014
+//
+// These routines interface with the Android USB Host devices for serial port communication.
+// The code uses the usb-serial-for-android software library. The UsbDeviceJNI class is the
+// interface to the C++ routines through jni calls. Do not change the functions without also
+// changing the corresponding calls in the C++ routines or you will break the interface.
+//
+////////////////////////////////////////////////////////////////////////////////////////////
+
+import java.util.HashMap;
+import java.util.List;
+import java.util.concurrent.ExecutorService;
+import java.util.concurrent.Executors;
+import java.io.IOException;
+
+import android.app.Activity;
+import android.content.BroadcastReceiver;
+import android.content.Context;
+import android.content.Intent;
+import android.content.IntentFilter;
+import android.hardware.usb.*;
+import android.widget.Toast;
+import android.util.Log;
+
+import com.hoho.android.usbserial.driver.*;
+import org.qtproject.qt5.android.bindings.QtActivity;
+import org.qtproject.qt5.android.bindings.QtApplication;
+
+public class UsbDeviceJNI extends QtActivity
+{
+ public static int BAD_PORT = 0;
+ private static UsbDeviceJNI m_instance;
+ private static UsbManager m_manager; // ANDROID USB HOST CLASS
+ private static List m_devices; // LIST OF CURRENT DEVICES
+ private static HashMap m_openedDevices; // LIST OF OPENED DEVICES
+ private static HashMap m_ioManager; // THREADS FOR LISTENING FOR INCOMING DATA
+ private static HashMap m_userData; // CORRESPONDING USER DATA FOR OPENED DEVICES. USED IN DISCONNECT CALLBACK
+ // USED TO DETECT WHEN A DEVICE HAS BEEN UNPLUGGED
+ private BroadcastReceiver m_UsbReceiver = null;
+ private final static ExecutorService m_Executor = Executors.newSingleThreadExecutor();
+ private static final String TAG = "QGC_UsbDeviceJNI";
+
+ private final static UsbIoManager.Listener m_Listener =
+ new UsbIoManager.Listener()
+ {
+ @Override
+ public void onRunError(Exception eA, int userDataA)
+ {
+ Log.e(TAG, "onRunError Exception");
+ nativeDeviceException(userDataA, eA.getMessage());
+ }
+
+ @Override
+ public void onNewData(final byte[] dataA, int userDataA)
+ {
+ nativeDeviceNewData(userDataA, dataA);
+ }
+ };
+
+
+ // NATIVE C++ FUNCTION THAT WILL BE CALLED IF THE DEVICE IS UNPLUGGED
+ private static native void nativeDeviceHasDisconnected(int userDataA);
+ private static native void nativeDeviceException(int userDataA, String messageA);
+ private static native void nativeDeviceNewData(int userDataA, byte[] dataA);
+
+ ////////////////////////////////////////////////////////////////////////////////////////////////
+ //
+ // Constructor. Only used once to create the initial instance for the static functions.
+ //
+ ////////////////////////////////////////////////////////////////////////////////////////////////
+ public UsbDeviceJNI()
+ {
+ m_instance = this;
+ m_openedDevices = new HashMap();
+ m_userData = new HashMap();
+ m_ioManager = new HashMap();
+ Log.i(TAG, "Instance created");
+ }
+
+ /////////////////////////////////////////////////////////////////////////////////////////////////////////
+ //
+ // Find all current devices that match the device filter described in the androidmanifest.xml and the
+ // device_filter.xml
+ //
+ /////////////////////////////////////////////////////////////////////////////////////////////////////////
+ private static boolean getCurrentDevices()
+ {
+ if (m_instance == null)
+ return false;
+
+ if (m_manager == null)
+ m_manager = (UsbManager)m_instance.getSystemService(Context.USB_SERVICE);
+
+ if (m_devices != null)
+ m_devices.clear();
+
+ m_devices = UsbSerialProber.findAllDevices(m_manager);
+
+ return true;
+ }
+
+ /////////////////////////////////////////////////////////////////////////////////////////////////////////
+ //
+ // List all available devices that are not already open. It returns the serial port info
+ // in a : separated string array. Each string entry consists of the following:
+ //
+ // DeviceName:Company:ProductId:VendorId
+ //
+ /////////////////////////////////////////////////////////////////////////////////////////////////////////
+ public static String[] availableDevicesInfo()
+ {
+ // GET THE LIST OF CURRENT DEVICES
+ if (!getCurrentDevices())
+ {
+ Log.e(TAG, "UsbDeviceJNI instance not present");
+ return null;
+ }
+
+ // MAKE SURE WE HAVE ENTRIES
+ if (m_devices.size() <= 0)
+ {
+ //Log.e(TAG, "No USB devices found");
+ return null;
+ }
+
+ if (m_openedDevices == null)
+ {
+ Log.e(TAG, "m_openedDevices is null");
+ return null;
+ }
+
+ int countL = 0;
+ int iL;
+
+ // CHECK FOR ALREADY OPENED DEVICES AND DON"T INCLUDE THEM IN THE COUNT
+ for (iL=0; iL 0)
+ {
+ final Listener listener = getListener();
+ if (listener != null)
+ {
+ final byte[] data = new byte[len];
+ mReadBuffer.get(data, 0, len);
+ listener.onNewData(data, mUserData);
+ }
+ mReadBuffer.clear();
+ }
+/*
+ // Handle outgoing data.
+ byte[] outBuff = null;
+ synchronized (mWriteBuffer)
+ {
+ if (mWriteBuffer.position() > 0)
+ {
+ len = mWriteBuffer.position();
+ outBuff = new byte[len];
+ mWriteBuffer.rewind();
+ mWriteBuffer.get(outBuff, 0, len);
+ mWriteBuffer.clear();
+ }
+ }
+ if (outBuff != null)
+ mDriver.write(outBuff, READ_WAIT_MILLIS);
+*/
+ }
+}
+
diff --git a/android_environment.sh b/android_environment.sh
new file mode 100644
index 0000000000000000000000000000000000000000..477c0dbd1b3d3e3be5afd084fd7e7e47f65a8405
--- /dev/null
+++ b/android_environment.sh
@@ -0,0 +1,37 @@
+#!/bin/bash
+#----------------------------------------------------------
+# You will need:
+# - Qt 5.4 android_armv7 kit
+# - Android SDK
+# - Androig NDK
+# - Current Java
+# - ant
+#----------------------------------------------------------
+# Update with correct location for these
+export ANDROID_HOME=~/Library/Android/sdk
+export ANDROID_SDK_ROOT=~/Library/Android/sdk
+export ANDROID_NDK_ROOT=~/Library/Android/ndk
+export ANDROID_NDK_HOST=darwin-x86_64
+export ANDROID_NDK_PLATFORM=/android-9
+export ANDROID_NDK_TOOLCHAIN_PREFIX=arm-linux-androideabi
+export ANDROID_NDK_TOOLCHAIN_VERSION=4.9
+export ANDROID_NDK_TOOLS_PREFIX=arm-linux-androideabi
+#----------------------------------------------------------
+# To build it, run (replacing the path with where you have Qt installed)
+#
+# For a shadow build: (strongly recomended)
+#
+# >source android_environment.sh
+# cd ../
+# mkdir android_build
+# cd android_build
+# >~/local/Qt/5.4/android_armv7/bin/qmake -r -spec android-g++ CONFIG+=debug ../qgroundcontrol/qgroundcontrol.pro
+# >make -j24
+# >~/local/Qt/5.4/android_armv7/bin/androiddeployqt --input ./android-libqgroundcontrol.so-deployment-settings.json --output ./android-build --deployment bundled --android-platform android-22 --jdk /System/Library/Frameworks/JavaVM.framework/Versions/CurrentJDK/Home --verbose --ant /opt/local/bin/ant
+#
+# For an in place build (not recomended)
+#
+# >source android_environment.sh
+# >~/local/Qt/5.4/android_armv7/bin/qmake -r -spec android-g++ CONFIG+=debug qgroundcontrol.pro
+# >make -j24
+# >~/local/Qt/5.4/android_armv7/bin/androiddeployqt --input ./android-libqgroundcontrol.so-deployment-settings.json --output ./android-build --deployment bundled --android-platform android-22 --jdk /System/Library/Frameworks/JavaVM.framework/Versions/CurrentJDK/Home --verbose --ant /opt/local/bin/ant
diff --git a/data/ParameterList.xml b/data/ParameterList.xml
deleted file mode 100644
index 445f4d5a738d0b7e3c202ad7ae67c7dfbbaa96f9..0000000000000000000000000000000000000000
--- a/data/ParameterList.xml
+++ /dev/null
@@ -1,227 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/data/kinect.cal b/data/kinect.cal
deleted file mode 100644
index ee802fa7c43fcac35c76f002e4d856a39a0e0dfd..0000000000000000000000000000000000000000
--- a/data/kinect.cal
+++ /dev/null
@@ -1,37 +0,0 @@
-[rgb]
-principal_point\x=314.70228964
-principal_point\y=264.30478827
-focal_length\x=527.91246131
-focal_length\y=527.91246131
-distortion\k1=0.20496745
-distortion\k2=-0.36341243
-distortion\k3=0.00000000
-distortion\k4=0.00000000
-distortion\k5=0.00000000
-
-[depth]
-principal_point\x=311.88621344
-principal_point\y=247.63447078
-focal_length\x=593.89813561
-focal_length\y=593.89813561
-distortion\k1=0.00000000
-distortion\k2=0.00000000
-distortion\k3=0.00000000
-distortion\k4=0.00000000
-distortion\k5=0.00000000
-
-[transform]
-R11=0.999982
-R12=0.000556
-R13=0.005927
-R21=-0.000563
-R22=0.999999
-R23=0.001235
-R31=-0.005926
-R32=-0.001239
-R33=0.999982
-Tx=-0.024287
-Ty=0.001018
-Tz=-0.015195
-baseline=0.06061
-disparity_offset=1092.3403
diff --git a/debian/changelog b/debian/changelog
new file mode 100644
index 0000000000000000000000000000000000000000..f3d1a56c6598b1e18fb1d493e3619d072940449f
--- /dev/null
+++ b/debian/changelog
@@ -0,0 +1,5 @@
+qgroundcontrol (2.4-0ubuntu1) trusty; urgency=low
+
+ * Initial release (Closes: #nnnn)
+
+ -- Daniel Agar Sat, 04 Apr 2015 17:14:10 -0400
diff --git a/debian/compat b/debian/compat
new file mode 100644
index 0000000000000000000000000000000000000000..ec635144f60048986bc560c5576355344005e6e7
--- /dev/null
+++ b/debian/compat
@@ -0,0 +1 @@
+9
diff --git a/debian/control b/debian/control
new file mode 100644
index 0000000000000000000000000000000000000000..d8593ea302d1c8d2faae8d91d7860f6ba4c72c65
--- /dev/null
+++ b/debian/control
@@ -0,0 +1,15 @@
+Source: qgroundcontrol
+Section: electronics
+Priority: optional
+Maintainer: Daniel Agar
+Build-Depends: debhelper (>= 9), qt54tools, qt54base, qt54declarative, qt54serialport, qt54svg, qt54webkit, qt54quickcontrols, qt54xmlpatterns, qt54x11extras, qt54websockets, qt54sensors, qt54script, qt54quick1, qt54qbs, qt54multimedia, qt54location, qt54imageformats, qt54graphicaleffects, qt54creator, qt54connectivity, libsdl1.2-dev, libudev-dev
+Standards-Version: 3.9.5
+Homepage: https://github.com/mavlink/qgroundcontrol
+Vcs-Git: git://github.com/mavlink/qgroundcontrol.git
+#Vcs-Browser: http://git.debian.org/?p=collab-maint/qgroundcontrol.git;a=summary
+
+Package: qgroundcontrol
+Architecture: any
+Depends: ${shlibs:Depends}, ${misc:Depends}, qt54tools, qt54base, qt54declarative, qt54serialport, qt54svg, qt54webkit, qt54quickcontrols, qt54xmlpatterns, qt54x11extras, qt54websockets, qt54sensors, qt54script, qt54quick1, qt54multimedia, qt54location, qt54imageformats, qt54graphicaleffects, qt54connectivity
+Description: Open Source Micro Air Vehicle Ground Control Station
+
diff --git a/debian/copyright b/debian/copyright
new file mode 100644
index 0000000000000000000000000000000000000000..833c87414c389a5ff3d7431083bfa475caa6225a
--- /dev/null
+++ b/debian/copyright
@@ -0,0 +1,7 @@
+Format: http://www.debian.org/doc/packaging-manuals/copyright-format/1.0/
+Upstream-Name: qgroundcontrol
+Source: https://github.com/mavlink/qgroundcontrol
+
+Files: *
+Copyright: QGroundControl Developers https://github.com/mavlink/qgroundcontrol/graphs/contributors
+License: GPL-3+
diff --git a/debian/menu b/debian/menu
new file mode 100644
index 0000000000000000000000000000000000000000..8e03196aa2657c41bcb51a13a06dfe7d8e74f4e0
--- /dev/null
+++ b/debian/menu
@@ -0,0 +1,4 @@
+ ?package(qgroundcontrol):needs="x11" \
+ section="Applications/Electronics" \
+ title="QGroundControl" \
+ command="/usr/bin/qgroundcontrol"
diff --git a/debian/qgroundcontrol.install b/debian/qgroundcontrol.install
new file mode 100644
index 0000000000000000000000000000000000000000..0f7a95ee9ecf680ce60acd6d90af6ae235c1bb73
--- /dev/null
+++ b/debian/qgroundcontrol.install
@@ -0,0 +1,4 @@
+qgroundcontrol.desktop usr/share/applications
+release/qgroundcontrol usr/bin
+resources/ usr/share/qgroundcontrol
+resources/icons/qgroundcontrol.png usr/share/pixmaps
diff --git a/debian/rules b/debian/rules
new file mode 100755
index 0000000000000000000000000000000000000000..7c1274abab733e4b41d6994fa7772c013ac3fc6d
--- /dev/null
+++ b/debian/rules
@@ -0,0 +1,12 @@
+#!/usr/bin/make -f
+# -*- makefile -*-
+export QT_SELECT := qt5
+
+# Uncomment this to turn on verbose mode.
+export DH_VERBOSE=1
+
+%:
+ dh $@
+
+override_dh_auto_configure:
+ /opt/qt54/bin/qmake qgroundcontrol.pro
diff --git a/debian/source/format b/debian/source/format
new file mode 100644
index 0000000000000000000000000000000000000000..163aaf8d82b6c54f23c45f32895dbdfdcc27b047
--- /dev/null
+++ b/debian/source/format
@@ -0,0 +1 @@
+3.0 (quilt)
diff --git a/debian/source/options b/debian/source/options
new file mode 100644
index 0000000000000000000000000000000000000000..2059712f8865a8e5e74779116b6e19ac3c8c76e2
--- /dev/null
+++ b/debian/source/options
@@ -0,0 +1 @@
+tar-ignore = ".git/*"
diff --git a/debian/watch b/debian/watch
new file mode 100644
index 0000000000000000000000000000000000000000..ad20addfd5a70417e01ddc40d9a73cb64c316324
--- /dev/null
+++ b/debian/watch
@@ -0,0 +1,2 @@
+version=3
+https://github.com/mavlink/qgroundcontrol/tags .*/archive/[a-z](\d\S*)\.tar\.gz
diff --git a/deploy/px4driver.msi b/deploy/px4driver.msi
new file mode 100644
index 0000000000000000000000000000000000000000..4e2b0866d45b6735affffce5955a2b5775c22589
Binary files /dev/null and b/deploy/px4driver.msi differ
diff --git a/deploy/qgroundcontrol_installer.nsi b/deploy/qgroundcontrol_installer.nsi
index 322a17f38c15c59a110d16065a01a3be23fce0a3..57836ff0a83e719ccb9f9cd7b8be24737ba83800 100644
--- a/deploy/qgroundcontrol_installer.nsi
+++ b/deploy/qgroundcontrol_installer.nsi
@@ -14,9 +14,11 @@ LicenseData license.txt
Section
SetOutPath $INSTDIR
File /r release\*.*
+ File deploy\px4driver.msi
WriteUninstaller $INSTDIR\QGroundControl_uninstall.exe
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\QGroundControl" "DisplayName" "QGroundControl"
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\QGroundControl" "UninstallString" "$\"$INSTDIR\QGroundControl_uninstall.exe$\""
+ ExecWait '"msiexec" /i "px4driver.msi"'
SectionEnd
Section "Uninstall"
diff --git a/files/QLoggingCategory/qtlogging.ini b/files/QLoggingCategory/qtlogging.ini
deleted file mode 100644
index c67fdd4cf2ace3d3b61f16e05690bfc50a237b0b..0000000000000000000000000000000000000000
--- a/files/QLoggingCategory/qtlogging.ini
+++ /dev/null
@@ -1,2 +0,0 @@
-[Rules]
-*Log=false
diff --git a/files/Setup/cogwheels.png b/files/Setup/cogwheels.png
deleted file mode 100644
index 7ef3297fed5815fe15293da65e7cddf17ab25aab..0000000000000000000000000000000000000000
Binary files a/files/Setup/cogwheels.png and /dev/null differ
diff --git a/files/images/.gitignore b/files/images/.gitignore
deleted file mode 100644
index b25c15b81fae06e1c55946ac6270bfdb293870e8..0000000000000000000000000000000000000000
--- a/files/images/.gitignore
+++ /dev/null
@@ -1 +0,0 @@
-*~
diff --git a/files/images/actions/address-book-new.svg b/files/images/actions/address-book-new.svg
deleted file mode 100644
index 600a82c1b0e1bacf236764be2ec3310b98d9fc4b..0000000000000000000000000000000000000000
--- a/files/images/actions/address-book-new.svg
+++ /dev/null
@@ -1,389 +0,0 @@
-
-
-
diff --git a/files/images/actions/appointment-new.svg b/files/images/actions/appointment-new.svg
deleted file mode 100644
index 4cb14f82f02d92ed24119a7d0c858848aead5f57..0000000000000000000000000000000000000000
--- a/files/images/actions/appointment-new.svg
+++ /dev/null
@@ -1,425 +0,0 @@
-
-
-
diff --git a/files/images/actions/bookmark-new.svg b/files/images/actions/bookmark-new.svg
deleted file mode 100644
index d6d095b7155dd2a7519e842ef630e2dd03579cd3..0000000000000000000000000000000000000000
--- a/files/images/actions/bookmark-new.svg
+++ /dev/null
@@ -1,672 +0,0 @@
-
-
-
diff --git a/files/images/actions/contact-new.svg b/files/images/actions/contact-new.svg
deleted file mode 100644
index 1efb89548d2ba6b8c216ef3ffda4ac380d1a807e..0000000000000000000000000000000000000000
--- a/files/images/actions/contact-new.svg
+++ /dev/null
@@ -1,606 +0,0 @@
-
-
-
diff --git a/files/images/actions/document-new.svg b/files/images/actions/document-new.svg
deleted file mode 100644
index 1bfdb16409c0e93e4eeddc0758c4383ff3e5474c..0000000000000000000000000000000000000000
--- a/files/images/actions/document-new.svg
+++ /dev/null
@@ -1,448 +0,0 @@
-
-
-
diff --git a/files/images/actions/document-open.svg b/files/images/actions/document-open.svg
deleted file mode 100644
index 55e6177d2ae26bdc89d30c2c2909033cf971f56b..0000000000000000000000000000000000000000
--- a/files/images/actions/document-open.svg
+++ /dev/null
@@ -1,535 +0,0 @@
-
-
-
diff --git a/files/images/actions/document-print-preview.svg b/files/images/actions/document-print-preview.svg
deleted file mode 100644
index d3501ac154d3f9f812cf7b23b2a64aab35bb2c52..0000000000000000000000000000000000000000
--- a/files/images/actions/document-print-preview.svg
+++ /dev/null
@@ -1,703 +0,0 @@
-
-
-
diff --git a/files/images/actions/document-print.svg b/files/images/actions/document-print.svg
deleted file mode 100644
index 0b8837ba1df643c64257b24ebaa0b6c5394a78c2..0000000000000000000000000000000000000000
--- a/files/images/actions/document-print.svg
+++ /dev/null
@@ -1,532 +0,0 @@
-
-
-
diff --git a/files/images/actions/document-properties.svg b/files/images/actions/document-properties.svg
deleted file mode 100644
index c57f96d2e29e2d45f61eb83d2dbbdaa2f467d0cd..0000000000000000000000000000000000000000
--- a/files/images/actions/document-properties.svg
+++ /dev/null
@@ -1,576 +0,0 @@
-
-
-
diff --git a/files/images/actions/document-save-as.svg b/files/images/actions/document-save-as.svg
deleted file mode 100644
index 01e2fb7a5db34a0c407d5e5c2561a18c10df3f40..0000000000000000000000000000000000000000
--- a/files/images/actions/document-save-as.svg
+++ /dev/null
@@ -1,663 +0,0 @@
-
-
-
diff --git a/files/images/actions/document-save.svg b/files/images/actions/document-save.svg
deleted file mode 100644
index 2922c4331a7f566ada86784b0b96be5d44035d7c..0000000000000000000000000000000000000000
--- a/files/images/actions/document-save.svg
+++ /dev/null
@@ -1,619 +0,0 @@
-
-
-
diff --git a/files/images/actions/edit-clear.svg b/files/images/actions/edit-clear.svg
deleted file mode 100644
index b2f20d44e7038d46fbc7ae7b82bf6e89fcda70ff..0000000000000000000000000000000000000000
--- a/files/images/actions/edit-clear.svg
+++ /dev/null
@@ -1,416 +0,0 @@
-
-
-
diff --git a/files/images/actions/edit-copy.svg b/files/images/actions/edit-copy.svg
deleted file mode 100644
index f4d9e9776c1156da09af1339c918bd820cf1b7ff..0000000000000000000000000000000000000000
--- a/files/images/actions/edit-copy.svg
+++ /dev/null
@@ -1,328 +0,0 @@
-
-
-
diff --git a/files/images/actions/edit-cut.svg b/files/images/actions/edit-cut.svg
deleted file mode 100644
index b9ac930c91a21bee2321d1cd510d4bf3bc4fa6bd..0000000000000000000000000000000000000000
--- a/files/images/actions/edit-cut.svg
+++ /dev/null
@@ -1,508 +0,0 @@
-
-
-
diff --git a/files/images/actions/edit-delete.svg b/files/images/actions/edit-delete.svg
deleted file mode 100644
index 69281e4239411b408e8d8b08a0bf88c91ec6dac1..0000000000000000000000000000000000000000
--- a/files/images/actions/edit-delete.svg
+++ /dev/null
@@ -1,896 +0,0 @@
-
-
-
diff --git a/files/images/actions/edit-find-replace.svg b/files/images/actions/edit-find-replace.svg
deleted file mode 100644
index 1f443ff7d3ff7008f33c36e743af15010b5fbc91..0000000000000000000000000000000000000000
--- a/files/images/actions/edit-find-replace.svg
+++ /dev/null
@@ -1,974 +0,0 @@
-
-
-
diff --git a/files/images/actions/edit-find.svg b/files/images/actions/edit-find.svg
deleted file mode 100644
index a499b486cf85b780cdcd97be247000b908ac22f3..0000000000000000000000000000000000000000
--- a/files/images/actions/edit-find.svg
+++ /dev/null
@@ -1,750 +0,0 @@
-
-
-
diff --git a/files/images/actions/edit-paste.svg b/files/images/actions/edit-paste.svg
deleted file mode 100644
index 39150d7155d11b0f9b4d405225afeff60be900f9..0000000000000000000000000000000000000000
--- a/files/images/actions/edit-paste.svg
+++ /dev/null
@@ -1,531 +0,0 @@
-
-
-
diff --git a/files/images/actions/edit-redo.svg b/files/images/actions/edit-redo.svg
deleted file mode 100644
index bc4d52af7c93e11c5903fd5120912f5e8737c68e..0000000000000000000000000000000000000000
--- a/files/images/actions/edit-redo.svg
+++ /dev/null
@@ -1,231 +0,0 @@
-
-
-
diff --git a/files/images/actions/edit-select-all.svg b/files/images/actions/edit-select-all.svg
deleted file mode 100644
index dd5250752b943409049712df289baedc89544c63..0000000000000000000000000000000000000000
--- a/files/images/actions/edit-select-all.svg
+++ /dev/null
@@ -1,349 +0,0 @@
-
-
-
diff --git a/files/images/actions/edit-undo.svg b/files/images/actions/edit-undo.svg
deleted file mode 100644
index d3cce96f1bee79a9a35b2aa72dac530b5f9d9778..0000000000000000000000000000000000000000
--- a/files/images/actions/edit-undo.svg
+++ /dev/null
@@ -1,230 +0,0 @@
-
-
-
diff --git a/files/images/actions/folder-new.svg b/files/images/actions/folder-new.svg
deleted file mode 100644
index 0791887afcbbe0593984807949702d42fc87f20a..0000000000000000000000000000000000000000
--- a/files/images/actions/folder-new.svg
+++ /dev/null
@@ -1,452 +0,0 @@
-
-
-
diff --git a/files/images/actions/format-indent-less.svg b/files/images/actions/format-indent-less.svg
deleted file mode 100644
index 00be1f3a355fb9805bfd27203b338d0865b94ae5..0000000000000000000000000000000000000000
--- a/files/images/actions/format-indent-less.svg
+++ /dev/null
@@ -1,373 +0,0 @@
-
-
-
diff --git a/files/images/actions/format-indent-more.svg b/files/images/actions/format-indent-more.svg
deleted file mode 100644
index 2047b623a4fbb72afabcd151773d325340235490..0000000000000000000000000000000000000000
--- a/files/images/actions/format-indent-more.svg
+++ /dev/null
@@ -1,368 +0,0 @@
-
-
-
diff --git a/files/images/actions/format-justify-center.svg b/files/images/actions/format-justify-center.svg
deleted file mode 100644
index d1564f33b36fb2a9299206b1a8e97f539cff5cb9..0000000000000000000000000000000000000000
--- a/files/images/actions/format-justify-center.svg
+++ /dev/null
@@ -1,342 +0,0 @@
-
-
-
diff --git a/files/images/actions/format-justify-fill.svg b/files/images/actions/format-justify-fill.svg
deleted file mode 100644
index 1ec09496307ebd1269289e932ac058c73bf80dbe..0000000000000000000000000000000000000000
--- a/files/images/actions/format-justify-fill.svg
+++ /dev/null
@@ -1,342 +0,0 @@
-
-
-
diff --git a/files/images/actions/format-justify-left.svg b/files/images/actions/format-justify-left.svg
deleted file mode 100644
index c250195007748130fbc744750e71cbb9f2150b2e..0000000000000000000000000000000000000000
--- a/files/images/actions/format-justify-left.svg
+++ /dev/null
@@ -1,271 +0,0 @@
-
-
-
diff --git a/files/images/actions/format-justify-right.svg b/files/images/actions/format-justify-right.svg
deleted file mode 100644
index f6f2205e734d8a58132d397641d11ef96549fd66..0000000000000000000000000000000000000000
--- a/files/images/actions/format-justify-right.svg
+++ /dev/null
@@ -1,342 +0,0 @@
-
-
-
diff --git a/files/images/actions/format-text-bold.svg b/files/images/actions/format-text-bold.svg
deleted file mode 100644
index 9268d4ea6013169a70db72e51e8a3da6cbffe6a1..0000000000000000000000000000000000000000
--- a/files/images/actions/format-text-bold.svg
+++ /dev/null
@@ -1,327 +0,0 @@
-
-
-
diff --git a/files/images/actions/format-text-italic.svg b/files/images/actions/format-text-italic.svg
deleted file mode 100644
index 3a4bc363a06fa79b4b29c4c986501a6de2784b09..0000000000000000000000000000000000000000
--- a/files/images/actions/format-text-italic.svg
+++ /dev/null
@@ -1,334 +0,0 @@
-
-
-
diff --git a/files/images/actions/format-text-strikethrough.svg b/files/images/actions/format-text-strikethrough.svg
deleted file mode 100644
index 5e87b5ede56b5d5a0fc622760fd2ce32d1cf2cd5..0000000000000000000000000000000000000000
--- a/files/images/actions/format-text-strikethrough.svg
+++ /dev/null
@@ -1,421 +0,0 @@
-
-
-
diff --git a/files/images/actions/format-text-underline.svg b/files/images/actions/format-text-underline.svg
deleted file mode 100644
index 22131f6c2b2abde4c23d7519efa8d943b6c45885..0000000000000000000000000000000000000000
--- a/files/images/actions/format-text-underline.svg
+++ /dev/null
@@ -1,434 +0,0 @@
-
-
-
diff --git a/files/images/actions/go-first.svg b/files/images/actions/go-first.svg
deleted file mode 100644
index 4e0b668f907828279dc4f05adb8aa893c76534ab..0000000000000000000000000000000000000000
--- a/files/images/actions/go-first.svg
+++ /dev/null
@@ -1,204 +0,0 @@
-
-
-
diff --git a/files/images/actions/go-home.svg b/files/images/actions/go-home.svg
deleted file mode 100644
index 4f16958844d23c0fd2263ee9af8e2e11410c1ab8..0000000000000000000000000000000000000000
--- a/files/images/actions/go-home.svg
+++ /dev/null
@@ -1,445 +0,0 @@
-
-
\ No newline at end of file
diff --git a/files/images/actions/go-last.svg b/files/images/actions/go-last.svg
deleted file mode 100644
index 00af499db702c4a792a4dd4711fd44b8263bdb9b..0000000000000000000000000000000000000000
--- a/files/images/actions/go-last.svg
+++ /dev/null
@@ -1,204 +0,0 @@
-
-
-
diff --git a/files/images/actions/go-top.svg b/files/images/actions/go-top.svg
deleted file mode 100644
index 4ee94d3c8f07db915d1e146a96af56a07f3ed661..0000000000000000000000000000000000000000
--- a/files/images/actions/go-top.svg
+++ /dev/null
@@ -1,974 +0,0 @@
-
-
-
diff --git a/files/images/actions/mail-forward.svg b/files/images/actions/mail-forward.svg
deleted file mode 100644
index b159ed5399ded63e66fec784c6cedee9cf8dcf68..0000000000000000000000000000000000000000
--- a/files/images/actions/mail-forward.svg
+++ /dev/null
@@ -1,961 +0,0 @@
-
-
-
diff --git a/files/images/actions/mail-mark-junk.svg b/files/images/actions/mail-mark-junk.svg
deleted file mode 100644
index 01631751f79fdae79551455aecefd3caf1f4d540..0000000000000000000000000000000000000000
--- a/files/images/actions/mail-mark-junk.svg
+++ /dev/null
@@ -1,504 +0,0 @@
-
-
-
diff --git a/files/images/actions/mail-message-new.svg b/files/images/actions/mail-message-new.svg
deleted file mode 100644
index 9f68587763947b6a2d331b602528f39d6ba19f8e..0000000000000000000000000000000000000000
--- a/files/images/actions/mail-message-new.svg
+++ /dev/null
@@ -1,464 +0,0 @@
-
-
-
diff --git a/files/images/actions/mail-reply-all.svg b/files/images/actions/mail-reply-all.svg
deleted file mode 100644
index f1ee15f4085e95110b79353bdfc01eff7ff9638c..0000000000000000000000000000000000000000
--- a/files/images/actions/mail-reply-all.svg
+++ /dev/null
@@ -1,976 +0,0 @@
-
-
-
diff --git a/files/images/actions/mail-reply-sender.svg b/files/images/actions/mail-reply-sender.svg
deleted file mode 100644
index ad1cab436aed923de978107fa799445da5b55215..0000000000000000000000000000000000000000
--- a/files/images/actions/mail-reply-sender.svg
+++ /dev/null
@@ -1,548 +0,0 @@
-
-
-
diff --git a/files/images/actions/mail-send-receive.svg b/files/images/actions/mail-send-receive.svg
deleted file mode 100644
index ef7157775eac5e0ffe0c2daeb027901c5bd94fdc..0000000000000000000000000000000000000000
--- a/files/images/actions/mail-send-receive.svg
+++ /dev/null
@@ -1,1101 +0,0 @@
-
-
-
diff --git a/files/images/actions/media-eject.svg b/files/images/actions/media-eject.svg
deleted file mode 100644
index d22eae1a4f3854e0211ea43a399cf7022b96a64c..0000000000000000000000000000000000000000
--- a/files/images/actions/media-eject.svg
+++ /dev/null
@@ -1,450 +0,0 @@
-
-
-
diff --git a/files/images/actions/media-record.svg b/files/images/actions/media-record.svg
deleted file mode 100644
index 85bbb98f6e298534d4fbc0d38a872695fb1e694b..0000000000000000000000000000000000000000
--- a/files/images/actions/media-record.svg
+++ /dev/null
@@ -1,337 +0,0 @@
-
-
-
diff --git a/files/images/actions/media-seek-backward.svg b/files/images/actions/media-seek-backward.svg
deleted file mode 100644
index 75f49f1a8243bff83f2e8a021cf9c7f16e4f77f0..0000000000000000000000000000000000000000
--- a/files/images/actions/media-seek-backward.svg
+++ /dev/null
@@ -1,374 +0,0 @@
-
-
-
diff --git a/files/images/actions/media-seek-forward.svg b/files/images/actions/media-seek-forward.svg
deleted file mode 100644
index b1b9fe950bf65e3e06850972e768a6845cbf0ce1..0000000000000000000000000000000000000000
--- a/files/images/actions/media-seek-forward.svg
+++ /dev/null
@@ -1,383 +0,0 @@
-
-
-
diff --git a/files/images/actions/media-skip-backward.svg b/files/images/actions/media-skip-backward.svg
deleted file mode 100644
index fccd7762cde6944501bd6647341f78e7dd905e51..0000000000000000000000000000000000000000
--- a/files/images/actions/media-skip-backward.svg
+++ /dev/null
@@ -1,1025 +0,0 @@
-
-
-
diff --git a/files/images/actions/media-skip-forward.svg b/files/images/actions/media-skip-forward.svg
deleted file mode 100644
index 7c4d40054b275de9ef81d57e3b3118acde9c320d..0000000000000000000000000000000000000000
--- a/files/images/actions/media-skip-forward.svg
+++ /dev/null
@@ -1,1013 +0,0 @@
-
-
-
diff --git a/files/images/actions/qgroundcontrol-apm.svg b/files/images/actions/qgroundcontrol-apm.svg
deleted file mode 100644
index d8ff8dee5a9bccad567dc48f4cc09e85e808a0da..0000000000000000000000000000000000000000
--- a/files/images/actions/qgroundcontrol-apm.svg
+++ /dev/null
@@ -1,4931 +0,0 @@
-
-
diff --git a/files/images/actions/qgroundcontrol-ardrone.svg b/files/images/actions/qgroundcontrol-ardrone.svg
deleted file mode 100644
index 9933b10fef67fcc4066b3365aa84b3f8cad3c26a..0000000000000000000000000000000000000000
--- a/files/images/actions/qgroundcontrol-ardrone.svg
+++ /dev/null
@@ -1,178 +0,0 @@
-
-
-
-
diff --git a/files/images/actions/qgroundcontrol-generic.svg b/files/images/actions/qgroundcontrol-generic.svg
deleted file mode 100644
index 92b3d0e7faf3cb254816b74aa423c70d9b1320f5..0000000000000000000000000000000000000000
--- a/files/images/actions/qgroundcontrol-generic.svg
+++ /dev/null
@@ -1,273 +0,0 @@
-
-
-
-
diff --git a/files/images/actions/qgroundcontrol-px4.svg b/files/images/actions/qgroundcontrol-px4.svg
deleted file mode 100644
index b264ca567425a285072e8ded8a4881ef78fdeadd..0000000000000000000000000000000000000000
--- a/files/images/actions/qgroundcontrol-px4.svg
+++ /dev/null
@@ -1,165 +0,0 @@
-
-
-
-
diff --git a/files/images/actions/qgroundcontrol-wifi.svg b/files/images/actions/qgroundcontrol-wifi.svg
deleted file mode 100644
index eaaf531d8cffea255bd241b2fb25f2e952ca0811..0000000000000000000000000000000000000000
--- a/files/images/actions/qgroundcontrol-wifi.svg
+++ /dev/null
@@ -1,109 +0,0 @@
-
-
-
-
diff --git a/files/images/actions/system-search.svg b/files/images/actions/system-search.svg
deleted file mode 100644
index 1a4c1cd776abd000264967cb7890afbab09afdc2..0000000000000000000000000000000000000000
--- a/files/images/actions/system-search.svg
+++ /dev/null
@@ -1,313 +0,0 @@
-
-
-
diff --git a/files/images/actions/system-shutdown.svg b/files/images/actions/system-shutdown.svg
deleted file mode 100644
index 9b0b32713ee60c866d201ec4b3a9cf203e205581..0000000000000000000000000000000000000000
--- a/files/images/actions/system-shutdown.svg
+++ /dev/null
@@ -1,424 +0,0 @@
-
-
-
diff --git a/files/images/actions/tab-new.svg b/files/images/actions/tab-new.svg
deleted file mode 100644
index f3c0a14d47d97a178144807a594f078f752ae80c..0000000000000000000000000000000000000000
--- a/files/images/actions/tab-new.svg
+++ /dev/null
@@ -1,328 +0,0 @@
-
-
-
diff --git a/files/images/actions/view-fullscreen.svg b/files/images/actions/view-fullscreen.svg
deleted file mode 100644
index d410654bcb36238fae327790a77c97e463d37759..0000000000000000000000000000000000000000
--- a/files/images/actions/view-fullscreen.svg
+++ /dev/null
@@ -1,522 +0,0 @@
-
-
-
diff --git a/files/images/actions/view-refresh.svg b/files/images/actions/view-refresh.svg
deleted file mode 100644
index 565f6dadec3d5841bc035133918ce0ad9472d7d0..0000000000000000000000000000000000000000
--- a/files/images/actions/view-refresh.svg
+++ /dev/null
@@ -1,393 +0,0 @@
-
-
-
diff --git a/files/images/actions/window-new.svg b/files/images/actions/window-new.svg
deleted file mode 100644
index 60d33cfb6dc00a4939684958b6b829e333727f4c..0000000000000000000000000000000000000000
--- a/files/images/actions/window-new.svg
+++ /dev/null
@@ -1,292 +0,0 @@
-
-
-
diff --git a/files/images/apps/accessories-calculator.svg b/files/images/apps/accessories-calculator.svg
deleted file mode 100644
index 88cf76a93d46af9ae9870846917ab237b1c85775..0000000000000000000000000000000000000000
--- a/files/images/apps/accessories-calculator.svg
+++ /dev/null
@@ -1,636 +0,0 @@
-
-
-
diff --git a/files/images/apps/accessories-character-map.svg b/files/images/apps/accessories-character-map.svg
deleted file mode 100644
index 8bb8dcfe49933de61cb987d0752672223a67823c..0000000000000000000000000000000000000000
--- a/files/images/apps/accessories-character-map.svg
+++ /dev/null
@@ -1,341 +0,0 @@
-
-
-
diff --git a/files/images/apps/accessories-text-editor.svg b/files/images/apps/accessories-text-editor.svg
deleted file mode 100644
index 70621f01fc1dff2d62761ebb227204e90339ab1a..0000000000000000000000000000000000000000
--- a/files/images/apps/accessories-text-editor.svg
+++ /dev/null
@@ -1,554 +0,0 @@
-
-
-
diff --git a/files/images/apps/help-browser.svg b/files/images/apps/help-browser.svg
deleted file mode 100644
index 851327f7769cbc1547be22eb2a297d287bcc3ae9..0000000000000000000000000000000000000000
--- a/files/images/apps/help-browser.svg
+++ /dev/null
@@ -1,224 +0,0 @@
-
-
-
diff --git a/files/images/apps/internet-group-chat.svg b/files/images/apps/internet-group-chat.svg
deleted file mode 100644
index 8e8945ecf838ccc9078306c3c00a0f4aeb7170e7..0000000000000000000000000000000000000000
--- a/files/images/apps/internet-group-chat.svg
+++ /dev/null
@@ -1,312 +0,0 @@
-
-
-
diff --git a/files/images/apps/internet-mail.svg b/files/images/apps/internet-mail.svg
deleted file mode 100644
index 8d5ea8cd324349192176297769b1d58c90a9190b..0000000000000000000000000000000000000000
--- a/files/images/apps/internet-mail.svg
+++ /dev/null
@@ -1,440 +0,0 @@
-
-
-
diff --git a/files/images/apps/internet-news-reader.svg b/files/images/apps/internet-news-reader.svg
deleted file mode 100644
index b86f419ed819c864a36a1c9c39cbde173ee7e4b3..0000000000000000000000000000000000000000
--- a/files/images/apps/internet-news-reader.svg
+++ /dev/null
@@ -1,408 +0,0 @@
-
-
-
diff --git a/files/images/apps/internet-web-browser.svg b/files/images/apps/internet-web-browser.svg
deleted file mode 100644
index d2366a9dcd4116084d85679bd84eeaf15a6f5bf8..0000000000000000000000000000000000000000
--- a/files/images/apps/internet-web-browser.svg
+++ /dev/null
@@ -1,982 +0,0 @@
-
-
-
diff --git a/files/images/apps/office-calendar.svg b/files/images/apps/office-calendar.svg
deleted file mode 100644
index d9f9281db54bcc8ef088ad089db4bf885ea93e5e..0000000000000000000000000000000000000000
--- a/files/images/apps/office-calendar.svg
+++ /dev/null
@@ -1,316 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-desktop-accessibility.svg b/files/images/apps/preferences-desktop-accessibility.svg
deleted file mode 100644
index 9977314bdcd9edcc3bc290cd615f608748b7cbe8..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-desktop-accessibility.svg
+++ /dev/null
@@ -1,245 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-desktop-assistive-technology.svg b/files/images/apps/preferences-desktop-assistive-technology.svg
deleted file mode 100644
index 39a46686f7f505b011837a7cd51d2fc3c9c30d77..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-desktop-assistive-technology.svg
+++ /dev/null
@@ -1,369 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-desktop-font.svg b/files/images/apps/preferences-desktop-font.svg
deleted file mode 100644
index 079398021d42220099abad77894e586c7ceb1f9c..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-desktop-font.svg
+++ /dev/null
@@ -1,243 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-desktop-keyboard-shortcuts.svg b/files/images/apps/preferences-desktop-keyboard-shortcuts.svg
deleted file mode 100644
index 6caf205d20bbae75fcc476de841bd269f9972f01..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-desktop-keyboard-shortcuts.svg
+++ /dev/null
@@ -1,839 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-desktop-locale.svg b/files/images/apps/preferences-desktop-locale.svg
deleted file mode 100644
index 2e71f18a80bd50671bd985ca3e405bbeb57961bb..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-desktop-locale.svg
+++ /dev/null
@@ -1,878 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-desktop-multimedia.svg b/files/images/apps/preferences-desktop-multimedia.svg
deleted file mode 100644
index 9ddee90ae61a6fc2dd2817044a81cb6ff023481f..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-desktop-multimedia.svg
+++ /dev/null
@@ -1,579 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-desktop-remote-desktop.svg b/files/images/apps/preferences-desktop-remote-desktop.svg
deleted file mode 100644
index 848e8922f02d8ffe6122041b10f1d2f9e187ae9d..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-desktop-remote-desktop.svg
+++ /dev/null
@@ -1,1479 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-desktop-screensaver.svg b/files/images/apps/preferences-desktop-screensaver.svg
deleted file mode 100644
index 0db417677389ac98c2e96ccec660ad0a63793007..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-desktop-screensaver.svg
+++ /dev/null
@@ -1,717 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-desktop-theme.svg b/files/images/apps/preferences-desktop-theme.svg
deleted file mode 100644
index 45ed886eae059e6ae6aca79fe2b0e81bd1a76232..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-desktop-theme.svg
+++ /dev/null
@@ -1,882 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-desktop-wallpaper.svg b/files/images/apps/preferences-desktop-wallpaper.svg
deleted file mode 100644
index 0f94fbd1572cecabec901190ee8e59f006beb80a..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-desktop-wallpaper.svg
+++ /dev/null
@@ -1,747 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-system-network-proxy.svg b/files/images/apps/preferences-system-network-proxy.svg
deleted file mode 100644
index efb2653f756bbc686101304137d49bc78e11074b..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-system-network-proxy.svg
+++ /dev/null
@@ -1,1168 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-system-session.svg b/files/images/apps/preferences-system-session.svg
deleted file mode 100644
index 27954bcecfac8b0ad29bbf2dc12a400b0d38b175..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-system-session.svg
+++ /dev/null
@@ -1,510 +0,0 @@
-
-
-
diff --git a/files/images/apps/preferences-system-windows.svg b/files/images/apps/preferences-system-windows.svg
deleted file mode 100644
index dc344f71622bb92ad6eaaca4f0f1a1df5a01d2f1..0000000000000000000000000000000000000000
--- a/files/images/apps/preferences-system-windows.svg
+++ /dev/null
@@ -1,386 +0,0 @@
-
-
-
diff --git a/files/images/apps/system-file-manager.svg b/files/images/apps/system-file-manager.svg
deleted file mode 100644
index 99ad454a49866368f92f2073b8e2a4756e2053d6..0000000000000000000000000000000000000000
--- a/files/images/apps/system-file-manager.svg
+++ /dev/null
@@ -1,317 +0,0 @@
-
-
-
diff --git a/files/images/apps/system-installer.svg b/files/images/apps/system-installer.svg
deleted file mode 100644
index 32007409722c0b4799e41e8ef72a23e018040119..0000000000000000000000000000000000000000
--- a/files/images/apps/system-installer.svg
+++ /dev/null
@@ -1,497 +0,0 @@
-
-
-
diff --git a/files/images/apps/system-software-update.svg b/files/images/apps/system-software-update.svg
deleted file mode 100644
index 66eb747c5d9dba82f901993086a0e44b9f31c6d1..0000000000000000000000000000000000000000
--- a/files/images/apps/system-software-update.svg
+++ /dev/null
@@ -1,1380 +0,0 @@
-
-
-
diff --git a/files/images/apps/system-users.svg b/files/images/apps/system-users.svg
deleted file mode 100644
index 7d628b86d848afb77c83e2f23bcc7dbe8fd38d59..0000000000000000000000000000000000000000
--- a/files/images/apps/system-users.svg
+++ /dev/null
@@ -1,539 +0,0 @@
-
-
-
diff --git a/files/images/apps/utilities-system-monitor.svg b/files/images/apps/utilities-system-monitor.svg
deleted file mode 100644
index 8f4b9462e3f879b5dddc756b03edf6464c302043..0000000000000000000000000000000000000000
--- a/files/images/apps/utilities-system-monitor.svg
+++ /dev/null
@@ -1,435 +0,0 @@
-
-
-
diff --git a/files/images/apps/utilities-terminal.svg b/files/images/apps/utilities-terminal.svg
deleted file mode 100644
index 995fb90b37e63106a19af7726485e4baa9720952..0000000000000000000000000000000000000000
--- a/files/images/apps/utilities-terminal.svg
+++ /dev/null
@@ -1,500 +0,0 @@
-
-
-
diff --git a/files/images/backgrounds/background-caution-button-active.png b/files/images/backgrounds/background-caution-button-active.png
deleted file mode 100644
index 7d21e4c682f48cb2cdb86b6107aa227262af72d2..0000000000000000000000000000000000000000
Binary files a/files/images/backgrounds/background-caution-button-active.png and /dev/null differ
diff --git a/files/images/backgrounds/background-caution-button.png b/files/images/backgrounds/background-caution-button.png
deleted file mode 100644
index 0e9598f43dae19a4fc062e8f62482faf33d5e216..0000000000000000000000000000000000000000
Binary files a/files/images/backgrounds/background-caution-button.png and /dev/null differ
diff --git a/files/images/backgrounds/background-caution.png b/files/images/backgrounds/background-caution.png
deleted file mode 100644
index 308589cd6e56788a05c9a6ec38d92d4e57914af2..0000000000000000000000000000000000000000
Binary files a/files/images/backgrounds/background-caution.png and /dev/null differ
diff --git a/files/images/categories/applications-accessories.svg b/files/images/categories/applications-accessories.svg
deleted file mode 100644
index 35527cb7559f1f75bbb93022a06d01090786c78a..0000000000000000000000000000000000000000
--- a/files/images/categories/applications-accessories.svg
+++ /dev/null
@@ -1,533 +0,0 @@
-
-
\ No newline at end of file
diff --git a/files/images/categories/applications-development.svg b/files/images/categories/applications-development.svg
deleted file mode 100644
index f575528941a8d7584b8da0296ce4d081778a2144..0000000000000000000000000000000000000000
--- a/files/images/categories/applications-development.svg
+++ /dev/null
@@ -1,329 +0,0 @@
-
-
-
diff --git a/files/images/categories/applications-games.svg b/files/images/categories/applications-games.svg
deleted file mode 100644
index 1d89e485b67846bc5950f749448c784c84f5dc77..0000000000000000000000000000000000000000
--- a/files/images/categories/applications-games.svg
+++ /dev/null
@@ -1,320 +0,0 @@
-
-
-
diff --git a/files/images/categories/applications-graphics.svg b/files/images/categories/applications-graphics.svg
deleted file mode 100644
index ec544d5a515d4ca8f40d82049ec0c57ce6dcbc8b..0000000000000000000000000000000000000000
--- a/files/images/categories/applications-graphics.svg
+++ /dev/null
@@ -1,547 +0,0 @@
-
-
-
diff --git a/files/images/categories/applications-internet.svg b/files/images/categories/applications-internet.svg
deleted file mode 100644
index ebe3c60b6f00e597340e01eeb4f5b86e0f28b54b..0000000000000000000000000000000000000000
--- a/files/images/categories/applications-internet.svg
+++ /dev/null
@@ -1,623 +0,0 @@
-
-
-
diff --git a/files/images/categories/applications-multimedia.svg b/files/images/categories/applications-multimedia.svg
deleted file mode 100644
index 6844e8db1a8445be853eb102aa6f36c6695ed4af..0000000000000000000000000000000000000000
--- a/files/images/categories/applications-multimedia.svg
+++ /dev/null
@@ -1,498 +0,0 @@
-
-
-
diff --git a/files/images/categories/applications-office.svg b/files/images/categories/applications-office.svg
deleted file mode 100644
index e1b60b47501bbaf22eb196c628b922dd3569ee8a..0000000000000000000000000000000000000000
--- a/files/images/categories/applications-office.svg
+++ /dev/null
@@ -1,616 +0,0 @@
-
-
-
diff --git a/files/images/categories/applications-other.svg b/files/images/categories/applications-other.svg
deleted file mode 100644
index 5e30c277c2be6b6e568c71785777f51e0f4cf24e..0000000000000000000000000000000000000000
--- a/files/images/categories/applications-other.svg
+++ /dev/null
@@ -1,377 +0,0 @@
-
-
-
diff --git a/files/images/categories/applications-system.svg b/files/images/categories/applications-system.svg
deleted file mode 100644
index 9d767742df480a954379c964cee3a74b973da415..0000000000000000000000000000000000000000
--- a/files/images/categories/applications-system.svg
+++ /dev/null
@@ -1,247 +0,0 @@
-
-
-
diff --git a/files/images/categories/preferences-desktop-peripherals.svg b/files/images/categories/preferences-desktop-peripherals.svg
deleted file mode 100644
index 1e1663ab179e3d01f7b7d4bd09f7f9028e9dead4..0000000000000000000000000000000000000000
--- a/files/images/categories/preferences-desktop-peripherals.svg
+++ /dev/null
@@ -1,848 +0,0 @@
-
-
-
diff --git a/files/images/categories/preferences-desktop.svg b/files/images/categories/preferences-desktop.svg
deleted file mode 100644
index a0fd144942649117847fde9ff20847cc910fd04a..0000000000000000000000000000000000000000
--- a/files/images/categories/preferences-desktop.svg
+++ /dev/null
@@ -1,777 +0,0 @@
-
-
-
diff --git a/files/images/categories/preferences-system.svg b/files/images/categories/preferences-system.svg
deleted file mode 100644
index d41028fc8dda63b22175daccc903bea501337bc2..0000000000000000000000000000000000000000
--- a/files/images/categories/preferences-system.svg
+++ /dev/null
@@ -1,398 +0,0 @@
-
-
-
diff --git a/files/images/contrib/slugs.png b/files/images/contrib/slugs.png
deleted file mode 100644
index 4af15559a963287e696c51a6b00c6b5dd5163c6b..0000000000000000000000000000000000000000
Binary files a/files/images/contrib/slugs.png and /dev/null differ
diff --git a/files/images/control/emergency-button-gradient.png b/files/images/control/emergency-button-gradient.png
deleted file mode 100644
index c9c98f43e24417374efea519b9c179298a880ef5..0000000000000000000000000000000000000000
Binary files a/files/images/control/emergency-button-gradient.png and /dev/null differ
diff --git a/files/images/control/emergency-button-simple.png b/files/images/control/emergency-button-simple.png
deleted file mode 100644
index d69eb1370ae782e133e33be428a9653c8bee5591..0000000000000000000000000000000000000000
Binary files a/files/images/control/emergency-button-simple.png and /dev/null differ
diff --git a/files/images/control/emergency-button.png b/files/images/control/emergency-button.png
deleted file mode 100644
index 5cbacdf11bdbe994eb25d11820c3445a4c8fea7a..0000000000000000000000000000000000000000
Binary files a/files/images/control/emergency-button.png and /dev/null differ
diff --git a/files/images/control/emergency-button.svg b/files/images/control/emergency-button.svg
deleted file mode 100644
index 69753fa988bd1a5e141d4688eaba68b76588d9d6..0000000000000000000000000000000000000000
--- a/files/images/control/emergency-button.svg
+++ /dev/null
@@ -1,218 +0,0 @@
-
-
-
diff --git a/files/images/control/empty-button.png b/files/images/control/empty-button.png
deleted file mode 100644
index 2215be7206b1da24daea58e3af292e79c41c6057..0000000000000000000000000000000000000000
Binary files a/files/images/control/empty-button.png and /dev/null differ
diff --git a/files/images/control/empty-button.svg b/files/images/control/empty-button.svg
deleted file mode 100644
index 48c04ddf98ae852bd8b3fecf6b478a233018aa19..0000000000000000000000000000000000000000
--- a/files/images/control/empty-button.svg
+++ /dev/null
@@ -1,212 +0,0 @@
-
-
-
diff --git a/files/images/control/empty-emergency-button-v2.svg b/files/images/control/empty-emergency-button-v2.svg
deleted file mode 100644
index 74589e5dc56859c97b0ff6142b426c701712e5f3..0000000000000000000000000000000000000000
--- a/files/images/control/empty-emergency-button-v2.svg
+++ /dev/null
@@ -1,319 +0,0 @@
-
-
-
diff --git a/files/images/control/empty-emergency-button.svg b/files/images/control/empty-emergency-button.svg
deleted file mode 100644
index dba3070e2630c471fabfb8548448264871ec7e13..0000000000000000000000000000000000000000
--- a/files/images/control/empty-emergency-button.svg
+++ /dev/null
@@ -1,239 +0,0 @@
-
-
-
diff --git a/files/images/control/land-button.svg b/files/images/control/land-button.svg
deleted file mode 100644
index 097f2fc7143392fe1aa833421af6fdaaa058935c..0000000000000000000000000000000000000000
--- a/files/images/control/land-button.svg
+++ /dev/null
@@ -1,174 +0,0 @@
-
-
-
diff --git a/files/images/devices/AC-0004-11-2.jpg b/files/images/devices/AC-0004-11-2.jpg
deleted file mode 100644
index 334486b6756e6b2671c1a2dd1099f2c051e4a20c..0000000000000000000000000000000000000000
Binary files a/files/images/devices/AC-0004-11-2.jpg and /dev/null differ
diff --git a/files/images/devices/BR-0004-03-2.jpg b/files/images/devices/BR-0004-03-2.jpg
deleted file mode 100644
index 0126646ef48942d00ed34f2b0e720b26a308f155..0000000000000000000000000000000000000000
Binary files a/files/images/devices/BR-0004-03-2.jpg and /dev/null differ
diff --git a/files/images/devices/BR-0016-01-3T.jpg b/files/images/devices/BR-0016-01-3T.jpg
deleted file mode 100644
index 534eba3f0b7cfa4f16f7aeab02f410bc489bc50b..0000000000000000000000000000000000000000
Binary files a/files/images/devices/BR-0016-01-3T.jpg and /dev/null differ
diff --git a/files/images/devices/BR-APMPWRDEAN-2.jpg b/files/images/devices/BR-APMPWRDEAN-2.jpg
deleted file mode 100644
index 62a6a83b8380283f52d1b9981cd960711a2e8630..0000000000000000000000000000000000000000
Binary files a/files/images/devices/BR-APMPWRDEAN-2.jpg and /dev/null differ
diff --git a/files/images/devices/BR-HMC5883-01-2.jpg b/files/images/devices/BR-HMC5883-01-2.jpg
deleted file mode 100644
index f695795f6f93082d0e4a9b588aef3e9f515ff133..0000000000000000000000000000000000000000
Binary files a/files/images/devices/BR-HMC5883-01-2.jpg and /dev/null differ
diff --git a/files/images/devices/MinimOSD.jpg b/files/images/devices/MinimOSD.jpg
deleted file mode 100644
index b24c7e4a9759278435edcefe778e51765177d26e..0000000000000000000000000000000000000000
Binary files a/files/images/devices/MinimOSD.jpg and /dev/null differ
diff --git a/files/images/devices/Shutter.png b/files/images/devices/Shutter.png
deleted file mode 100644
index 0362734d5762771d2b98bcfe55fe6c08138cf412..0000000000000000000000000000000000000000
Binary files a/files/images/devices/Shutter.png and /dev/null differ
diff --git a/files/images/devices/audio-card.svg b/files/images/devices/audio-card.svg
deleted file mode 100644
index d7816a85c42bafd8d81028b28f3eccf56262ee3b..0000000000000000000000000000000000000000
--- a/files/images/devices/audio-card.svg
+++ /dev/null
@@ -1,434 +0,0 @@
-
-
-
diff --git a/files/images/devices/audio-input-microphone.svg b/files/images/devices/audio-input-microphone.svg
deleted file mode 100644
index d31409c4e5b99a645e4ea063fe0d5f45d9017fb0..0000000000000000000000000000000000000000
--- a/files/images/devices/audio-input-microphone.svg
+++ /dev/null
@@ -1,501 +0,0 @@
-
-
-
diff --git a/files/images/devices/battery.svg b/files/images/devices/battery.svg
deleted file mode 100644
index 30695dda0f34bb76235912d83d8c3ae0465f3d42..0000000000000000000000000000000000000000
--- a/files/images/devices/battery.svg
+++ /dev/null
@@ -1,348 +0,0 @@
-
-
-
diff --git a/files/images/devices/camera-photo.svg b/files/images/devices/camera-photo.svg
deleted file mode 100644
index 4911410136f7bb65905d063ea691aa52d1ab9603..0000000000000000000000000000000000000000
--- a/files/images/devices/camera-photo.svg
+++ /dev/null
@@ -1,681 +0,0 @@
-
-
-
diff --git a/files/images/devices/camera-video.svg b/files/images/devices/camera-video.svg
deleted file mode 100644
index e24713457fbfefeb7dc0416a1a6882a0659d5e5c..0000000000000000000000000000000000000000
--- a/files/images/devices/camera-video.svg
+++ /dev/null
@@ -1,1257 +0,0 @@
-
-
-
diff --git a/files/images/devices/cameraGimalPitch1.png b/files/images/devices/cameraGimalPitch1.png
deleted file mode 100644
index 158429893b5aa82506f4ca902b7d8acdec03253f..0000000000000000000000000000000000000000
Binary files a/files/images/devices/cameraGimalPitch1.png and /dev/null differ
diff --git a/files/images/devices/cameraGimalRoll1.png b/files/images/devices/cameraGimalRoll1.png
deleted file mode 100644
index bff678c9e7adc2264732f2df1d2bdfd29e7e3368..0000000000000000000000000000000000000000
Binary files a/files/images/devices/cameraGimalRoll1.png and /dev/null differ
diff --git a/files/images/devices/cameraGimalYaw.png b/files/images/devices/cameraGimalYaw.png
deleted file mode 100644
index 0375add2c31bf2c7a5926ce864037bd43a550068..0000000000000000000000000000000000000000
Binary files a/files/images/devices/cameraGimalYaw.png and /dev/null differ
diff --git a/files/images/devices/computer.svg b/files/images/devices/computer.svg
deleted file mode 100644
index 4a63d5d77626190bf2924a6a342dc4cf43281543..0000000000000000000000000000000000000000
--- a/files/images/devices/computer.svg
+++ /dev/null
@@ -1,740 +0,0 @@
-
-
-
diff --git a/files/images/devices/drive-harddisk.svg b/files/images/devices/drive-harddisk.svg
deleted file mode 100644
index 2d38ac6b8ae1a2fd5c1d69101a01564b401f7223..0000000000000000000000000000000000000000
--- a/files/images/devices/drive-harddisk.svg
+++ /dev/null
@@ -1,471 +0,0 @@
-
-
-
diff --git a/files/images/devices/drive-optical.svg b/files/images/devices/drive-optical.svg
deleted file mode 100644
index 644ef8ae1e1ca5cdd60372f4e130b450b98d7624..0000000000000000000000000000000000000000
--- a/files/images/devices/drive-optical.svg
+++ /dev/null
@@ -1,515 +0,0 @@
-
-
-
diff --git a/files/images/devices/drive-removable-media.svg b/files/images/devices/drive-removable-media.svg
deleted file mode 100644
index 2b1987414535b09053e0bea77381ac7756fd7782..0000000000000000000000000000000000000000
--- a/files/images/devices/drive-removable-media.svg
+++ /dev/null
@@ -1,392 +0,0 @@
-
-
-
diff --git a/files/images/devices/input-gaming.svg b/files/images/devices/input-gaming.svg
deleted file mode 100644
index 5909a53eaf31598807aa50b864d7875dbbe7ded1..0000000000000000000000000000000000000000
--- a/files/images/devices/input-gaming.svg
+++ /dev/null
@@ -1,530 +0,0 @@
-
-
-
diff --git a/files/images/devices/input-keyboard.svg b/files/images/devices/input-keyboard.svg
deleted file mode 100644
index 534dd384f436abdcf2c8cf8383c5c2cf713a4b43..0000000000000000000000000000000000000000
--- a/files/images/devices/input-keyboard.svg
+++ /dev/null
@@ -1,838 +0,0 @@
-
-
-
diff --git a/files/images/devices/input-mouse.svg b/files/images/devices/input-mouse.svg
deleted file mode 100644
index 2fda0182a967487c041ba0036704bdf1fba8e396..0000000000000000000000000000000000000000
--- a/files/images/devices/input-mouse.svg
+++ /dev/null
@@ -1,343 +0,0 @@
-
-
-
diff --git a/files/images/devices/media-flash.svg b/files/images/devices/media-flash.svg
deleted file mode 100644
index 13f910fdd820793cc23d33a378c0dc81f989db71..0000000000000000000000000000000000000000
--- a/files/images/devices/media-flash.svg
+++ /dev/null
@@ -1,477 +0,0 @@
-
-
-
diff --git a/files/images/devices/media-floppy.svg b/files/images/devices/media-floppy.svg
deleted file mode 100644
index 6700163d9f7f3c357a14b7a4f2b6f4fe50a396d5..0000000000000000000000000000000000000000
--- a/files/images/devices/media-floppy.svg
+++ /dev/null
@@ -1,350 +0,0 @@
-
-
-
diff --git a/files/images/devices/media-optical.svg b/files/images/devices/media-optical.svg
deleted file mode 100644
index 34aa13f56a6d25d7695fedb7cbec999e5fd4d710..0000000000000000000000000000000000000000
--- a/files/images/devices/media-optical.svg
+++ /dev/null
@@ -1,722 +0,0 @@
-
-
-
diff --git a/files/images/devices/multimedia-player.svg b/files/images/devices/multimedia-player.svg
deleted file mode 100644
index 01bf244efed8713ba3739f400e076f5c39e4809b..0000000000000000000000000000000000000000
--- a/files/images/devices/multimedia-player.svg
+++ /dev/null
@@ -1,693 +0,0 @@
-
-
-
diff --git a/files/images/devices/network-wired.svg b/files/images/devices/network-wired.svg
deleted file mode 100644
index bfa56d582764a5aad85b463e4939564f2e316ea1..0000000000000000000000000000000000000000
--- a/files/images/devices/network-wired.svg
+++ /dev/null
@@ -1,465 +0,0 @@
-
-
-
diff --git a/files/images/devices/network-wireless.svg b/files/images/devices/network-wireless.svg
deleted file mode 100644
index e52d2bbcf000e694fc2f44c7a57a094ccff94242..0000000000000000000000000000000000000000
--- a/files/images/devices/network-wireless.svg
+++ /dev/null
@@ -1,325 +0,0 @@
-
-
-
diff --git a/files/images/devices/printer.svg b/files/images/devices/printer.svg
deleted file mode 100644
index 4c702dc48e2f24716c7bb2d8bf19567fea12429a..0000000000000000000000000000000000000000
--- a/files/images/devices/printer.svg
+++ /dev/null
@@ -1,502 +0,0 @@
-
-
-
diff --git a/files/images/devices/video-display.svg b/files/images/devices/video-display.svg
deleted file mode 100644
index 26fe3a9e8061d361096255a2f913ea4adf81ab6f..0000000000000000000000000000000000000000
--- a/files/images/devices/video-display.svg
+++ /dev/null
@@ -1,488 +0,0 @@
-
-
-
diff --git a/files/images/earth-singlesystem.html b/files/images/earth-singlesystem.html
deleted file mode 100644
index 5091ce347d391c2ac7a7d1bf0ada9520905db346..0000000000000000000000000000000000000000
--- a/files/images/earth-singlesystem.html
+++ /dev/null
@@ -1,759 +0,0 @@
-
-
-
-
-
-
-
- QGroundControl Google Earth View
-
-
-
-
-
-
-
-
-
-