Commit 6541cbf0 authored by dogmaphobic's avatar dogmaphobic

Merge remote-tracking branch 'MavLink/master' into serialSettings

* MavLink/master:
  More reliable radio flash
  Fix autoconnect/re-autoconnect, plus windows connect
  Don't show resource busy errors from auto connect attempt
  Don't pop modal dialog during boot sequence

Conflicts:
	src/comm/LinkManager.cc
parents a8dabf1f e6f5eb34
...@@ -63,7 +63,7 @@ void AutoPilotPlugin::_parametersReadyChanged(bool parametersReady) ...@@ -63,7 +63,7 @@ void AutoPilotPlugin::_parametersReadyChanged(bool parametersReady)
if (parametersReady) { if (parametersReady) {
_recalcSetupComplete(); _recalcSetupComplete();
if (!_setupComplete) { if (!_setupComplete) {
QGCMessageBox::warning("Setup", "One or more vehicle components require setup prior to flight."); qgcApp()->showToolBarMessage("One or more vehicle components require setup prior to flight.");
// Take the user to Vehicle Summary // Take the user to Vehicle Summary
MainWindow::instance()->showSetupView(); MainWindow::instance()->showSetupView();
......
...@@ -27,7 +27,8 @@ ...@@ -27,7 +27,8 @@
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
// Add Global logging categories (not class specific) here using QGC_LOGGING_CATEGORY // Add Global logging categories (not class specific) here using QGC_LOGGING_CATEGORY
QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog") QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog")
QGCLoggingCategoryRegister* _instance = NULL; QGCLoggingCategoryRegister* _instance = NULL;
......
...@@ -32,6 +32,7 @@ ...@@ -32,6 +32,7 @@
// Add Global logging categories (not class specific) here using Q_DECLARE_LOGGING_CATEGORY // Add Global logging categories (not class specific) here using Q_DECLARE_LOGGING_CATEGORY
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog) Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog)
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog)
/// @def QGC_LOGGING_CATEGORY /// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a /// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
......
...@@ -273,7 +273,7 @@ bool Bootloader::_ihxProgram(QextSerialPort* port, const FirmwareImage* image) ...@@ -273,7 +273,7 @@ bool Bootloader::_ihxProgram(QextSerialPort* port, const FirmwareImage* image)
return false; return false;
} }
qCDebug(FirmwareUpgradeLog) << QString("Bootloader::_ihxProgram - address:%1 size:%2 block:%3").arg(flashAddress).arg(bytes.count()).arg(index); qCDebug(FirmwareUpgradeVerboseLog) << QString("Bootloader::_ihxProgram - address:%1 size:%2 block:%3").arg(flashAddress).arg(bytes.count()).arg(index);
// Set flash address // Set flash address
...@@ -348,7 +348,7 @@ bool Bootloader::verify(QextSerialPort* port, const FirmwareImage* image) ...@@ -348,7 +348,7 @@ bool Bootloader::verify(QextSerialPort* port, const FirmwareImage* image)
return ret; return ret;
} }
/// @brief Verify the flash on bootloader eading it back and comparing it against the original image-> /// @brief Verify the flash on bootloader reading it back and comparing it against the original image
bool Bootloader::_verifyBytes(QextSerialPort* port, const FirmwareImage* image) bool Bootloader::_verifyBytes(QextSerialPort* port, const FirmwareImage* image)
{ {
if (image->imageIsBinFormat()) { if (image->imageIsBinFormat()) {
...@@ -445,7 +445,7 @@ bool Bootloader::_ihxVerifyBytes(QextSerialPort* port, const FirmwareImage* imag ...@@ -445,7 +445,7 @@ bool Bootloader::_ihxVerifyBytes(QextSerialPort* port, const FirmwareImage* imag
return false; return false;
} }
qCDebug(FirmwareUpgradeLog) << QString("Bootloader::_ihxVerifyBytes - address:%1 size:%2 block:%3").arg(readAddress).arg(imageBytes.count()).arg(index); qCDebug(FirmwareUpgradeLog) << QString("Bootloader::_ihxVerifyBytes - address:0x%1 size:%2 block:%3").arg(readAddress, 8, 16, QLatin1Char('0')).arg(imageBytes.count()).arg(index);
// Set read address // Set read address
......
...@@ -165,7 +165,7 @@ bool FirmwareImage::_ihxLoad(const QString& ihxFilename) ...@@ -165,7 +165,7 @@ bool FirmwareImage::_ihxLoad(const QString& ihxFilename)
if (appendToLastBlock) { if (appendToLastBlock) {
_ihxBlocks[_ihxBlocks.count() - 1].bytes += bytes; _ihxBlocks[_ihxBlocks.count() - 1].bytes += bytes;
qCDebug(FirmwareUpgradeLog) << QString("_ihxLoad - append - address:%1 size:%2 block:%3").arg(address).arg(blockByteCount).arg(ihxBlockCount()); qCDebug(FirmwareUpgradeVerboseLog) << QString("_ihxLoad - append - address:%1 size:%2 block:%3").arg(address).arg(blockByteCount).arg(ihxBlockCount());
} else { } else {
IntelHexBlock_t block; IntelHexBlock_t block;
...@@ -173,7 +173,7 @@ bool FirmwareImage::_ihxLoad(const QString& ihxFilename) ...@@ -173,7 +173,7 @@ bool FirmwareImage::_ihxLoad(const QString& ihxFilename)
block.bytes = bytes; block.bytes = bytes;
_ihxBlocks += block; _ihxBlocks += block;
qCDebug(FirmwareUpgradeLog) << QString("_ihxLoad - new block - address:%1 size:%2 block:%3").arg(address).arg(blockByteCount).arg(ihxBlockCount()); qCDebug(FirmwareUpgradeVerboseLog) << QString("_ihxLoad - new block - address:%1 size:%2 block:%3").arg(address).arg(blockByteCount).arg(ihxBlockCount());
} }
_imageSize += blockByteCount; _imageSize += blockByteCount;
......
...@@ -132,13 +132,13 @@ void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void) ...@@ -132,13 +132,13 @@ void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void)
bool PX4FirmwareUpgradeThreadWorker::_findBoardFromPorts(QGCSerialPortInfo& portInfo, QGCSerialPortInfo::BoardType_t& boardType) bool PX4FirmwareUpgradeThreadWorker::_findBoardFromPorts(QGCSerialPortInfo& portInfo, QGCSerialPortInfo::BoardType_t& boardType)
{ {
foreach (QGCSerialPortInfo info, QGCSerialPortInfo::availablePorts()) { foreach (QGCSerialPortInfo info, QGCSerialPortInfo::availablePorts()) {
qCDebug(FirmwareUpgradeLog) << "Serial Port --------------"; qCDebug(FirmwareUpgradeVerboseLog) << "Serial Port --------------";
qCDebug(FirmwareUpgradeLog) << "\tboard type" << info.boardType(); qCDebug(FirmwareUpgradeVerboseLog) << "\tboard type" << info.boardType();
qCDebug(FirmwareUpgradeLog) << "\tport name:" << info.portName(); qCDebug(FirmwareUpgradeVerboseLog) << "\tport name:" << info.portName();
qCDebug(FirmwareUpgradeLog) << "\tdescription:" << info.description(); qCDebug(FirmwareUpgradeVerboseLog) << "\tdescription:" << info.description();
qCDebug(FirmwareUpgradeLog) << "\tsystem location:" << info.systemLocation(); qCDebug(FirmwareUpgradeVerboseLog) << "\tsystem location:" << info.systemLocation();
qCDebug(FirmwareUpgradeLog) << "\tvendor ID:" << info.vendorIdentifier(); qCDebug(FirmwareUpgradeVerboseLog) << "\tvendor ID:" << info.vendorIdentifier();
qCDebug(FirmwareUpgradeLog) << "\tproduct ID:" << info.productIdentifier(); qCDebug(FirmwareUpgradeVerboseLog) << "\tproduct ID:" << info.productIdentifier();
boardType = info.boardType(); boardType = info.boardType();
if (boardType != QGCSerialPortInfo::BoardTypeUnknown) { if (boardType != QGCSerialPortInfo::BoardTypeUnknown) {
...@@ -167,13 +167,8 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor ...@@ -167,13 +167,8 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor
emit status("Putting radio into command mode"); emit status("Putting radio into command mode");
// Wait a little while for the USB port to initialize. 3DR Radio boot is really slow. // Wait a little while for the USB port to initialize. 3DR Radio boot is really slow.
for (int i=0; i<12; i++) { QGC::SLEEP::msleep(2000);
if (port.open(QIODevice::ReadWrite)) { port.open(QIODevice::ReadWrite);
break;
} else {
QGC::SLEEP::msleep(250);
}
}
if (!port.isOpen()) { if (!port.isOpen()) {
emit error(QString("Unable to open port: %1 error: %2").arg(portInfo.systemLocation()).arg(port.errorString())); emit error(QString("Unable to open port: %1 error: %2").arg(portInfo.systemLocation()).arg(port.errorString()));
...@@ -181,6 +176,7 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor ...@@ -181,6 +176,7 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor
} }
// Put radio into command mode // Put radio into command mode
QGC::SLEEP::msleep(2000);
port.write("+++", 3); port.write("+++", 3);
if (!port.waitForReadyRead(1500)) { if (!port.waitForReadyRead(1500)) {
emit error("Unable to put radio into command mode"); emit error("Unable to put radio into command mode");
...@@ -188,6 +184,7 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor ...@@ -188,6 +184,7 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor
} }
QByteArray bytes = port.readAll(); QByteArray bytes = port.readAll();
if (!bytes.contains("OK")) { if (!bytes.contains("OK")) {
qCDebug(FirmwareUpgradeLog) << bytes;
emit error("Unable to put radio into command mode"); emit error("Unable to put radio into command mode");
return; return;
} }
...@@ -196,10 +193,14 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor ...@@ -196,10 +193,14 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor
port.write("AT&UPDATE\r\n"); port.write("AT&UPDATE\r\n");
if (!port.waitForBytesWritten(1500)) { if (!port.waitForBytesWritten(1500)) {
emit error("Unable to reboot radio"); emit error("Unable to reboot radio (bytes written)");
return; return;
} }
QGC::SLEEP::msleep(2000); if (!port.waitForReadyRead(1500)) {
emit error("Unable to reboot radio (ready read)");
return;
}
QGC::SLEEP::msleep(700);
port.close(); port.close();
// The bootloader should be waiting for us now // The bootloader should be waiting for us now
...@@ -218,7 +219,10 @@ bool PX4FirmwareUpgradeThreadWorker::_findBootloader(const QGCSerialPortInfo& po ...@@ -218,7 +219,10 @@ bool PX4FirmwareUpgradeThreadWorker::_findBootloader(const QGCSerialPortInfo& po
_bootloaderPort = new QextSerialPort(QextSerialPort::Polling); _bootloaderPort = new QextSerialPort(QextSerialPort::Polling);
Q_CHECK_PTR(_bootloaderPort); Q_CHECK_PTR(_bootloaderPort);
if (radioMode) {
_bootloaderPort->setBaudRate(BAUD115200);
}
// Wait a little while for the USB port to initialize. // Wait a little while for the USB port to initialize.
for (int i=0; i<10; i++) { for (int i=0; i<10; i++) {
if (_bootloader->open(_bootloaderPort, portInfo.systemLocation())) { if (_bootloader->open(_bootloaderPort, portInfo.systemLocation())) {
......
...@@ -55,6 +55,14 @@ const char* LinkManager::_autoconnect3DRRadioKey = "Autoconnect3DRRadio"; ...@@ -55,6 +55,14 @@ const char* LinkManager::_autoconnect3DRRadioKey = "Autoconnect3DRRadio";
const char* LinkManager::_autoconnectPX4FlowKey = "AutoconnectPX4Flow"; const char* LinkManager::_autoconnectPX4FlowKey = "AutoconnectPX4Flow";
const char* LinkManager::_defaultUPDLinkName = "Default UDP Link"; const char* LinkManager::_defaultUPDLinkName = "Default UDP Link";
const int LinkManager::_autoconnectUpdateTimerMSecs = 1000;
#ifdef Q_OS_WIN
// Have to manually let the bootloader go by on Windows to get a working connect
const int LinkManager::_autoconnectConnectDelayMSecs = 6000;
#else
const int LinkManager::_autoconnectConnectDelayMSecs = 1000;
#endif
LinkManager::LinkManager(QGCApplication* app) LinkManager::LinkManager(QGCApplication* app)
: QGCTool(app) : QGCTool(app)
, _configUpdateSuspended(false) , _configUpdateSuspended(false)
...@@ -96,7 +104,7 @@ void LinkManager::setToolbox(QGCToolbox *toolbox) ...@@ -96,7 +104,7 @@ void LinkManager::setToolbox(QGCToolbox *toolbox)
connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &LinkManager::_vehicleHeartbeatInfo); connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &LinkManager::_vehicleHeartbeatInfo);
connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks); connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);
_portListTimer.start(6000); // timeout must be long enough to get past bootloader on second pass _portListTimer.start(_autoconnectUpdateTimerMSecs); // timeout must be long enough to get past bootloader on second pass
} }
...@@ -220,10 +228,16 @@ void LinkManager::disconnectLink(LinkInterface* link) ...@@ -220,10 +228,16 @@ void LinkManager::disconnectLink(LinkInterface* link)
link->_disconnect(); link->_disconnect();
LinkConfiguration* config = link->getLinkConfiguration(); LinkConfiguration* config = link->getLinkConfiguration();
if(config) { if (config) {
config->setLink(NULL); if (_autoconnectConfigurations.contains(config)) {
config->setLink(NULL);
}
} }
_deleteLink(link); _deleteLink(link);
if (_autoconnectConfigurations.contains(config)) {
_autoconnectConfigurations.removeOne(config);
delete config;
}
} }
void LinkManager::_deleteLink(LinkInterface* link) void LinkManager::_deleteLink(LinkInterface* link)
...@@ -472,11 +486,11 @@ void LinkManager::_updateAutoConnectLinks(void) ...@@ -472,11 +486,11 @@ void LinkManager::_updateAutoConnectLinks(void)
// are in the bootloader is flaky from a cross-platform standpoint. So by putting it on a wait list // are in the bootloader is flaky from a cross-platform standpoint. So by putting it on a wait list
// and only connect on the second pass we leave enough time for the board to boot up. // and only connect on the second pass we leave enough time for the board to boot up.
qCDebug(LinkManagerLog) << "Waiting for next autoconnect pass" << portInfo.systemLocation(); qCDebug(LinkManagerLog) << "Waiting for next autoconnect pass" << portInfo.systemLocation();
_autoconnectWaitList.append(portInfo.systemLocation()); _autoconnectWaitList[portInfo.systemLocation()] = 1;
} else { } else if (++_autoconnectWaitList[portInfo.systemLocation()] * _autoconnectUpdateTimerMSecs > _autoconnectConnectDelayMSecs) {
SerialConfiguration* pSerialConfig = NULL; SerialConfiguration* pSerialConfig = NULL;
_autoconnectWaitList.removeOne(portInfo.systemLocation()); _autoconnectWaitList.remove(portInfo.systemLocation());
switch (boardType) { switch (boardType) {
case QGCSerialPortInfo::BoardTypePX4FMUV1: case QGCSerialPortInfo::BoardTypePX4FMUV1:
...@@ -832,3 +846,8 @@ void LinkManager::removeConfiguration(LinkConfiguration* config) ...@@ -832,3 +846,8 @@ void LinkManager::removeConfiguration(LinkConfiguration* config)
// Save list // Save list
saveLinkConfigurationList(); saveLinkConfigurationList();
} }
bool LinkManager::isAutoconnectLink(LinkInterface* link)
{
return _autoconnectConfigurations.contains(link->getLinkConfiguration());
}
...@@ -169,6 +169,9 @@ public: ...@@ -169,6 +169,9 @@ public:
// Called to signal app shutdown. Disconnects all links while turning off auto-connect. // Called to signal app shutdown. Disconnects all links while turning off auto-connect.
void shutdown(void); void shutdown(void);
/// @return true: specified link is an autoconnect link
bool isAutoconnectLink(LinkInterface* link);
// Override from QGCTool // Override from QGCTool
virtual void setToolbox(QGCToolbox *toolbox); virtual void setToolbox(QGCToolbox *toolbox);
...@@ -230,7 +233,7 @@ private: ...@@ -230,7 +233,7 @@ private:
QmlObjectListModel _linkConfigurations; QmlObjectListModel _linkConfigurations;
QmlObjectListModel _autoconnectConfigurations; QmlObjectListModel _autoconnectConfigurations;
QStringList _autoconnectWaitList; QMap<QString, int> _autoconnectWaitList; ///< key: QGCSerialPortInfo.systemLocation, value: wait count
QStringList _commPortList; QStringList _commPortList;
QStringList _commPortDisplayList; QStringList _commPortDisplayList;
...@@ -239,12 +242,14 @@ private: ...@@ -239,12 +242,14 @@ private:
bool _autoconnect3DRRadio; bool _autoconnect3DRRadio;
bool _autoconnectPX4Flow; bool _autoconnectPX4Flow;
static const char* _settingsGroup; static const char* _settingsGroup;
static const char* _autoconnectUDPKey; static const char* _autoconnectUDPKey;
static const char* _autoconnectPixhawkKey; static const char* _autoconnectPixhawkKey;
static const char* _autoconnect3DRRadioKey; static const char* _autoconnect3DRRadioKey;
static const char* _autoconnectPX4FlowKey; static const char* _autoconnectPX4FlowKey;
static const char* _defaultUPDLinkName; static const char* _defaultUPDLinkName;
static const int _autoconnectUpdateTimerMSecs;
static const int _autoconnectConnectDelayMSecs;
}; };
#endif #endif
...@@ -154,28 +154,30 @@ bool SerialLink::_connect(void) ...@@ -154,28 +154,30 @@ bool SerialLink::_connect(void)
qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(true); qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(true);
#endif #endif
QSerialPort::SerialPortError error;
QString errorString;
// Initialize the connection // Initialize the connection
if (!_hardwareConnect(_type)) { if (!_hardwareConnect(error, errorString)) {
// Need to error out here. if (qgcApp()->toolbox()->linkManager()->isAutoconnectLink(this)) {
QString err("Could not create port."); // Be careful with spitting out open error related to trying to open a busy port using autoconnect
if (_port) { if (error == QSerialPort::PermissionError) {
err = _port->errorString(); // Device already open, ignore and fail connect
return false;
}
} }
_emitLinkError("Error connecting: " + err);
_emitLinkError(QString("Error connecting: Could not create port. %1").arg(errorString));
return false; return false;
} }
return true; return true;
} }
/** /// Performs the actual hardware port connection.
* @brief This function is called indirectly by the _connect() call. /// @param[out] error if failed
* /// @param[out] error string if failed
* The _connect() function starts the thread and indirectly calls this method. /// @return success/fail
* bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString& errorString)
* @return True if the connection could be established, false otherwise
* @see _connect() For the right function to establish the connection.
**/
bool SerialLink::_hardwareConnect(QString &type)
{ {
if (_port) { if (_port) {
qCDebug(SerialLinkLog) << "SerialLink:" << QString::number((long)this, 16) << "closing port"; qCDebug(SerialLinkLog) << "SerialLink:" << QString::number((long)this, 16) << "closing port";
...@@ -235,6 +237,9 @@ bool SerialLink::_hardwareConnect(QString &type) ...@@ -235,6 +237,9 @@ bool SerialLink::_hardwareConnect(QString &type)
} }
#endif #endif
if (!_port->isOpen() ) { if (!_port->isOpen() ) {
qDebug() << "open failed" << _port->errorString() << _port->error() << getName() << qgcApp()->toolbox()->linkManager()->isAutoconnectLink(this);
error = _port->error();
errorString = _port->errorString();
emit communicationUpdate(getName(),"Error opening port: " + _port->errorString()); emit communicationUpdate(getName(),"Error opening port: " + _port->errorString());
_port->close(); _port->close();
delete _port; delete _port;
...@@ -252,7 +257,7 @@ bool SerialLink::_hardwareConnect(QString &type) ...@@ -252,7 +257,7 @@ bool SerialLink::_hardwareConnect(QString &type)
emit communicationUpdate(getName(), "Opened port!"); emit communicationUpdate(getName(), "Opened port!");
emit connected(); emit connected();
qCDebug(SerialLinkLog) << "CONNECTING LINK: " << __FILE__ << __LINE__ << "type:" << type << "with settings" << _config->portName() qCDebug(SerialLinkLog) << "Connection SeriaLink: " << "with settings" << _config->portName()
<< _config->baud() << _config->dataBits() << _config->parity() << _config->stopBits(); << _config->baud() << _config->dataBits() << _config->parity() << _config->stopBits();
return true; // successful connection return true; // successful connection
......
...@@ -171,7 +171,6 @@ protected: ...@@ -171,7 +171,6 @@ protected:
int _timeout; int _timeout;
QMutex _dataMutex; // Mutex for reading data from _port QMutex _dataMutex; // Mutex for reading data from _port
QMutex _writeMutex; // Mutex for accessing the _transmitBuffer. QMutex _writeMutex; // Mutex for accessing the _transmitBuffer.
QString _type;
private slots: private slots:
void _readBytes(void); void _readBytes(void);
...@@ -187,7 +186,7 @@ private: ...@@ -187,7 +186,7 @@ private:
// Internal methods // Internal methods
void _emitLinkError(const QString& errorMsg); void _emitLinkError(const QString& errorMsg);
bool _hardwareConnect(QString &_type); bool _hardwareConnect(QSerialPort::SerialPortError& error, QString& errorString);
bool _isBootloader(); bool _isBootloader();
void _resetConfiguration(); void _resetConfiguration();
......
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