Browse Source

Minor cleanups

QGC4.4
Lorenz Meier 13 years ago
parent
commit
a9a7dc9f27
  1. 20
      src/QGCCore.cc
  2. 34
      src/comm/LinkManager.cc
  3. 8
      src/comm/MAVLinkProtocol.cc
  4. 56
      src/comm/MAVLinkSimulationLink.cc
  5. 6
      src/uas/UAS.cc
  6. 19
      src/ui/MainWindow.cc
  7. 4
      src/ui/QGCParamWidget.cc

20
src/QGCCore.cc

@ -84,16 +84,20 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
// Show user an upgrade message if QGC got upgraded (see code below, after splash screen) // Show user an upgrade message if QGC got upgraded (see code below, after splash screen)
bool upgraded = false; bool upgraded = false;
QString lastApplicationVersion(""); QString lastApplicationVersion("");
if (settings.contains("QGC_APPLICATION_VERSION")) { if (settings.contains("QGC_APPLICATION_VERSION"))
{
QString qgcVersion = settings.value("QGC_APPLICATION_VERSION").toString(); QString qgcVersion = settings.value("QGC_APPLICATION_VERSION").toString();
if (qgcVersion != QGC_APPLICATION_VERSION) { if (qgcVersion != QGC_APPLICATION_VERSION)
{
lastApplicationVersion = qgcVersion; lastApplicationVersion = qgcVersion;
settings.clear(); settings.clear();
// Write current application version // Write current application version
settings.setValue("QGC_APPLICATION_VERSION", QGC_APPLICATION_VERSION); settings.setValue("QGC_APPLICATION_VERSION", QGC_APPLICATION_VERSION);
upgraded = true; upgraded = true;
} }
} else { }
else
{
// If application version is not set, clear settings anyway // If application version is not set, clear settings anyway
settings.clear(); settings.clear();
// Write current application version // Write current application version
@ -117,7 +121,7 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
// Load application font // Load application font
QFontDatabase fontDatabase = QFontDatabase(); QFontDatabase fontDatabase = QFontDatabase();
const QString fontFileName = ":/general/vera.ttf"; ///< Font file is part of the QRC file and compiled into the app const QString fontFileName = ":/general/vera.ttf"; ///< Font file is part of the QRC file and compiled into the app
const QString fontFamilyName = "Bitstream Vera Sans"; //const QString fontFamilyName = "Bitstream Vera Sans";
if(!QFile::exists(fontFileName)) printf("ERROR! font file: %s DOES NOT EXIST!\n", fontFileName.toStdString().c_str()); if(!QFile::exists(fontFileName)) printf("ERROR! font file: %s DOES NOT EXIST!\n", fontFileName.toStdString().c_str());
fontDatabase.addApplicationFont(fontFileName); fontDatabase.addApplicationFont(fontFileName);
// Avoid Using setFont(). In the Qt docu you can read the following: // Avoid Using setFont(). In the Qt docu you can read the following:
@ -132,9 +136,6 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
splashScreen->showMessage(tr("Starting UAS Manager"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); splashScreen->showMessage(tr("Starting UAS Manager"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141));
startUASManager(); startUASManager();
//tarsus = new ViconTarsusProtocol();
//tarsus->start();
// Start the user interface // Start the user interface
splashScreen->showMessage(tr("Starting User Interface"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); splashScreen->showMessage(tr("Starting User Interface"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141));
// Start UI // Start UI
@ -147,17 +148,14 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
// Listen on Multicast-Address 239.255.77.77, Port 14550 // Listen on Multicast-Address 239.255.77.77, Port 14550
//QHostAddress * multicast_udp = new QHostAddress("239.255.77.77"); //QHostAddress * multicast_udp = new QHostAddress("239.255.77.77");
//UDPLink* udpLink = new UDPLink(*multicast_udp, 14550); //UDPLink* udpLink = new UDPLink(*multicast_udp, 14550);
//mainWindow->addLink(udpLink);
#ifdef OPAL_RT #ifdef OPAL_RT
// Add OpalRT Link, but do not connect // Add OpalRT Link, but do not connect
OpalLink* opalLink = new OpalLink(); OpalLink* opalLink = new OpalLink();
//mainWindow->addLink(opalLink); MainWindow::instance()->addLink(opalLink);
#endif #endif
// MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(":/demo-log.txt"); MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(":/demo-log.txt");
simulationLink->disconnect(); simulationLink->disconnect();
//mainWindow->addLink(simulationLink);
mainWindow = MainWindow::instance(splashScreen); mainWindow = MainWindow::instance(splashScreen);

34
src/comm/LinkManager.cc

@ -63,11 +63,16 @@ LinkManager::LinkManager()
LinkManager::~LinkManager() LinkManager::~LinkManager()
{ {
disconnectAll(); disconnectAll();
foreach (LinkInterface* link, links)
{
if(link) link->deleteLater();
}
} }
void LinkManager::add(LinkInterface* link) void LinkManager::add(LinkInterface* link)
{ {
if (!links.contains(link)) { if (!links.contains(link))
{
if(!link) return; if(!link) return;
connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*))); connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
links.append(link); links.append(link);
@ -85,7 +90,8 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol)
// If protocol has not been added before (list length == 0) // If protocol has not been added before (list length == 0)
// OR if link has not been added to protocol, add // OR if link has not been added to protocol, add
if ((linkList.length() > 0 && !linkList.contains(link)) || linkList.length() == 0) { if ((linkList.length() > 0 && !linkList.contains(link)) || linkList.length() == 0)
{
// Protocol is new, add // Protocol is new, add
connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray))); connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray)));
// Store the connection information in the protocol links map // Store the connection information in the protocol links map
@ -104,7 +110,8 @@ bool LinkManager::connectAll()
{ {
bool allConnected = true; bool allConnected = true;
foreach (LinkInterface* link, links) { foreach (LinkInterface* link, links)
{
if(!link) {} if(!link) {}
else if(!link->connect()) allConnected = false; else if(!link->connect()) allConnected = false;
} }
@ -116,7 +123,8 @@ bool LinkManager::disconnectAll()
{ {
bool allDisconnected = true; bool allDisconnected = true;
foreach (LinkInterface* link, links) { foreach (LinkInterface* link, links)
{
//static int i=0; //static int i=0;
if(!link) {} if(!link) {}
else if(!link->disconnect()) allDisconnected = false; else if(!link->disconnect()) allDisconnected = false;
@ -140,22 +148,27 @@ bool LinkManager::disconnectLink(LinkInterface* link)
void LinkManager::removeLink(QObject* link) void LinkManager::removeLink(QObject* link)
{ {
LinkInterface* linkInterface = dynamic_cast<LinkInterface*>(link); LinkInterface* linkInterface = dynamic_cast<LinkInterface*>(link);
if (linkInterface) { if (linkInterface)
{
removeLink(linkInterface); removeLink(linkInterface);
} }
} }
bool LinkManager::removeLink(LinkInterface* link) bool LinkManager::removeLink(LinkInterface* link)
{ {
if(link) { if(link)
for (int i=0; i < QList<LinkInterface*>(links).size(); i++) { {
if(link==links.at(i)) { for (int i=0; i < QList<LinkInterface*>(links).size(); i++)
{
if(link==links.at(i))
{
links.removeAt(i); //remove from link list links.removeAt(i); //remove from link list
} }
} }
// Remove link from protocol map // Remove link from protocol map
QList<ProtocolInterface* > protocols = protocolLinks.keys(link); QList<ProtocolInterface* > protocols = protocolLinks.keys(link);
foreach (ProtocolInterface* proto, protocols) { foreach (ProtocolInterface* proto, protocols)
{
protocolLinks.remove(proto, link); protocolLinks.remove(proto, link);
} }
return true; return true;
@ -171,7 +184,8 @@ bool LinkManager::removeLink(LinkInterface* link)
*/ */
LinkInterface* LinkManager::getLinkForId(int id) LinkInterface* LinkManager::getLinkForId(int id)
{ {
foreach (LinkInterface* link, links) { foreach (LinkInterface* link, links)
{
if (link->getId() == id) return link; if (link->getId() == id) return link;
} }
return NULL; return NULL;

8
src/comm/MAVLinkProtocol.cc

@ -470,7 +470,7 @@ void MAVLinkProtocol::sendMessage(mavlink_message_t message)
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message) void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message)
{ {
// Create buffer // Create buffer
uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
// Rewriting header to ensure correct link ID is set // Rewriting header to ensure correct link ID is set
static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS; static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
if (link->getId() != 0) mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]); if (link->getId() != 0) mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
@ -491,12 +491,14 @@ void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message
*/ */
void MAVLinkProtocol::sendHeartbeat() void MAVLinkProtocol::sendHeartbeat()
{ {
if (m_heartbeatsEnabled) { if (m_heartbeatsEnabled)
{
mavlink_message_t beat; mavlink_message_t beat;
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL_ARMED, 0, MAV_STATE_ACTIVE); mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL_ARMED, 0, MAV_STATE_ACTIVE);
sendMessage(beat); sendMessage(beat);
} }
if (m_authEnabled) { if (m_authEnabled)
{
mavlink_message_t msg; mavlink_message_t msg;
mavlink_auth_key_t auth; mavlink_auth_key_t auth;
if (m_authKey.length() != MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN) m_authKey.resize(MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN); if (m_authKey.length() != MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN) m_authKey.resize(MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN);

56
src/comm/MAVLinkSimulationLink.cc

@ -84,15 +84,19 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile
// Comments on the variables can be found in the header file // Comments on the variables can be found in the header file
simulationFile = new QFile(readFile, this); simulationFile = new QFile(readFile, this);
if (simulationFile->exists() && simulationFile->open(QIODevice::ReadOnly | QIODevice::Text)) { if (simulationFile->exists() && simulationFile->open(QIODevice::ReadOnly | QIODevice::Text))
{
simulationHeader = simulationFile->readLine(); simulationHeader = simulationFile->readLine();
} }
receiveFile = new QFile(writeFile, this); receiveFile = new QFile(writeFile, this);
lastSent = QGC::groundTimeMilliseconds(); lastSent = QGC::groundTimeMilliseconds();
if (simulationFile->exists()) { if (simulationFile->exists())
{
this->name = "Simulation: " + QFileInfo(simulationFile->fileName()).fileName(); this->name = "Simulation: " + QFileInfo(simulationFile->fileName()).fileName();
} else { }
else
{
this->name = "MAVLink simulation link"; this->name = "MAVLink simulation link";
} }
@ -111,6 +115,11 @@ MAVLinkSimulationLink::~MAVLinkSimulationLink()
//TODO Check destructor //TODO Check destructor
// fileStream->flush(); // fileStream->flush();
// outStream->flush(); // outStream->flush();
// Force termination, there is no
// need for cleanup since
// this thread is not manipulating
// any relevant data
terminate();
delete simulationFile; delete simulationFile;
} }
@ -124,28 +133,26 @@ void MAVLinkSimulationLink::run()
system.custom_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_SAFETY_ARMED; system.custom_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_SAFETY_ARMED;
system.system_status = MAV_STATE_UNINIT; system.system_status = MAV_STATE_UNINIT;
forever { forever
{
static quint64 last = 0; static quint64 last = 0;
if (QGC::groundTimeMilliseconds() - last >= rate) { if (QGC::groundTimeMilliseconds() - last >= rate)
if (_isConnected) { {
if (_isConnected)
{
mainloop(); mainloop();
// FIXME Hacky code to read from packet log file
// readyBufferMutex.lock();
// for (int i = 0; i < streampointer; i++)
// {
// readyBuffer.enqueue(*(stream + i));
// }
// readyBufferMutex.unlock();
readBytes(); readBytes();
} }
else
{
// Sleep for substantially longer
// if not connected
QGC::SLEEP::msleep(500);
}
last = QGC::groundTimeMilliseconds(); last = QGC::groundTimeMilliseconds();
} }
QGC::SLEEP::msleep(3); QGC::SLEEP::msleep(3);
} }
} }
@ -157,7 +164,8 @@ void MAVLinkSimulationLink::sendMAVLinkMessage(const mavlink_message_t* msg)
// Pack to link buffer // Pack to link buffer
readyBufferMutex.lock(); readyBufferMutex.lock();
for (unsigned int i = 0; i < bufferlength; i++) { for (unsigned int i = 0; i < bufferlength; i++)
{
readyBuffer.enqueue(*(buf + i)); readyBuffer.enqueue(*(buf + i));
} }
readyBufferMutex.unlock(); readyBufferMutex.unlock();
@ -217,14 +225,17 @@ void MAVLinkSimulationLink::mainloop()
static int state = 0; static int state = 0;
if (state == 0) { if (state == 0)
{
state++; state++;
} }
// 50 HZ TASKS // 50 HZ TASKS
if (rate50hzCounter == 1000 / rate / 40) { if (rate50hzCounter == 1000 / rate / 40)
if (simulationFile->isOpen()) { {
if (simulationFile->isOpen())
{
if (simulationFile->atEnd()) { if (simulationFile->atEnd()) {
// We reached the end of the file, start from scratch // We reached the end of the file, start from scratch
simulationFile->reset(); simulationFile->reset();
@ -916,7 +927,8 @@ void MAVLinkSimulationLink::readBytes()
bool MAVLinkSimulationLink::disconnect() bool MAVLinkSimulationLink::disconnect()
{ {
if(isConnected()) { if(isConnected())
{
// timer->stop(); // timer->stop();
_isConnected = false; _isConnected = false;

6
src/uas/UAS.cc

@ -142,7 +142,8 @@ void UAS::readSettings()
this->name = settings.value("NAME", this->name).toString(); this->name = settings.value("NAME", this->name).toString();
this->airframe = settings.value("AIRFRAME", this->airframe).toInt(); this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt(); this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
if (settings.contains("BATTERY_SPECS")) { if (settings.contains("BATTERY_SPECS"))
{
setBatterySpecs(settings.value("BATTERY_SPECS").toString()); setBatterySpecs(settings.value("BATTERY_SPECS").toString());
} }
settings.endGroup(); settings.endGroup();
@ -1479,9 +1480,11 @@ void UAS::sendMessage(mavlink_message_t message)
// 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)
{ {
qDebug() << "ITERATING THROUGH LINKS";
if (link) if (link)
{ {
sendMessage(link, message); sendMessage(link, message);
qDebug() << "SENT MESSAGE";
} }
else else
{ {
@ -1716,6 +1719,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";
} }
void UAS::writeParametersToStorage() void UAS::writeParametersToStorage()

19
src/ui/MainWindow.cc

@ -234,8 +234,21 @@ MainWindow::MainWindow(QWidget *parent):
MainWindow::~MainWindow() MainWindow::~MainWindow()
{ {
if (mavlink)
{
delete mavlink; delete mavlink;
mavlink = NULL;
}
// if (simulationLink)
// {
// simulationLink->deleteLater();
// simulationLink = NULL;
// }
if (joystick)
{
delete joystick; delete joystick;
joystick = NULL;
}
// Get and delete all dockwidgets and contained // Get and delete all dockwidgets and contained
// widgets // widgets
@ -252,10 +265,12 @@ MainWindow::~MainWindow()
// removeDockWidget(dockWidget); // removeDockWidget(dockWidget);
// delete dockWidget->widget(); // delete dockWidget->widget();
delete dockWidget; delete dockWidget;
dockWidget = NULL;
} }
else if (dynamic_cast<QObject*>(*i)) else if (dynamic_cast<QWidget*>(*i))
{ {
delete dynamic_cast<QObject*>(*i); delete dynamic_cast<QWidget*>(*i);
*i = NULL;
} }
} }
// Delete all UAS objects // Delete all UAS objects

4
src/ui/QGCParamWidget.cc

@ -590,7 +590,6 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
*/ */
void QGCParamWidget::requestParameterList() void QGCParamWidget::requestParameterList()
{ {
qDebug() << "LOADING PARAM LIST";
if (!mav) return; if (!mav) return;
// FIXME This call does not belong here // FIXME This call does not belong here
// Once the comm handling is moved to a new // Once the comm handling is moved to a new
@ -606,7 +605,8 @@ void QGCParamWidget::requestParameterList()
// Clear transmission state // Clear transmission state
transmissionListMode = true; transmissionListMode = true;
transmissionListSizeKnown.clear(); transmissionListSizeKnown.clear();
foreach (int key, transmissionMissingPackets.keys()) { foreach (int key, transmissionMissingPackets.keys())
{
transmissionMissingPackets.value(key)->clear(); transmissionMissingPackets.value(key)->clear();
} }
transmissionActive = true; transmissionActive = true;

Loading…
Cancel
Save