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)
if (parametersReady) {
_recalcSetupComplete();
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
MainWindow::instance()->showSetupView();
......
......@@ -28,6 +28,7 @@
// Add Global logging categories (not class specific) here using QGC_LOGGING_CATEGORY
QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog")
QGCLoggingCategoryRegister* _instance = NULL;
......
......@@ -32,6 +32,7 @@
// Add Global logging categories (not class specific) here using Q_DECLARE_LOGGING_CATEGORY
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog)
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog)
/// @def QGC_LOGGING_CATEGORY
/// 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)
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
......@@ -348,7 +348,7 @@ bool Bootloader::verify(QextSerialPort* port, const FirmwareImage* image)
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)
{
if (image->imageIsBinFormat()) {
......@@ -445,7 +445,7 @@ bool Bootloader::_ihxVerifyBytes(QextSerialPort* port, const FirmwareImage* imag
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
......
......@@ -165,7 +165,7 @@ bool FirmwareImage::_ihxLoad(const QString& ihxFilename)
if (appendToLastBlock) {
_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 {
IntelHexBlock_t block;
......@@ -173,7 +173,7 @@ bool FirmwareImage::_ihxLoad(const QString& ihxFilename)
block.bytes = bytes;
_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;
......
......@@ -132,13 +132,13 @@ void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void)
bool PX4FirmwareUpgradeThreadWorker::_findBoardFromPorts(QGCSerialPortInfo& portInfo, QGCSerialPortInfo::BoardType_t& boardType)
{
foreach (QGCSerialPortInfo info, QGCSerialPortInfo::availablePorts()) {
qCDebug(FirmwareUpgradeLog) << "Serial Port --------------";
qCDebug(FirmwareUpgradeLog) << "\tboard type" << info.boardType();
qCDebug(FirmwareUpgradeLog) << "\tport name:" << info.portName();
qCDebug(FirmwareUpgradeLog) << "\tdescription:" << info.description();
qCDebug(FirmwareUpgradeLog) << "\tsystem location:" << info.systemLocation();
qCDebug(FirmwareUpgradeLog) << "\tvendor ID:" << info.vendorIdentifier();
qCDebug(FirmwareUpgradeLog) << "\tproduct ID:" << info.productIdentifier();
qCDebug(FirmwareUpgradeVerboseLog) << "Serial Port --------------";
qCDebug(FirmwareUpgradeVerboseLog) << "\tboard type" << info.boardType();
qCDebug(FirmwareUpgradeVerboseLog) << "\tport name:" << info.portName();
qCDebug(FirmwareUpgradeVerboseLog) << "\tdescription:" << info.description();
qCDebug(FirmwareUpgradeVerboseLog) << "\tsystem location:" << info.systemLocation();
qCDebug(FirmwareUpgradeVerboseLog) << "\tvendor ID:" << info.vendorIdentifier();
qCDebug(FirmwareUpgradeVerboseLog) << "\tproduct ID:" << info.productIdentifier();
boardType = info.boardType();
if (boardType != QGCSerialPortInfo::BoardTypeUnknown) {
......@@ -167,13 +167,8 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor
emit status("Putting radio into command mode");
// Wait a little while for the USB port to initialize. 3DR Radio boot is really slow.
for (int i=0; i<12; i++) {
if (port.open(QIODevice::ReadWrite)) {
break;
} else {
QGC::SLEEP::msleep(250);
}
}
QGC::SLEEP::msleep(2000);
port.open(QIODevice::ReadWrite);
if (!port.isOpen()) {
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
}
// Put radio into command mode
QGC::SLEEP::msleep(2000);
port.write("+++", 3);
if (!port.waitForReadyRead(1500)) {
emit error("Unable to put radio into command mode");
......@@ -188,6 +184,7 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor
}
QByteArray bytes = port.readAll();
if (!bytes.contains("OK")) {
qCDebug(FirmwareUpgradeLog) << bytes;
emit error("Unable to put radio into command mode");
return;
}
......@@ -196,10 +193,14 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QGCSerialPor
port.write("AT&UPDATE\r\n");
if (!port.waitForBytesWritten(1500)) {
emit error("Unable to reboot radio");
emit error("Unable to reboot radio (bytes written)");
return;
}
QGC::SLEEP::msleep(2000);
if (!port.waitForReadyRead(1500)) {
emit error("Unable to reboot radio (ready read)");
return;
}
QGC::SLEEP::msleep(700);
port.close();
// The bootloader should be waiting for us now
......@@ -218,6 +219,9 @@ bool PX4FirmwareUpgradeThreadWorker::_findBootloader(const QGCSerialPortInfo& po
_bootloaderPort = new QextSerialPort(QextSerialPort::Polling);
Q_CHECK_PTR(_bootloaderPort);
if (radioMode) {
_bootloaderPort->setBaudRate(BAUD115200);
}
// Wait a little while for the USB port to initialize.
for (int i=0; i<10; i++) {
......
......@@ -55,6 +55,14 @@ const char* LinkManager::_autoconnect3DRRadioKey = "Autoconnect3DRRadio";
const char* LinkManager::_autoconnectPX4FlowKey = "AutoconnectPX4Flow";
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)
: QGCTool(app)
, _configUpdateSuspended(false)
......@@ -96,7 +104,7 @@ void LinkManager::setToolbox(QGCToolbox *toolbox)
connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &LinkManager::_vehicleHeartbeatInfo);
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)
link->_disconnect();
LinkConfiguration* config = link->getLinkConfiguration();
if(config) {
if (config) {
if (_autoconnectConfigurations.contains(config)) {
config->setLink(NULL);
}
}
_deleteLink(link);
if (_autoconnectConfigurations.contains(config)) {
_autoconnectConfigurations.removeOne(config);
delete config;
}
}
void LinkManager::_deleteLink(LinkInterface* link)
......@@ -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
// 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();
_autoconnectWaitList.append(portInfo.systemLocation());
} else {
_autoconnectWaitList[portInfo.systemLocation()] = 1;
} else if (++_autoconnectWaitList[portInfo.systemLocation()] * _autoconnectUpdateTimerMSecs > _autoconnectConnectDelayMSecs) {
SerialConfiguration* pSerialConfig = NULL;
_autoconnectWaitList.removeOne(portInfo.systemLocation());
_autoconnectWaitList.remove(portInfo.systemLocation());
switch (boardType) {
case QGCSerialPortInfo::BoardTypePX4FMUV1:
......@@ -832,3 +846,8 @@ void LinkManager::removeConfiguration(LinkConfiguration* config)
// Save list
saveLinkConfigurationList();
}
bool LinkManager::isAutoconnectLink(LinkInterface* link)
{
return _autoconnectConfigurations.contains(link->getLinkConfiguration());
}
......@@ -169,6 +169,9 @@ public:
// Called to signal app shutdown. Disconnects all links while turning off auto-connect.
void shutdown(void);
/// @return true: specified link is an autoconnect link
bool isAutoconnectLink(LinkInterface* link);
// Override from QGCTool
virtual void setToolbox(QGCToolbox *toolbox);
......@@ -230,7 +233,7 @@ private:
QmlObjectListModel _linkConfigurations;
QmlObjectListModel _autoconnectConfigurations;
QStringList _autoconnectWaitList;
QMap<QString, int> _autoconnectWaitList; ///< key: QGCSerialPortInfo.systemLocation, value: wait count
QStringList _commPortList;
QStringList _commPortDisplayList;
......@@ -245,6 +248,8 @@ private:
static const char* _autoconnect3DRRadioKey;
static const char* _autoconnectPX4FlowKey;
static const char* _defaultUPDLinkName;
static const int _autoconnectUpdateTimerMSecs;
static const int _autoconnectConnectDelayMSecs;
};
#endif
......@@ -154,28 +154,30 @@ bool SerialLink::_connect(void)
qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(true);
#endif
QSerialPort::SerialPortError error;
QString errorString;
// Initialize the connection
if (!_hardwareConnect(_type)) {
// Need to error out here.
QString err("Could not create port.");
if (_port) {
err = _port->errorString();
if (!_hardwareConnect(error, errorString)) {
if (qgcApp()->toolbox()->linkManager()->isAutoconnectLink(this)) {
// Be careful with spitting out open error related to trying to open a busy port using autoconnect
if (error == QSerialPort::PermissionError) {
// 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 true;
}
/**
* @brief This function is called indirectly by the _connect() call.
*
* The _connect() function starts the thread and indirectly calls this method.
*
* @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)
/// Performs the actual hardware port connection.
/// @param[out] error if failed
/// @param[out] error string if failed
/// @return success/fail
bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString& errorString)
{
if (_port) {
qCDebug(SerialLinkLog) << "SerialLink:" << QString::number((long)this, 16) << "closing port";
......@@ -235,6 +237,9 @@ bool SerialLink::_hardwareConnect(QString &type)
}
#endif
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());
_port->close();
delete _port;
......@@ -252,7 +257,7 @@ bool SerialLink::_hardwareConnect(QString &type)
emit communicationUpdate(getName(), "Opened port!");
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();
return true; // successful connection
......
......@@ -171,7 +171,6 @@ protected:
int _timeout;
QMutex _dataMutex; // Mutex for reading data from _port
QMutex _writeMutex; // Mutex for accessing the _transmitBuffer.
QString _type;
private slots:
void _readBytes(void);
......@@ -187,7 +186,7 @@ private:
// Internal methods
void _emitLinkError(const QString& errorMsg);
bool _hardwareConnect(QString &_type);
bool _hardwareConnect(QSerialPort::SerialPortError& error, QString& errorString);
bool _isBootloader();
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