diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 74b6dc98c1f3e73149888e4adf795b03a4dea4d2..fd8501cb9efecb43568262e6ed34727385d250fb 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -262,6 +262,7 @@ HEADERS += \ src/HomePositionManager.h \ src/Joystick/Joystick.h \ src/Joystick/JoystickManager.h \ + src/VehicleSetup/JoystickConfigController.h \ src/FollowMe/FollowMe.h \ src/PositionManager/SimulatedPosition.h \ src/JsonHelper.h \ @@ -309,6 +310,10 @@ HEADERS += \ src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h \ src/PositionManager/PositionManager.h +AndroidBuild { +HEADERS += \ +} + DebugBuild { HEADERS += \ src/comm/MockLink.h \ @@ -341,6 +346,7 @@ HEADERS += \ src/comm/QGCHilLink.h \ src/comm/QGCJSBSimLink.h \ src/comm/QGCXPlaneLink.h \ + src/Joystick/JoystickSDL.h \ src/QGCFileDialog.h \ src/QGCMessageBox.h \ src/uas/FileManager.h \ @@ -385,7 +391,6 @@ HEADERS += \ src/GPS/GPSManager.h \ src/GPS/GPSPositionMessage.h \ src/GPS/GPSProvider.h \ - src/VehicleSetup/JoystickConfigController.h \ src/ViewWidgets/CustomCommandWidget.h \ src/ViewWidgets/CustomCommandWidgetController.h \ src/ViewWidgets/LogDownload.h \ @@ -398,6 +403,7 @@ iOSBuild { src/audio/QGCAudioWorker_iOS.mm \ src/MobileScreenMgr.mm \ } + AndroidBuild { SOURCES += src/MobileScreenMgr.cc \ } @@ -418,6 +424,7 @@ SOURCES += \ src/HomePositionManager.cc \ src/Joystick/Joystick.cc \ src/Joystick/JoystickManager.cc \ + src/VehicleSetup/JoystickConfigController.cc \ src/JsonHelper.cc \ src/FollowMe/FollowMe.cc \ src/LogCompressor.cc \ @@ -495,6 +502,7 @@ SOURCES += \ src/comm/QGCFlightGearLink.cc \ src/comm/QGCJSBSimLink.cc \ src/comm/QGCXPlaneLink.cc \ + src/Joystick/JoystickSDL.cc \ src/ui/HILDockWidget.cc \ src/ui/linechart/ChartPlot.cc \ src/ui/linechart/IncrementalPlot.cc \ @@ -525,7 +533,6 @@ SOURCES += \ src/GPS/RTCM/RTCMMavlink.cc \ src/GPS/GPSManager.cc \ src/GPS/GPSProvider.cc \ - src/VehicleSetup/JoystickConfigController.cc \ src/ViewWidgets/CustomCommandWidget.cc \ src/ViewWidgets/CustomCommandWidgetController.cc \ src/ViewWidgets/LogDownload.cc \ diff --git a/src/GPS/Drivers b/src/GPS/Drivers index 60739aaace1723c700f23b22212696dc75169559..5c1ae956552c3887c5fddd303a8f242efa715333 160000 --- a/src/GPS/Drivers +++ b/src/GPS/Drivers @@ -1 +1 @@ -Subproject commit 60739aaace1723c700f23b22212696dc75169559 +Subproject commit 5c1ae956552c3887c5fddd303a8f242efa715333 diff --git a/src/GPS/GPSProvider.cc b/src/GPS/GPSProvider.cc index 44121945a014a1d06e3163f7683e96fde44f0295..f8c836b489f3ae9551d83ceb4b483b8b93fe57ff 100644 --- a/src/GPS/GPSProvider.cc +++ b/src/GPS/GPSProvider.cc @@ -18,9 +18,25 @@ #include "Drivers/src/gps_helper.h" #include "definitions.h" +//#define SIMULATE_RTCM_OUTPUT //if defined, generate simulated RTCM messages + //additionally make sure to call connectGPS(""), eg. from QGCToolbox.cc + void GPSProvider::run() { +#ifdef SIMULATE_RTCM_OUTPUT + const int fakeMsgLengths[3] = { 30, 170, 240 }; + uint8_t* fakeData = new uint8_t[fakeMsgLengths[2]]; + while (!_requestStop) { + for (int i = 0; i < 3; ++i) { + gotRTCMData((uint8_t*) fakeData, fakeMsgLengths[i]); + msleep(4); + } + msleep(100); + } + delete[] fakeData; +#endif /* SIMULATE_RTCM_OUTPUT */ + if (_serial) delete _serial; _serial = new QSerialPort(); @@ -125,10 +141,11 @@ int GPSProvider::callback(GPSCallbackType type, void *data1, int data2) { switch (type) { case GPSCallbackType::readDeviceData: { - int timeout = *((int *) data1); - if (!_serial->waitForReadyRead(timeout)) - return 0; //timeout - msleep(10); //give some more time to buffer data + if (_serial->bytesAvailable() == 0) { + int timeout = *((int *) data1); + if (!_serial->waitForReadyRead(timeout)) + return 0; //timeout + } return (int)_serial->read((char*) data1, data2); } case GPSCallbackType::writeDeviceData: diff --git a/src/GPS/RTCM/RTCMMavlink.cc b/src/GPS/RTCM/RTCMMavlink.cc index 87b0d23aad95f39ff55f9403c7f4efa139696ebd..3b570d5382ea9ae990b010304cd98b430fefb9e1 100644 --- a/src/GPS/RTCM/RTCMMavlink.cc +++ b/src/GPS/RTCM/RTCMMavlink.cc @@ -11,7 +11,6 @@ #include "RTCMMavlink.h" #include "MultiVehicleManager.h" -#include "MAVLinkProtocol.h" #include "Vehicle.h" #include @@ -24,8 +23,6 @@ RTCMMavlink::RTCMMavlink(QGCToolbox& toolbox) void RTCMMavlink::RTCMDataUpdate(QByteArray message) { - Q_ASSERT(message.size() <= 110); //mavlink message uses a fixed-size buffer - /* statistics */ _bandwidthByteCounter += message.size(); qint64 elapsed = _bandwidthTimer.elapsed(); @@ -34,19 +31,38 @@ void RTCMMavlink::RTCMDataUpdate(QByteArray message) _bandwidthTimer.restart(); _bandwidthByteCounter = 0; } - QmlObjectListModel& vehicles = *_toolbox.multiVehicleManager()->vehicles(); - MAVLinkProtocol* mavlinkProtocol = _toolbox.mavlinkProtocol(); - mavlink_gps_inject_data_t mavlinkRtcmData; - memset(&mavlinkRtcmData, 0, sizeof(mavlink_gps_inject_data_t)); - mavlinkRtcmData.len = message.size(); - memcpy(&mavlinkRtcmData.data, message.data(), message.size()); + const int maxMessageLength = MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN; + mavlink_gps_rtcm_data_t mavlinkRtcmData; + memset(&mavlinkRtcmData, 0, sizeof(mavlink_gps_rtcm_data_t)); + if (message.size() < maxMessageLength) { + mavlinkRtcmData.len = message.size(); + memcpy(&mavlinkRtcmData.data, message.data(), message.size()); + sendMessageToVehicle(mavlinkRtcmData); + } else { + //we need to fragment + int start = 0; + while (start < message.size()) { + int length = std::min(message.size() - start, maxMessageLength); + mavlinkRtcmData.flags = 1; //fragmented + mavlinkRtcmData.len = length; + memcpy(&mavlinkRtcmData.data, message.data() + start, length); + sendMessageToVehicle(mavlinkRtcmData); + start += length; + } + } +} + +void RTCMMavlink::sendMessageToVehicle(const mavlink_gps_rtcm_data_t& msg) +{ + QmlObjectListModel& vehicles = *_toolbox.multiVehicleManager()->vehicles(); + MAVLinkProtocol* mavlinkProtocol = _toolbox.mavlinkProtocol(); for (int i = 0; i < vehicles.count(); i++) { Vehicle* vehicle = qobject_cast(vehicles[i]); mavlink_message_t message; - mavlink_msg_gps_inject_data_encode(mavlinkProtocol->getSystemId(), - mavlinkProtocol->getComponentId(), &message, &mavlinkRtcmData); + mavlink_msg_gps_rtcm_data_encode(mavlinkProtocol->getSystemId(), + mavlinkProtocol->getComponentId(), &message, &msg); vehicle->sendMessage(message); } } diff --git a/src/GPS/RTCM/RTCMMavlink.h b/src/GPS/RTCM/RTCMMavlink.h index be780f4d75c30e35706d59f059d04e50e5ab88bc..6c59974e38809e2f72f0b6c9d97d9946ff01cd89 100644 --- a/src/GPS/RTCM/RTCMMavlink.h +++ b/src/GPS/RTCM/RTCMMavlink.h @@ -14,6 +14,7 @@ #include #include "QGCToolbox.h" +#include "MAVLinkProtocol.h" /** ** class RTCMMavlink @@ -30,6 +31,8 @@ public slots: void RTCMDataUpdate(QByteArray message); private: + void sendMessageToVehicle(const mavlink_gps_rtcm_data_t& msg); + QGCToolbox& _toolbox; QElapsedTimer _bandwidthTimer; int _bandwidthByteCounter = 0; diff --git a/src/GPS/definitions.h b/src/GPS/definitions.h index b28351e3e5d1529495aabca0d76de981e4f27b62..ca655d0b79ea621a8698952941a53e32ce4887be 100644 --- a/src/GPS/definitions.h +++ b/src/GPS/definitions.h @@ -41,6 +41,8 @@ #include +#define GPS_READ_BUFFER_SIZE 1024 + #define GPS_INFO(...) qInfo(__VA_ARGS__) #define GPS_WARN(...) qWarning(__VA_ARGS__) #define GPS_ERR(...) qCritical(__VA_ARGS__) @@ -59,7 +61,9 @@ public: static void usleep(unsigned long usecs) { QThread::usleep(usecs); } }; -#define usleep Sleeper::usleep +static inline void usleep(unsigned long usecs) { + Sleeper::usleep(usecs); +} typedef uint64_t gps_abstime; diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index 36d5d17a77d07b90260b78897467cee66625878b..9492dbed8304d27611cbf5f190af364afbe74695 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -15,14 +15,6 @@ #include -#ifndef __mobile__ - #ifdef Q_OS_MAC - #include - #else - #include - #endif -#endif - QGC_LOGGING_CATEGORY(JoystickLog, "JoystickLog") QGC_LOGGING_CATEGORY(JoystickValuesLog, "JoystickValuesLog") @@ -38,10 +30,8 @@ const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = { "ThrottleAxis" }; -Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlIndex, MultiVehicleManager* multiVehicleManager) -#ifndef __mobile__ - : _sdlIndex(sdlIndex) - , _exitThread(false) +Joystick::Joystick(const QString& name, int axisCount, int buttonCount, MultiVehicleManager* multiVehicleManager) + : _exitThread(false) , _name(name) , _axisCount(axisCount) , _buttonCount(buttonCount) @@ -55,15 +45,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlI , _activeVehicle(NULL) , _pollingStartedForCalibration(false) , _multiVehicleManager(multiVehicleManager) -#endif // __mobile__ { -#ifdef __mobile__ - Q_UNUSED(name) - Q_UNUSED(axisCount) - Q_UNUSED(buttonCount) - Q_UNUSED(sdlIndex) - Q_UNUSED(multiVehicleManager) -#else _rgAxisValues = new int[_axisCount]; _rgCalibration = new Calibration_t[_axisCount]; _rgButtonValues = new bool[_buttonCount]; @@ -77,21 +59,16 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlI } _loadSettings(); -#endif // __mobile__ } Joystick::~Joystick() { -#ifndef __mobile__ delete _rgAxisValues; delete _rgCalibration; delete _rgButtonValues; delete _rgButtonActions; -#endif } -#ifndef __mobile__ - void Joystick::_loadSettings(void) { QSettings settings; @@ -244,19 +221,14 @@ float Joystick::_adjustRange(int value, Calibration_t calibration) void Joystick::run(void) { - SDL_Joystick* sdlJoystick = SDL_JoystickOpen(_sdlIndex); - - if (!sdlJoystick) { - qCWarning(JoystickLog) << "SDL_JoystickOpen failed:" << SDL_GetError(); - return; - } + _open(); while (!_exitThread) { - SDL_JoystickUpdate(); + _update(); // Update axes for (int axisIndex=0; axisIndex<_axisCount; axisIndex++) { - int newAxisValue = SDL_JoystickGetAxis(sdlJoystick, axisIndex); + int newAxisValue = _getAxis(axisIndex); // Calibration code requires signal to be emitted even if value hasn't changed _rgAxisValues[axisIndex] = newAxisValue; emit rawAxisValueChanged(axisIndex, newAxisValue); @@ -264,7 +236,7 @@ void Joystick::run(void) // Update buttons for (int buttonIndex=0; buttonIndex<_buttonCount; buttonIndex++) { - bool newButtonValue = !!SDL_JoystickGetButton(sdlJoystick, buttonIndex); + bool newButtonValue = _getButton(buttonIndex); if (newButtonValue != _rgButtonValues[buttonIndex]) { _rgButtonValues[buttonIndex] = newButtonValue; emit rawButtonPressedChanged(buttonIndex, newButtonValue); @@ -349,7 +321,7 @@ void Joystick::run(void) QGC::SLEEP::msleep(40); } - SDL_JoystickClose(sdlJoystick); + _close(); } void Joystick::startPolling(Vehicle* vehicle) @@ -566,4 +538,3 @@ bool Joystick::_validButton(int button) return button >= 0 && button < _buttonCount; } -#endif // __mobile__ diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index 2ad575c61c1aa28f8c81e3fbbb358c4c69b13bc2..c4a100804a721c929bb5646cb7151e50d55852f9 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -26,9 +26,9 @@ class Joystick : public QThread Q_OBJECT public: - Joystick(const QString& name, int axisCount, int buttonCount, int sdlIndex, MultiVehicleManager* multiVehicleManager); + Joystick(const QString& name, int axisCount, int buttonCount, MultiVehicleManager* multiVehicleManager); ~Joystick(); - + typedef struct { int min; int max; @@ -50,7 +50,6 @@ public: ThrottleModeMax } ThrottleMode_t; -#ifndef __mobile__ Q_PROPERTY(QString name READ name CONSTANT) Q_PROPERTY(bool calibrated MEMBER _calibrated NOTIFY calibratedChanged) @@ -124,7 +123,7 @@ signals: void buttonActionTriggered(int action); -private: +protected: void _saveSettings(void); void _loadSettings(void); float _adjustRange(int value, Calibration_t calibration); @@ -132,11 +131,18 @@ private: bool _validAxis(int axis); bool _validButton(int button); +private: + virtual bool _open() = 0; + virtual void _close() = 0; + virtual bool _update() = 0; + + virtual bool _getButton(int i) = 0; + virtual int _getAxis(int i) = 0; + // Override from QThread virtual void run(void); -private: - int _sdlIndex; ///< Index for SDL_JoystickOpen +protected: bool _exitThread; ///< true: signal thread to exit @@ -161,7 +167,6 @@ private: bool _pollingStartedForCalibration; MultiVehicleManager* _multiVehicleManager; -#endif // __mobile__ private: static const char* _rgFunctionSettingsKey[maxFunction]; diff --git a/src/Joystick/JoystickManager.cc b/src/Joystick/JoystickManager.cc index 9bfc3dc6bd040012151a8e1bc58207d9fe1008c0..1ef0fc607b73b83326bf5724f84f91958aa2214a 100644 --- a/src/Joystick/JoystickManager.cc +++ b/src/Joystick/JoystickManager.cc @@ -14,11 +14,15 @@ #include #ifndef __mobile__ - #ifdef Q_OS_MAC - #include - #else - #include - #endif + #include "JoystickSDL.h" + #define __sdljoystick__ +#endif + +#ifdef __android__ + /* + * Android Joystick not yet supported + * #include "JoystickAndroid.h" + */ #endif QGC_LOGGING_CATEGORY(JoystickManagerLog, "JoystickManagerLog") @@ -31,7 +35,15 @@ JoystickManager::JoystickManager(QGCApplication* app) , _activeJoystick(NULL) , _multiVehicleManager(NULL) { - +} + +JoystickManager::~JoystickManager() { + QMap::iterator i; + for (i = _name2JoystickMap.begin(); i != _name2JoystickMap.end(); ++i) { + qDebug() << "Releasing joystick:" << i.key(); + delete i.value(); + } + qDebug() << "Done"; } void JoystickManager::setToolbox(QGCToolbox *toolbox) @@ -42,33 +54,13 @@ void JoystickManager::setToolbox(QGCToolbox *toolbox) QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); -#ifndef __mobile__ - if (SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_NOPARACHUTE) < 0) { - qWarning() << "Couldn't initialize SimpleDirectMediaLayer:" << SDL_GetError(); - return; - } - - // Load available joysticks - - qCDebug(JoystickManagerLog) << "Available joysticks"; - - for (int i=0; iname()); -#endif } Joystick* JoystickManager::activeJoystick(void) @@ -104,9 +93,6 @@ Joystick* JoystickManager::activeJoystick(void) void JoystickManager::setActiveJoystick(Joystick* joystick) { -#ifdef __mobile__ - Q_UNUSED(joystick) -#else QSettings settings; if (!_name2JoystickMap.contains(joystick->name())) { @@ -125,7 +111,6 @@ void JoystickManager::setActiveJoystick(Joystick* joystick) emit activeJoystickChanged(_activeJoystick); emit activeJoystickNameChanged(_activeJoystick->name()); -#endif } QVariantList JoystickManager::joysticks(void) @@ -146,11 +131,7 @@ QStringList JoystickManager::joystickNames(void) QString JoystickManager::activeJoystickName(void) { -#ifdef __mobile__ - return QString(); -#else return _activeJoystick ? _activeJoystick->name() : QString(); -#endif } void JoystickManager::setActiveJoystickName(const QString& name) diff --git a/src/Joystick/JoystickManager.h b/src/Joystick/JoystickManager.h index abebc50204b994c26cbb3a4249d230c713ff7718..96f22f80b923514544fdd3f2224e36f25130f363 100644 --- a/src/Joystick/JoystickManager.h +++ b/src/Joystick/JoystickManager.h @@ -28,6 +28,7 @@ class JoystickManager : public QGCTool public: JoystickManager(QGCApplication* app); + ~JoystickManager(); /// List of available joysticks Q_PROPERTY(QVariantList joysticks READ joysticks CONSTANT) diff --git a/src/Joystick/JoystickSDL.cc b/src/Joystick/JoystickSDL.cc new file mode 100644 index 0000000000000000000000000000000000000000..14bdd0cf6a5031e71d8a7a065aae4adcca139a4d --- /dev/null +++ b/src/Joystick/JoystickSDL.cc @@ -0,0 +1,73 @@ +#include "JoystickSDL.h" + +#include "QGCApplication.h" + +#include + +JoystickSDL::JoystickSDL(const QString& name, int axisCount, int buttonCount, int index, MultiVehicleManager* multiVehicleManager) + : Joystick(name,axisCount,buttonCount,multiVehicleManager) + , _index(index) +{ +} + +QMap JoystickSDL::discover(MultiVehicleManager* _multiVehicleManager) { + static QMap ret; + + if (SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_NOPARACHUTE) < 0) { + qWarning() << "Couldn't initialize SimpleDirectMediaLayer:" << SDL_GetError(); + return ret; + } + + // Load available joysticks + + qCDebug(JoystickLog) << "Available joysticks"; + + for (int i=0; i +#else + #include +#endif + + +class JoystickSDL : public Joystick +{ +public: + JoystickSDL(const QString& name, int axisCount, int buttonCount, int index, MultiVehicleManager* multiVehicleManager); + + static QMap discover(MultiVehicleManager* _multiVehicleManager); + +private: + bool _open() final; + void _close() final; + bool _update() final; + + bool _getButton(int i) final; + int _getAxis(int i) final; + + SDL_Joystick *sdlJoystick; + int _index; ///< Index for SDL_JoystickOpen +}; + +#endif // JOYSTICKSDL_H diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 38c4bd098c25947f6c2c71dc1f4be7a25ed7d4bc..db0acc399ffa133face0e7d127907d87c3785729 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -72,6 +72,7 @@ #include "PX4/PX4FirmwarePlugin.h" #include "Vehicle.h" #include "MavlinkQmlSingleton.h" +#include "JoystickConfigController.h" #include "JoystickManager.h" #include "QmlObjectListModel.h" #include "MissionManager.h" @@ -102,7 +103,6 @@ #include "QGCFileDialog.h" #include "QGCMessageBox.h" #include "FirmwareUpgradeController.h" - #include "JoystickConfigController.h" #include "MainWindow.h" #endif @@ -386,12 +386,11 @@ void QGCApplication::_initCommon(void) qmlRegisterType ("QGroundControl.Controllers", 1, 0, "ValuesWidgetController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "QGCMobileFileDialogController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "RCChannelMonitorController"); - + qmlRegisterType ("QGroundControl.Controllers", 1, 0, "JoystickConfigController"); #ifndef __mobile__ qmlRegisterType ("QGroundControl.Controllers", 1, 0, "ViewWidgetController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "CustomCommandWidgetController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "FirmwareUpgradeController"); - qmlRegisterType ("QGroundControl.Controllers", 1, 0, "JoystickConfigController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "LogDownloadController"); #endif diff --git a/src/Vehicle/GPSFact.json b/src/Vehicle/GPSFact.json index 73046fb2f4ac3db04b6bc4d065b41e41d87e6229..826ae1d6d6a60a7af7eec194006a58e1691918f7 100644 --- a/src/Vehicle/GPSFact.json +++ b/src/Vehicle/GPSFact.json @@ -25,8 +25,8 @@ "name": "lock", "shortDescription": "GPS Lock", "type": "uint32", - "enumStrings": "None,None,2D Lock,3D Lock,3D DGPS Lock,3D RTK GPS Lock", - "enumValues": "0,1,2,3,4,5", + "enumStrings": "None,None,2D Lock,3D Lock,3D DGPS Lock,3D RTK GPS Lock (float),3D RTK GPS Lock (fixed)", + "enumValues": "0,1,2,3,4,5,6", "decimalPlaces": 0 }, { diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index b2ab02024c1f6624688997b80fecd01179fb9f97..b9fdaec03263f299b0b78255e21900d40df85284 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1111,7 +1111,6 @@ void Vehicle::setJoystickEnabled(bool enabled) void Vehicle::_startJoystick(bool start) { -#ifndef __mobile__ Joystick* joystick = _joystickManager->activeJoystick(); if (joystick) { if (start) { @@ -1122,9 +1121,6 @@ void Vehicle::_startJoystick(bool start) joystick->stopPolling(); } } -#else - Q_UNUSED(start); -#endif } bool Vehicle::active(void)