Commit eb5a54c0 authored by Lorenz Meier's avatar Lorenz Meier

Compile and serial port error handling fixes

parent 4640d27e
...@@ -31,11 +31,11 @@ ...@@ -31,11 +31,11 @@
#include <QDateTime> #include <QDateTime>
namespace internals { namespace internals {
static const QString googleCopyright = QString("%1 Google - Map data %1 Tele Atlas, Imagery %1 TerraMetrics").arg(QDate::currentDate().year()); static const QString googleCopyright = QString("(c)%1 Google - Map data (c)%1 Tele Atlas, Imagery (c)%1 TerraMetrics").arg(QDate::currentDate().year());
static const QString openStreetMapCopyright = QString(" OpenStreetMap - Map data %1 OpenStreetMap").arg(QDate::currentDate().year()); static const QString openStreetMapCopyright = QString("(c) OpenStreetMap - Map data (c)%1 OpenStreetMap").arg(QDate::currentDate().year());
static const QString yahooMapCopyright = QString(" Yahoo! Inc. - Map data & Imagery %1 NAVTEQ").arg(QDate::currentDate().year()); static const QString yahooMapCopyright = QString("(c) Yahoo! Inc. - Map data & Imagery (c)%1 NAVTEQ").arg(QDate::currentDate().year());
static const QString virtualEarthCopyright = QString("%1 Microsoft Corporation, %1 NAVTEQ, %1 Image courtesy of NASA").arg(QDate::currentDate().year()); static const QString virtualEarthCopyright = QString("(c)%1 Microsoft Corporation, (c)%1 NAVTEQ, (c)%1 Image courtesy of NASA").arg(QDate::currentDate().year());
static const QString arcGisCopyright = QString("%1 ESRI - Map data %1 ArcGIS").arg(QDate::currentDate().year()); static const QString arcGisCopyright = QString("(c)%1 ESRI - Map data (c)%1 ArcGIS").arg(QDate::currentDate().year());
} }
#endif // COPYRIGHTSTRINGS_H #endif // COPYRIGHTSTRINGS_H
...@@ -169,15 +169,15 @@ QGCCore::QGCCore(bool firstStart, int &argc, char* argv[]) : QApplication(argc, ...@@ -169,15 +169,15 @@ QGCCore::QGCCore(bool firstStart, int &argc, char* argv[]) : QApplication(argc,
// first messages arrive // first messages arrive
udpLink = new UDPLink(QHostAddress::Any, 14550); udpLink = new UDPLink(QHostAddress::Any, 14550);
LinkManager::instance()->add(udpLink); LinkManager::instance()->add(udpLink);
//MainWindow::instance()->addLink(udpLink);
} else if (mainWindow->getCustomMode() == MainWindow::CUSTOM_MODE_PX4) { } else if (mainWindow->getCustomMode() == MainWindow::CUSTOM_MODE_PX4) {
udpLink = new UDPLink(QHostAddress::Any, 14550); udpLink = new UDPLink(QHostAddress::Any, 14550);
LinkManager::instance()->add(udpLink); LinkManager::instance()->add(udpLink);
SerialLink *slink = new SerialLink(); SerialLink *slink = new SerialLink();
LinkManager::instance()->add(slink);
} else { } else {
// We want to have a default serial link available for "quick" connecting. // We want to have a default serial link available for "quick" connecting.
SerialLink *slink = new SerialLink(); SerialLink *slink = new SerialLink();
// MainWindow::instance()->addLink(slink); LinkManager::instance()->add(slink);
} }
#ifdef OPAL_RT #ifdef OPAL_RT
......
...@@ -142,6 +142,7 @@ void SerialLink::run() ...@@ -142,6 +142,7 @@ void SerialLink::run()
//Need to error out here. //Need to error out here.
emit communicationError(getName(),"Error connecting: " + m_port->errorString()); emit communicationError(getName(),"Error connecting: " + m_port->errorString());
disconnect(); // This tidies up and sends the necessary signals disconnect(); // This tidies up and sends the necessary signals
emit communicationError(tr("Serial Port %1").arg(getPortName()), tr("Cannot read / write data - check physical USB and cable connections."));
return; return;
} }
...@@ -152,6 +153,7 @@ void SerialLink::run() ...@@ -152,6 +153,7 @@ void SerialLink::run()
bool triedreset = false; bool triedreset = false;
bool triedDTR = false; bool triedDTR = false;
qint64 timeout = 5000; qint64 timeout = 5000;
int linkErrorCount = 0;
forever forever
{ {
...@@ -173,20 +175,28 @@ void SerialLink::run() ...@@ -173,20 +175,28 @@ void SerialLink::run()
} }
} }
if (m_transmitBuffer.length() > 0) { if (isConnected() && (linkErrorCount > 100)) {
linkErrorCount = 0;
disconnect();
}
if (m_transmitBuffer.count() > 0) {
QMutexLocker writeLocker(&m_writeMutex); QMutexLocker writeLocker(&m_writeMutex);
int numWritten = m_port->write(m_transmitBuffer); int numWritten = m_port->write(m_transmitBuffer);
bool txError = m_port->waitForBytesWritten(-1); bool txSuccess = m_port->waitForBytesWritten(1);
// if ((txError) || (numWritten == -1)) if (!txSuccess || (numWritten != m_transmitBuffer.count()))
// qDebug() << "TX Error!"; {
linkErrorCount++;
qDebug() << "TX Error! wrote" << numWritten << ", asked for " << m_transmitBuffer.count() << "bytes";
} else {
linkErrorCount = 0;
}
m_transmitBuffer = m_transmitBuffer.remove(0, numWritten); m_transmitBuffer = m_transmitBuffer.remove(0, numWritten);
} else {
// qDebug() << "Wait write response timeout %1" << QTime::currentTime().toString();
} }
bool error = m_port->waitForReadyRead(10); bool success = m_port->waitForReadyRead(10);
if(error) { // Waits for 1/2 second [TODO][BB] lower to SerialLink::poll_interval? if (success) { // Waits for 1/2 second [TODO][BB] lower to SerialLink::poll_interval?
QByteArray readData = m_port->readAll(); QByteArray readData = m_port->readAll();
while (m_port->waitForReadyRead(10)) while (m_port->waitForReadyRead(10))
readData += m_port->readAll(); readData += m_port->readAll();
...@@ -196,9 +206,11 @@ void SerialLink::run() ...@@ -196,9 +206,11 @@ void SerialLink::run()
m_bytesRead += readData.length(); m_bytesRead += readData.length();
m_bitsReceivedTotal += readData.length() * 8; m_bitsReceivedTotal += readData.length() * 8;
linkErrorCount = 0;
} }
} else { } else {
// qDebug() << "Wait write response timeout %1" << QTime::currentTime().toString(); linkErrorCount++;
qDebug() << "Wait read response timeout" << QTime::currentTime().toString();
} }
if (bytes != m_bytesRead) // i.e things are good and data is being read. if (bytes != m_bytesRead) // i.e things are good and data is being read.
......
...@@ -11,7 +11,7 @@ ...@@ -11,7 +11,7 @@
#define WITH_TEXT_TO_SPEECH 1 #define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl" #define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 1.1.1 (beta)" #define QGC_APPLICATION_VERSION "v. 1.1.2 (beta)"
namespace QGC namespace QGC
......
...@@ -1975,13 +1975,23 @@ void UAS::setMode(int mode) ...@@ -1975,13 +1975,23 @@ void UAS::setMode(int mode)
*/ */
void UAS::sendMessage(mavlink_message_t message) void UAS::sendMessage(mavlink_message_t message)
{ {
if (!LinkManager::instance()) return; if (!LinkManager::instance())
{
qWarning() << "LINKMANAGER NOT AVAILABLE!";
return;
}
if (links->count() < 1) {
qDebug() << "NO LINK AVAILABLE TO SEND!";
}
// Emit message on all links that are currently connected // Emit message on all links that are currently connected
foreach (LinkInterface* link, *links) foreach (LinkInterface* link, *links)
{ {
if (LinkManager::instance()->getLinks().contains(link)) if (LinkManager::instance()->getLinks().contains(link))
{ {
sendMessage(link, message); sendMessage(link, message);
qDebug() << "SENT MESSAGE!";
} }
else else
{ {
...@@ -2034,12 +2044,17 @@ void UAS::sendMessage(LinkInterface* link, mavlink_message_t message) ...@@ -2034,12 +2044,17 @@ void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
int len = mavlink_msg_to_send_buffer(buffer, &message); int len = mavlink_msg_to_send_buffer(buffer, &message);
static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS; static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]); mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
// If link is connected // If link is connected
if (link->isConnected()) if (link->isConnected())
{ {
// Send the portion of the buffer now occupied by the message // Send the portion of the buffer now occupied by the message
link->writeBytes((const char*)buffer, len); link->writeBytes((const char*)buffer, len);
} }
else
{
qDebug() << "LINK NOT CONNECTED, NOT SENDING!";
}
} }
/** /**
...@@ -2232,7 +2247,7 @@ void UAS::requestParameters() ...@@ -2232,7 +2247,7 @@ void UAS::requestParameters()
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL); mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
sendMessage(msg); sendMessage(msg);
qDebug() << __FILE__ << __LINE__ << "LOADING PARAM LIST"; qDebug() << __FILE__ << ":" << __LINE__ << "LOADING PARAM LIST";
} }
void UAS::writeParametersToStorage() void UAS::writeParametersToStorage()
......
...@@ -217,6 +217,7 @@ void DebugConsole::removeLink(LinkInterface* const linkInterface) ...@@ -217,6 +217,7 @@ void DebugConsole::removeLink(LinkInterface* const linkInterface)
} }
void DebugConsole::linkStatusUpdate(const QString& name,const QString& text) void DebugConsole::linkStatusUpdate(const QString& name,const QString& text)
{ {
Q_UNUSED(name);
m_ui->receiveText->appendPlainText(text); m_ui->receiveText->appendPlainText(text);
// Ensure text area scrolls correctly // Ensure text area scrolls correctly
m_ui->receiveText->ensureCursorVisible(); m_ui->receiveText->ensureCursorVisible();
...@@ -579,7 +580,7 @@ QString DebugConsole::bytesToSymbolNames(const QByteArray& b) ...@@ -579,7 +580,7 @@ QString DebugConsole::bytesToSymbolNames(const QByteArray& b)
} else if (b.contains(0x09)) { } else if (b.contains(0x09)) {
text = "<TAB>"; text = "<TAB>";
} else if (b.contains((char)0x00)) { } else if (b.contains((char)0x00)) {
text == "<NUL>"; text = "<NUL>";
} else if (b.contains(0x1B)) { } else if (b.contains(0x1B)) {
text = "<ESC>"; text = "<ESC>";
} else if (b.contains(0x7E)) { } else if (b.contains(0x7E)) {
...@@ -688,7 +689,7 @@ void DebugConsole::sendBytes() ...@@ -688,7 +689,7 @@ void DebugConsole::sendBytes()
str.append(specialSymbol); str.append(specialSymbol);
str.remove(' '); str.remove(' ');
str.remove("0x"); str.remove("0x");
str.simplified(); str = str.simplified();
int bufferIndex = 0; int bufferIndex = 0;
if ((str.size() % 2) == 0) { if ((str.size() % 2) == 0) {
for (int i = 0; i < str.size(); i=i+2) { for (int i = 0; i < str.size(); i=i+2) {
......
...@@ -36,6 +36,8 @@ This file is part of the QGROUNDCONTROL project ...@@ -36,6 +36,8 @@ This file is part of the QGROUNDCONTROL project
#include "QGCSensorSettingsWidget.h" #include "QGCSensorSettingsWidget.h"
#include <QDebug> #include <QDebug>
#include <QSettings>
#include "MainWindow.h"
ParameterInterface::ParameterInterface(QWidget *parent) : ParameterInterface::ParameterInterface(QWidget *parent) :
QWidget(parent), QWidget(parent),
...@@ -45,6 +47,15 @@ ParameterInterface::ParameterInterface(QWidget *parent) : ...@@ -45,6 +47,15 @@ ParameterInterface::ParameterInterface(QWidget *parent) :
{ {
m_ui->setupUi(this); m_ui->setupUi(this);
QSettings settings;
enum MainWindow::CUSTOM_MODE mode = static_cast<enum MainWindow::CUSTOM_MODE>(settings.value("QGC_CUSTOM_MODE", MainWindow::CUSTOM_MODE_NONE).toInt());
if (mode == MainWindow::CUSTOM_MODE_PX4)
{
delete m_ui->sensorSettings;
m_ui->sensorSettings = NULL;
}
// Get current MAV list // Get current MAV list
QList<UASInterface*> systems = UASManager::instance()->getUASList(); QList<UASInterface*> systems = UASManager::instance()->getUASList();
...@@ -67,7 +78,8 @@ ParameterInterface::~ParameterInterface() ...@@ -67,7 +78,8 @@ ParameterInterface::~ParameterInterface()
void ParameterInterface::selectUAS(int index) void ParameterInterface::selectUAS(int index)
{ {
m_ui->stackedWidget->setCurrentIndex(index); m_ui->stackedWidget->setCurrentIndex(index);
m_ui->sensorSettings->setCurrentIndex(index); if (m_ui->sensorSettings)
m_ui->sensorSettings->setCurrentIndex(index);
curr = index; curr = index;
} }
...@@ -81,14 +93,19 @@ void ParameterInterface::addUAS(UASInterface* uas) ...@@ -81,14 +93,19 @@ void ParameterInterface::addUAS(UASInterface* uas)
paramWidgets->insert(uas->getUASID(), param); paramWidgets->insert(uas->getUASID(), param);
m_ui->stackedWidget->addWidget(param); m_ui->stackedWidget->addWidget(param);
QGCSensorSettingsWidget* sensor = NULL;
QGCSensorSettingsWidget* sensor = new QGCSensorSettingsWidget(uas, this); if (m_ui->sensorSettings)
m_ui->sensorSettings->addWidget(sensor); {
sensor = new QGCSensorSettingsWidget(uas, this);
m_ui->sensorSettings->addWidget(sensor);
}
// Set widgets as default // Set widgets as default
if (curr == -1) { if (curr == -1) {
// Clear // Clear
m_ui->sensorSettings->setCurrentWidget(sensor); if (m_ui->sensorSettings && sensor)
m_ui->sensorSettings->setCurrentWidget(sensor);
m_ui->stackedWidget->setCurrentWidget(param); m_ui->stackedWidget->setCurrentWidget(param);
curr = 0; curr = 0;
} }
......
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