Commit 0866ee10 authored by Don Gagne's avatar Don Gagne

Much better missing SD Card detection

Plus other auto connect bug fixes
parent 2fd104fa
......@@ -123,6 +123,9 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
setActiveVehicle(vehicle);
// Mark link as active
link->setActive(true);
#if defined __android__
if(_vehicles.count() == 1) {
//-- Once a vehicle is connected, keep Android screen from going off
......
......@@ -233,16 +233,6 @@ protected:
_logDataRateToBuffer(_outDataWriteAmounts, _outDataWriteTimes, &_outDataIndex, byteCount, time);
}
protected slots:
/**
* @brief Read a number of bytes from the interface.
*
* @param bytes The pointer to write the bytes to
* @param maxLength The maximum length which can be written
**/
virtual void readBytes() = 0;
private:
/**
* @brief logDataRateToBuffer Stores transmission times/amounts for statistics
......
......@@ -32,6 +32,7 @@ This file is part of the QGROUNDCONTROL project
#include <QList>
#include <QApplication>
#include <QDebug>
#include <QSignalSpy>
#ifndef __ios__
#include "QGCSerialPortInfo.h"
......@@ -121,7 +122,7 @@ LinkInterface* LinkManager::createConnectedLink(LinkConfiguration* config)
if (serialConfig) {
pLink = new SerialLink(serialConfig);
if (serialConfig->usbDirect()) {
_activeLinkCheckList.append(pLink);
_activeLinkCheckList.append((SerialLink*)pLink);
if (!_activeLinkCheckTimer.isActive()) {
_activeLinkCheckTimer.start();
}
......@@ -247,6 +248,7 @@ void LinkManager::disconnectLink(LinkInterface* link)
}
_deleteLink(link);
if (_autoconnectConfigurations.contains(config)) {
qCDebug(LinkManagerLog) << "Removing disconnected autoconnect config" << config->name();
_autoconnectConfigurations.removeOne(config);
delete config;
}
......@@ -560,13 +562,17 @@ void LinkManager::_updateAutoConnectLinks(void)
SerialConfiguration* linkConfig = _autoconnectConfigurations.value<SerialConfiguration*>(i);
if (linkConfig) {
if (!currentPorts.contains(linkConfig->portName())) {
// We don't remove links which are still connected even though at this point the cable may
// have been pulled. This is due to the fact that whether a serial port goes away from the
// list when the cable is pulled is OS dependant. By not disconnecting in this case, we keep
// things working the same across all OS.
if (!linkConfig->link() || !linkConfig->link()->isConnected()) {
_confToDelete.append(linkConfig);
if (linkConfig->link()) {
if (linkConfig->link()->isConnected()) {
if (linkConfig->link()->active()) {
// We don't remove links which are still connected which have been active with a vehicle on them
// even though at this point the cable may have been pulled. Instead we wait for the user to
// Disconnect. Once the user disconnects, the link will be removed.
continue;
}
}
}
_confToDelete.append(linkConfig);
}
} else {
qWarning() << "Internal error";
......@@ -577,6 +583,9 @@ void LinkManager::_updateAutoConnectLinks(void)
foreach (LinkConfiguration* pDeleteConfig, _confToDelete) {
qCDebug(LinkManagerLog) << "Removing unused autoconnect config" << pDeleteConfig->name();
_autoconnectConfigurations.removeOne(pDeleteConfig);
if (pDeleteConfig->link()) {
disconnectLink(pDeleteConfig->link());
}
delete pDeleteConfig;
}
#endif // __ios__
......@@ -842,10 +851,11 @@ bool LinkManager::isBluetoothAvailable(void)
void LinkManager::_activeLinkCheck(void)
{
SerialLink* link = NULL;
bool found = false;
if (_activeLinkCheckList.count() != 0) {
LinkInterface* link = _activeLinkCheckList.takeFirst();
link = _activeLinkCheckList.takeFirst();
if (_links.contains(link) && link->isConnected()) {
// Make sure there is a vehicle on the link
QmlObjectListModel* vehicles = _toolbox->multiVehicleManager()->vehicles();
......@@ -856,6 +866,8 @@ void LinkManager::_activeLinkCheck(void)
break;
}
}
} else {
link = NULL;
}
}
......@@ -863,7 +875,20 @@ void LinkManager::_activeLinkCheck(void)
_activeLinkCheckTimer.stop();
}
if (!found) {
qgcApp()->showMessage("Your Vehicle is not responding. If this continues please check that you have an SD Card inserted and try again.");
if (!found && link) {
// See if we can get an NSH prompt on this link
bool foundNSHPrompt = false;
link->writeBytes("\r", 1);
QSignalSpy spy(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)));
if (spy.wait(100)) {
QList<QVariant> arguments = spy.takeFirst();
if (arguments[1].value<QByteArray>().contains("nsh>")) {
foundNSHPrompt = true;
}
}
qgcApp()->showMessage(foundNSHPrompt ?
QStringLiteral("Please check to make sure you have an SD Card inserted in your Vehicle and try again.") :
QStringLiteral("Your Vehicle is not responding. If this continues shutdown QGroundControl, restart the Vehicle letting it boot completely, then start QGroundControl."));
}
}
......@@ -153,14 +153,6 @@ public:
/// Disconnect the specified link
Q_INVOKABLE void disconnectLink(LinkInterface* link);
/// Called to notify that a heartbeat was received with the specified information. Will transition
/// a link to active as needed.
/// @param link Heartbeat came through on this link
/// @param vehicleId Mavlink system id for vehicle
/// @param heartbeat Mavlink heartbeat message
/// @return true: continue further processing of this message, false: disregard this message
bool notifyHeartbeatInfo(LinkInterface* link, int vehicleId, mavlink_heartbeat_t& heartbeat);
// The following APIs are public but should not be called in normal use. The are mainly exposed
// here for unit test code.
void _deleteLink(LinkInterface* link);
......@@ -244,9 +236,9 @@ private:
bool _autoconnect3DRRadio;
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 = 10000; ///< Amount of time to wait for a heatbeat. Keep in mind ArduPilot stack heartbeat is slow to come.
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
static const int _activeLinkCheckTimeoutMSecs = 15000; ///< Amount of time to wait for a heatbeat. Keep in mind ArduPilot stack heartbeat is slow to come.
static const char* _settingsGroup;
static const char* _autoconnectUDPKey;
......
......@@ -150,11 +150,6 @@ void LogReplayLink::_replayError(const QString& errorMsg)
emit communicationError(_errorTitle, errorMsg);
}
void LogReplayLink::readBytes(void)
{
// FIXME: This is a bad virtual from LinkInterface?
}
/// Since this is log replay, we just drops writes on the floor
void LogReplayLink::writeBytes(const char* bytes, qint64 cBytes)
{
......
......@@ -114,10 +114,6 @@ signals:
void _pauseOnThread(void);
void _setAccelerationFactorOnThread(int factor);
protected slots:
// FIXME: This should not be part of LinkInterface. It is an internal link implementation detail.
virtual void readBytes(void);
private slots:
void _readNextLogEntry(void);
void _play(void);
......
......@@ -121,11 +121,6 @@ MockLink::~MockLink(void)
_disconnect();
}
void MockLink::readBytes(void)
{
// FIXME: This is a bad virtual from LinkInterface?
}
bool MockLink::_connect(void)
{
if (!_connected) {
......
......@@ -157,10 +157,6 @@ signals:
public slots:
virtual void writeBytes(const char *bytes, qint64 cBytes);
protected slots:
// FIXME: This should not be part of LinkInterface. It is an internal link implementation detail.
virtual void readBytes(void);
private slots:
void _run1HzTasks(void);
void _run10HzTasks(void);
......
......@@ -93,34 +93,6 @@ void SerialLink::writeBytes(const char* data, qint64 size)
}
}
/**
* @brief Read a number of bytes from the interface.
*
* @param data Pointer to the data byte array to write the bytes to
* @param maxLength The maximum number of bytes to write
**/
void SerialLink::readBytes()
{
if(_port && _port->isOpen()) {
const qint64 maxLength = 2048;
char data[maxLength];
_dataMutex.lock();
qint64 numBytes = _port->bytesAvailable();
if (numBytes > 0) {
/* Read as much data in buffer as possible without overflow */
if(maxLength < numBytes) numBytes = maxLength;
_logInputDataRate(numBytes, QDateTime::currentMSecsSinceEpoch());
_port->read(data, numBytes);
QByteArray b(data, numBytes);
emit bytesReceived(this, b);
}
_dataMutex.unlock();
}
}
/**
* @brief Disconnect the connection.
*
......@@ -267,8 +239,7 @@ bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString&
void SerialLink::_readBytes(void)
{
qint64 byteCount = _port->bytesAvailable();
if (byteCount)
{
if (byteCount) {
QByteArray buffer;
buffer.resize(byteCount);
_port->read(buffer.data(), buffer.size());
......
......@@ -158,8 +158,6 @@ public:
bool disconnect(void);
public slots:
void readBytes();
/**
* @brief Write a number of bytes to the interface.
*
......
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