Commit 891e1d56 authored by Don Gagne's avatar Don Gagne

Prompt for missing SD Card

parent 529f8dde
...@@ -282,6 +282,8 @@ public: ...@@ -282,6 +282,8 @@ public:
static const int cMaxRcChannels = 18; static const int cMaxRcChannels = 18;
bool containsLink(LinkInterface* link) { return _links.contains(link); }
public slots: public slots:
void setLatitude(double latitude); void setLatitude(double latitude);
void setLongitude(double longitude); void setLongitude(double longitude);
......
...@@ -87,6 +87,10 @@ LinkManager::LinkManager(QGCApplication* app) ...@@ -87,6 +87,10 @@ LinkManager::LinkManager(QGCApplication* app)
_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();
_activeLinkCheckTimer.setInterval(_activeLinkCheckTimeoutMSecs);
_activeLinkCheckTimer.setSingleShot(false);
connect(&_activeLinkCheckTimer, &QTimer::timeout, this, &LinkManager::_activeLinkCheck);
} }
LinkManager::~LinkManager() LinkManager::~LinkManager()
...@@ -112,8 +116,19 @@ LinkInterface* LinkManager::createConnectedLink(LinkConfiguration* config) ...@@ -112,8 +116,19 @@ LinkInterface* LinkManager::createConnectedLink(LinkConfiguration* config)
switch(config->type()) { switch(config->type()) {
#ifndef __ios__ #ifndef __ios__
case LinkConfiguration::TypeSerial: case LinkConfiguration::TypeSerial:
pLink = new SerialLink(dynamic_cast<SerialConfiguration*>(config)); {
break; SerialConfiguration* serialConfig = dynamic_cast<SerialConfiguration*>(config);
if (serialConfig) {
pLink = new SerialLink(serialConfig);
if (serialConfig->usbDirect()) {
_activeLinkCheckList.append(pLink);
if (!_activeLinkCheckTimer.isActive()) {
_activeLinkCheckTimer.start();
}
}
}
}
break;
#endif #endif
case LinkConfiguration::TypeUdp: case LinkConfiguration::TypeUdp:
pLink = new UDPLink(dynamic_cast<UDPConfiguration*>(config)); pLink = new UDPLink(dynamic_cast<UDPConfiguration*>(config));
...@@ -447,7 +462,7 @@ void LinkManager::_updateAutoConnectLinks(void) ...@@ -447,7 +462,7 @@ void LinkManager::_updateAutoConnectLinks(void)
break; break;
} }
} }
if (!foundUDP) { if (!foundUDP && _autoconnectUDP) {
qCDebug(LinkManagerLog) << "New auto-connect UDP port added"; qCDebug(LinkManagerLog) << "New auto-connect UDP port added";
UDPConfiguration* udpConfig = new UDPConfiguration(_defaultUPDLinkName); UDPConfiguration* udpConfig = new UDPConfiguration(_defaultUPDLinkName);
udpConfig->setLocalPort(QGC_UDP_LOCAL_PORT); udpConfig->setLocalPort(QGC_UDP_LOCAL_PORT);
...@@ -824,3 +839,31 @@ bool LinkManager::isBluetoothAvailable(void) ...@@ -824,3 +839,31 @@ bool LinkManager::isBluetoothAvailable(void)
{ {
return qgcApp()->isBluetoothAvailable(); return qgcApp()->isBluetoothAvailable();
} }
void LinkManager::_activeLinkCheck(void)
{
bool found = false;
if (_activeLinkCheckList.count() != 0) {
LinkInterface* link = _activeLinkCheckList.takeFirst();
if (_links.contains(link) && link->isConnected()) {
// Make sure there is a vehicle on the link
QmlObjectListModel* vehicles = _toolbox->multiVehicleManager()->vehicles();
for (int i=0; i<vehicles->count(); i++) {
Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles->get(i));
if (vehicle->containsLink(link)) {
found = true;
break;
}
}
}
}
if (_activeLinkCheckList.count() == 0) {
_activeLinkCheckTimer.stop();
}
if (!found) {
qgcApp()->showMessage("You have connected to a Vehicle which does not have an SD Card inserted. Please insert an SD card and try again.");
}
}
...@@ -210,6 +210,7 @@ signals: ...@@ -210,6 +210,7 @@ signals:
private slots: private slots:
void _linkConnected(void); void _linkConnected(void);
void _linkDisconnected(void); void _linkDisconnected(void);
void _activeLinkCheck(void);
private: private:
bool _connectionsSuspendedMsg(void); bool _connectionsSuspendedMsg(void);
...@@ -243,6 +244,10 @@ private: ...@@ -243,6 +244,10 @@ private:
bool _autoconnect3DRRadio; bool _autoconnect3DRRadio;
bool _autoconnectPX4Flow; bool _autoconnectPX4Flow;
QTimer _activeLinkCheckTimer; // Timer which checks for a vehicle showing up on a usb direct link
QList<LinkInterface*> _activeLinkCheckList; // List of links we are waiting for a vehicle to show up on
static const int _activeLinkCheckTimeoutMSecs = 7000;
static const char* _settingsGroup; static const char* _settingsGroup;
static const char* _autoconnectUDPKey; static const char* _autoconnectUDPKey;
static const char* _autoconnectPixhawkKey; static const char* _autoconnectPixhawkKey;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment