Browse Source

[LP Support] - Implement support on QT side, handle autoconnect

QGC4.4
Alessio Morale 9 years ago
parent
commit
43e3af27f4
  1. 39
      src/comm/LinkManager.cc
  2. 28
      src/comm/LinkManager.h
  3. 15
      src/comm/QGCSerialPortInfo.cc
  4. 7
      src/comm/QGCSerialPortInfo.h
  5. 5
      src/ui/preferences/GeneralSettings.qml

39
src/comm/LinkManager.cc

@ -40,13 +40,14 @@
QGC_LOGGING_CATEGORY(LinkManagerLog, "LinkManagerLog") QGC_LOGGING_CATEGORY(LinkManagerLog, "LinkManagerLog")
QGC_LOGGING_CATEGORY(LinkManagerVerboseLog, "LinkManagerVerboseLog") QGC_LOGGING_CATEGORY(LinkManagerVerboseLog, "LinkManagerVerboseLog")
const char* LinkManager::_settingsGroup = "LinkManager"; const char* LinkManager::_settingsGroup = "LinkManager";
const char* LinkManager::_autoconnectUDPKey = "AutoconnectUDP"; const char* LinkManager::_autoconnectUDPKey = "AutoconnectUDP";
const char* LinkManager::_autoconnectPixhawkKey = "AutoconnectPixhawk"; const char* LinkManager::_autoconnectPixhawkKey = "AutoconnectPixhawk";
const char* LinkManager::_autoconnect3DRRadioKey = "Autoconnect3DRRadio"; const char* LinkManager::_autoconnect3DRRadioKey = "Autoconnect3DRRadio";
const char* LinkManager::_autoconnectPX4FlowKey = "AutoconnectPX4Flow"; const char* LinkManager::_autoconnectPX4FlowKey = "AutoconnectPX4Flow";
const char* LinkManager::_autoconnectRTKGPSKey = "AutoconnectRTKGPS"; const char* LinkManager::_autoconnectRTKGPSKey = "AutoconnectRTKGPS";
const char* LinkManager::_defaultUPDLinkName = "Default UDP Link"; const char* LinkManager::_autoconnectLibrePilotKey = "AutoconnectLibrePilot";
const char* LinkManager::_defaultUPDLinkName = "Default UDP Link";
const int LinkManager::_autoconnectUpdateTimerMSecs = 1000; const int LinkManager::_autoconnectUpdateTimerMSecs = 1000;
#ifdef Q_OS_WIN #ifdef Q_OS_WIN
@ -68,6 +69,7 @@ LinkManager::LinkManager(QGCApplication* app)
, _autoconnect3DRRadio(true) , _autoconnect3DRRadio(true)
, _autoconnectPX4Flow(true) , _autoconnectPX4Flow(true)
, _autoconnectRTKGPS(true) , _autoconnectRTKGPS(true)
, _autoconnectLibrePilot(true)
{ {
qmlRegisterUncreatableType<LinkManager> ("QGroundControl", 1, 0, "LinkManager", "Reference only"); qmlRegisterUncreatableType<LinkManager> ("QGroundControl", 1, 0, "LinkManager", "Reference only");
qmlRegisterUncreatableType<LinkConfiguration> ("QGroundControl", 1, 0, "LinkConfiguration", "Reference only"); qmlRegisterUncreatableType<LinkConfiguration> ("QGroundControl", 1, 0, "LinkConfiguration", "Reference only");
@ -76,11 +78,12 @@ LinkManager::LinkManager(QGCApplication* app)
QSettings settings; QSettings settings;
settings.beginGroup(_settingsGroup); settings.beginGroup(_settingsGroup);
_autoconnectUDP = settings.value(_autoconnectUDPKey, true).toBool(); _autoconnectUDP = settings.value(_autoconnectUDPKey, true).toBool();
_autoconnectPixhawk = settings.value(_autoconnectPixhawkKey, true).toBool(); _autoconnectPixhawk = settings.value(_autoconnectPixhawkKey, true).toBool();
_autoconnect3DRRadio = settings.value(_autoconnect3DRRadioKey, true).toBool(); _autoconnect3DRRadio = settings.value(_autoconnect3DRRadioKey, true).toBool();
_autoconnectPX4Flow = settings.value(_autoconnectPX4FlowKey, true).toBool(); _autoconnectPX4Flow = settings.value(_autoconnectPX4FlowKey, true).toBool();
_autoconnectRTKGPS = settings.value(_autoconnectRTKGPSKey, true).toBool(); _autoconnectRTKGPS = settings.value(_autoconnectRTKGPSKey, true).toBool();
_autoconnectLibrePilot = settings.value(_autoconnectLibrePilotKey, true).toBool();
#ifndef __ios__ #ifndef __ios__
_activeLinkCheckTimer.setInterval(_activeLinkCheckTimeoutMSecs); _activeLinkCheckTimer.setInterval(_activeLinkCheckTimeoutMSecs);
@ -564,6 +567,11 @@ void LinkManager::_updateAutoConnectLinks(void)
pSerialConfig = new SerialConfiguration(QString("SiK Radio on %1").arg(portInfo.portName().trimmed())); pSerialConfig = new SerialConfiguration(QString("SiK Radio on %1").arg(portInfo.portName().trimmed()));
} }
break; break;
case QGCSerialPortInfo::BoardTypeLibrePilot:
if (_autoconnectLibrePilot) {
pSerialConfig = new SerialConfiguration(QString("LibrePilot on %1").arg(portInfo.portName().trimmed()));
}
break;
#ifndef __mobile__ #ifndef __mobile__
case QGCSerialPortInfo::BoardTypeRTKGPS: case QGCSerialPortInfo::BoardTypeRTKGPS:
if (_autoconnectRTKGPS && !_toolbox->gpsManager()->connected()) { if (_autoconnectRTKGPS && !_toolbox->gpsManager()->connected()) {
@ -679,6 +687,13 @@ void LinkManager::setAutoconnectRTKGPS(bool autoconnect)
} }
} }
void LinkManager::setAutoconnectLibrePilot(bool autoconnect)
{
if (_setAutoconnectWorker(_autoconnectLibrePilot, autoconnect, _autoconnectLibrePilotKey)) {
emit autoconnectLibrePilotChanged(autoconnect);
}
}
QStringList LinkManager::linkTypeStrings(void) const QStringList LinkManager::linkTypeStrings(void) const
{ {
//-- Must follow same order as enum LinkType in LinkConfiguration.h //-- Must follow same order as enum LinkType in LinkConfiguration.h

28
src/comm/LinkManager.h

@ -66,6 +66,7 @@ public:
Q_PROPERTY(bool autoconnect3DRRadio READ autoconnect3DRRadio WRITE setAutoconnect3DRRadio NOTIFY autoconnect3DRRadioChanged) Q_PROPERTY(bool autoconnect3DRRadio READ autoconnect3DRRadio WRITE setAutoconnect3DRRadio NOTIFY autoconnect3DRRadioChanged)
Q_PROPERTY(bool autoconnectPX4Flow READ autoconnectPX4Flow WRITE setAutoconnectPX4Flow NOTIFY autoconnectPX4FlowChanged) Q_PROPERTY(bool autoconnectPX4Flow READ autoconnectPX4Flow WRITE setAutoconnectPX4Flow NOTIFY autoconnectPX4FlowChanged)
Q_PROPERTY(bool autoconnectRTKGPS READ autoconnectRTKGPS WRITE setAutoconnectRTKGPS NOTIFY autoconnectRTKGPSChanged) Q_PROPERTY(bool autoconnectRTKGPS READ autoconnectRTKGPS WRITE setAutoconnectRTKGPS NOTIFY autoconnectRTKGPSChanged)
Q_PROPERTY(bool autoconnectLibrePilot READ autoconnectLibrePilot WRITE setAutoconnectLibrePilot NOTIFY autoconnectLibrePilotChanged)
Q_PROPERTY(bool isBluetoothAvailable READ isBluetoothAvailable CONSTANT) Q_PROPERTY(bool isBluetoothAvailable READ isBluetoothAvailable CONSTANT)
/// LinkInterface Accessor /// LinkInterface Accessor
@ -96,6 +97,7 @@ public:
bool autoconnect3DRRadio (void) { return _autoconnect3DRRadio; } bool autoconnect3DRRadio (void) { return _autoconnect3DRRadio; }
bool autoconnectPX4Flow (void) { return _autoconnectPX4Flow; } bool autoconnectPX4Flow (void) { return _autoconnectPX4Flow; }
bool autoconnectRTKGPS (void) { return _autoconnectRTKGPS; } bool autoconnectRTKGPS (void) { return _autoconnectRTKGPS; }
bool autoconnectLibrePilot (void) { return _autoconnectLibrePilot; }
bool isBluetoothAvailable (void); bool isBluetoothAvailable (void);
QmlObjectListModel* links (void) { return &_links; } QmlObjectListModel* links (void) { return &_links; }
@ -105,11 +107,12 @@ public:
QStringList serialPortStrings (void); QStringList serialPortStrings (void);
QStringList serialPorts (void); QStringList serialPorts (void);
void setAutoconnectUDP (bool autoconnect); void setAutoconnectUDP (bool autoconnect);
void setAutoconnectPixhawk (bool autoconnect); void setAutoconnectPixhawk (bool autoconnect);
void setAutoconnect3DRRadio (bool autoconnect); void setAutoconnect3DRRadio (bool autoconnect);
void setAutoconnectPX4Flow (bool autoconnect); void setAutoconnectPX4Flow (bool autoconnect);
void setAutoconnectRTKGPS (bool autoconnect); void setAutoconnectRTKGPS (bool autoconnect);
void setAutoconnectLibrePilot (bool autoconnect);
/// Load list of link configurations from disk /// Load list of link configurations from disk
void loadLinkConfigurationList(); void loadLinkConfigurationList();
@ -163,11 +166,13 @@ public:
virtual void setToolbox(QGCToolbox *toolbox); virtual void setToolbox(QGCToolbox *toolbox);
signals: signals:
void autoconnectUDPChanged (bool autoconnect); void autoconnectUDPChanged (bool autoconnect);
void autoconnectPixhawkChanged (bool autoconnect); void autoconnectPixhawkChanged (bool autoconnect);
void autoconnect3DRRadioChanged (bool autoconnect); void autoconnect3DRRadioChanged (bool autoconnect);
void autoconnectPX4FlowChanged (bool autoconnect); void autoconnectPX4FlowChanged (bool autoconnect);
void autoconnectRTKGPSChanged (bool autoconnect); void autoconnectRTKGPSChanged (bool autoconnect);
void autoconnectLibrePilotChanged (bool autoconnect);
void newLink(LinkInterface* link); void newLink(LinkInterface* link);
@ -231,7 +236,7 @@ private:
bool _autoconnect3DRRadio; bool _autoconnect3DRRadio;
bool _autoconnectPX4Flow; bool _autoconnectPX4Flow;
bool _autoconnectRTKGPS; bool _autoconnectRTKGPS;
bool _autoconnectLibrePilot;
#ifndef __ios__ #ifndef __ios__
QTimer _activeLinkCheckTimer; ///< Timer which checks for a vehicle showing up on a usb direct link QTimer _activeLinkCheckTimer; ///< Timer which checks for a vehicle showing up on a usb direct link
QList<SerialLink*> _activeLinkCheckList; ///< List of links we are waiting for a vehicle to show up on QList<SerialLink*> _activeLinkCheckList; ///< List of links we are waiting for a vehicle to show up on
@ -244,6 +249,7 @@ private:
static const char* _autoconnect3DRRadioKey; static const char* _autoconnect3DRRadioKey;
static const char* _autoconnectPX4FlowKey; static const char* _autoconnectPX4FlowKey;
static const char* _autoconnectRTKGPSKey; static const char* _autoconnectRTKGPSKey;
static const char* _autoconnectLibrePilotKey;
static const char* _defaultUPDLinkName; static const char* _defaultUPDLinkName;
static const int _autoconnectUpdateTimerMSecs; static const int _autoconnectUpdateTimerMSecs;
static const int _autoconnectConnectDelayMSecs; static const int _autoconnectConnectDelayMSecs;

15
src/comm/QGCSerialPortInfo.cc

@ -30,6 +30,10 @@ static const struct VIDPIDMapInfo_s {
{ QGCSerialPortInfo::threeDRRadioVendorId, QGCSerialPortInfo::threeDRRadioProductId, QGCSerialPortInfo::BoardTypeSikRadio, "Found SiK Radio" }, { QGCSerialPortInfo::threeDRRadioVendorId, QGCSerialPortInfo::threeDRRadioProductId, QGCSerialPortInfo::BoardTypeSikRadio, "Found SiK Radio" },
{ QGCSerialPortInfo::siLabsRadioVendorId, QGCSerialPortInfo::siLabsRadioProductId, QGCSerialPortInfo::BoardTypeSikRadio, "Found SiK Radio" }, { QGCSerialPortInfo::siLabsRadioVendorId, QGCSerialPortInfo::siLabsRadioProductId, QGCSerialPortInfo::BoardTypeSikRadio, "Found SiK Radio" },
{ QGCSerialPortInfo::ubloxRTKVendorId, QGCSerialPortInfo::ubloxRTKProductId, QGCSerialPortInfo::BoardTypeRTKGPS, "Found RTK GPS" }, { QGCSerialPortInfo::ubloxRTKVendorId, QGCSerialPortInfo::ubloxRTKProductId, QGCSerialPortInfo::BoardTypeRTKGPS, "Found RTK GPS" },
{ QGCSerialPortInfo::openpilotVendorId, QGCSerialPortInfo::revolutionProductId, QGCSerialPortInfo::BoardTypeLibrePilot, "Found OP Revolution" },
{ QGCSerialPortInfo::openpilotVendorId, QGCSerialPortInfo::oplinkProductId, QGCSerialPortInfo::BoardTypeLibrePilot, "Found OP OPLink" },
{ QGCSerialPortInfo::openpilotVendorId, QGCSerialPortInfo::sparky2ProductId, QGCSerialPortInfo::BoardTypeLibrePilot, "Found TL Sparky2" },
{ QGCSerialPortInfo::openpilotVendorId, QGCSerialPortInfo::CC3DProductId, QGCSerialPortInfo::BoardTypeLibrePilot, "Found OP CC3D" },
}; };
QGCSerialPortInfo::QGCSerialPortInfo(void) : QGCSerialPortInfo::QGCSerialPortInfo(void) :
@ -135,6 +139,15 @@ bool QGCSerialPortInfo::isBootloader(void) const
bool QGCSerialPortInfo::canFlash(void) bool QGCSerialPortInfo::canFlash(void)
{ {
BoardType_t boardType = this->boardType(); BoardType_t boardType = this->boardType();
switch(boardType){
case QGCSerialPortInfo::BoardTypeUnknown:
case QGCSerialPortInfo::BoardTypeRTKGPS:
case QGCSerialPortInfo::BoardTypeLibrePilot:
return false;
default:
return true;
}
return boardType != QGCSerialPortInfo::BoardTypeUnknown && boardType != QGCSerialPortInfo::BoardTypeRTKGPS;
} }

7
src/comm/QGCSerialPortInfo.h

@ -37,6 +37,7 @@ public:
BoardTypeMINDPXFMUV2, BoardTypeMINDPXFMUV2,
BoardTypeTAPV1, BoardTypeTAPV1,
BoardTypeASCV1, BoardTypeASCV1,
BoardTypeLibrePilot,
BoardTypeUnknown BoardTypeUnknown
} BoardType_t; } BoardType_t;
@ -66,6 +67,12 @@ public:
static const int ubloxRTKVendorId = 5446; ///< Vendor ID for ublox RTK static const int ubloxRTKVendorId = 5446; ///< Vendor ID for ublox RTK
static const int ubloxRTKProductId = 424; ///< Product ID for ublox RTK static const int ubloxRTKProductId = 424; ///< Product ID for ublox RTK
static const int openpilotVendorId = 0x20A0; ///< Vendor ID for OpenPilot
static const int revolutionProductId = 0x415E; ///< Product ID for OpenPilot Revolution
static const int oplinkProductId = 0x415C; ///< Product ID for OpenPilot OPLink
static const int sparky2ProductId = 0x41D0; ///< Product ID for Taulabs Sparky2
static const int CC3DProductId = 0x415D; ///< Product ID for OpenPilot CC3D
QGCSerialPortInfo(void); QGCSerialPortInfo(void);
QGCSerialPortInfo(const QSerialPort & port); QGCSerialPortInfo(const QSerialPort & port);

5
src/ui/preferences/GeneralSettings.qml

@ -472,6 +472,11 @@ QGCView {
onClicked: QGroundControl.linkManager.autoconnectPX4Flow = checked onClicked: QGroundControl.linkManager.autoconnectPX4Flow = checked
} }
QGCCheckBox { QGCCheckBox {
text: qsTr("LibrePilot")
checked: QGroundControl.linkManager.autoconnectLibrePilot
onClicked: QGroundControl.linkManager.autoconnectLibrePilot = checked
}
QGCCheckBox {
text: qsTr("UDP") text: qsTr("UDP")
checked: QGroundControl.linkManager.autoconnectUDP checked: QGroundControl.linkManager.autoconnectUDP
onClicked: QGroundControl.linkManager.autoconnectUDP = checked onClicked: QGroundControl.linkManager.autoconnectUDP = checked

Loading…
Cancel
Save