Browse Source

Merge remote-tracking branch 'upstream/master' into fgfsrate

QGC4.4
Thomas Gubler 11 years ago
parent
commit
bfae98b7e3
  1. 5
      QGCExternalLibs.pri
  2. 10
      qgroundcontrol.pro
  3. 59
      src/CmdLineOptParser.cc
  4. 46
      src/CmdLineOptParser.h
  5. 22
      src/QGCCore.cc
  6. 2
      src/comm/LinkInterface.h
  7. 30
      src/comm/MAVLinkProtocol.cc
  8. 4
      src/comm/MAVLinkProtocol.h
  9. 10
      src/comm/QGCXPlaneLink.cc
  10. 1
      src/comm/QGCXPlaneLink.h
  11. 2
      src/configuration.h
  12. 45
      src/main.cc
  13. 10
      src/qgcunittest/UASUnitTest.cc
  14. 18
      src/uas/QGCMAVLinkUASFactory.cc
  15. 24
      src/uas/QGCUASWorker.cc
  16. 20
      src/uas/QGCUASWorker.h
  17. 37
      src/uas/UAS.cc
  18. 3
      src/uas/UAS.h
  19. 3
      src/ui/MainWindow.cc
  20. 60
      src/ui/PrimaryFlightDisplay.cc
  21. 6
      src/ui/PrimaryFlightDisplay.h
  22. 3
      src/ui/QGCHilXPlaneConfiguration.cc
  23. 1
      src/ui/QGCMAVLinkLogPlayer.cc

5
QGCExternalLibs.pri

@ -416,9 +416,10 @@ contains(DEFINES, DISABLE_3DMOUSE) { @@ -416,9 +416,10 @@ contains(DEFINES, DISABLE_3DMOUSE) {
exists(/usr/local/lib/libxdrvlib.so) {
message("Including support for 3DConnexion mice")
DEFINES +=
DEFINES += \
QGC_MOUSE_ENABLED_LINUX \
ParameterCheck # Hack: Has to be defined for magellan usage
ParameterCheck
# Hack: Has to be defined for magellan usage
HEADERS += src/input/Mouse6dofInput.h
SOURCES += src/input/Mouse6dofInput.cpp

10
qgroundcontrol.pro

@ -187,7 +187,6 @@ DebugBuild { @@ -187,7 +187,6 @@ DebugBuild {
src/qgcunittest/MockUAS.h \
src/qgcunittest/MockQGCUASParamManager.h \
src/qgcunittest/MultiSignalSpy.h \
src/qgcunittest/TCPLinkTest.h \
src/qgcunittest/FlightModeConfigTest.h
SOURCES += \
@ -196,7 +195,6 @@ DebugBuild { @@ -196,7 +195,6 @@ DebugBuild {
src/qgcunittest/MockUAS.cc \
src/qgcunittest/MockQGCUASParamManager.cc \
src/qgcunittest/MultiSignalSpy.cc \
src/qgcunittest/TCPLinkTest.cc \
src/qgcunittest/FlightModeConfigTest.cc
}
@ -562,7 +560,9 @@ HEADERS += \ @@ -562,7 +560,9 @@ HEADERS += \
src/ui/designer/QGCXYPlot.h \
src/ui/menuactionhelper.h \
src/uas/UASManagerInterface.h \
src/uas/QGCUASParamManagerInterface.h
src/uas/QGCUASParamManagerInterface.h \
src/uas/QGCUASWorker.h \
src/CmdLineOptParser.h
SOURCES += \
src/main.cc \
@ -745,4 +745,6 @@ SOURCES += \ @@ -745,4 +745,6 @@ SOURCES += \
src/ui/px4_configuration/QGCPX4MulticopterConfig.cc \
src/ui/px4_configuration/QGCPX4SensorCalibration.cc \
src/ui/designer/QGCXYPlot.cc \
src/ui/menuactionhelper.cpp
src/ui/menuactionhelper.cpp \
src/uas/QGCUASWorker.cc \
src/CmdLineOptParser.cc

59
src/CmdLineOptParser.cc

@ -0,0 +1,59 @@ @@ -0,0 +1,59 @@
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @brief Command line option parser
///
/// @author Don Gagne <don@thegagnes.com>
#include "CmdLineOptParser.h"
#include <QString>
/// @brief Implements a simple command line parser which sets booleans to true if the option is found.
void ParseCmdLineOptions(int& argc, ///< count of arguments in argv
char* argv[], ///< command line arguments
CmdLineOpt_t* prgOpts, ///< command line options
size_t cOpts, ///< count of command line options
bool removeParsedOptions) ///< true: remove parsed option from argc/argv
{
// Start with all options off
for (size_t iOption=0; iOption<cOpts; iOption++) {
*prgOpts[iOption].flag = false;
}
for (int iArg=1; iArg<argc; iArg++) {
for (size_t iOption=0; iOption<cOpts; iOption++) {
if (QString(argv[iArg]).compare(prgOpts[iOption].optionStr, Qt::CaseInsensitive) == 0) {
*prgOpts[iOption].flag = true;
if (removeParsedOptions) {
for (int iShift=iArg; iShift<argc-1; iShift++) {
argv[iShift] = argv[iShift+1];
}
argc--;
iArg--;
}
}
}
}
}

46
src/CmdLineOptParser.h

@ -0,0 +1,46 @@ @@ -0,0 +1,46 @@
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @brief Command line option parser
///
/// @author Don Gagne <don@thegagnes.com>
#ifndef CMDLINEOPTPARSER_H
#define CMDLINEOPTPARSER_H
#include <cstring>
/// @brief Structure used to pass command line options to the ParseCmdLineOptions function.
typedef struct {
const char* optionStr; ///< command line option, for example "--foo"
bool* flag; ///< if option is found this variable will be set to true
} CmdLineOpt_t;
void ParseCmdLineOptions(int& argc,
char* argv[],
CmdLineOpt_t* prgOpts,
size_t cOpts,
bool removeParsedOptions);
#endif

22
src/QGCCore.cc

@ -47,6 +47,7 @@ This file is part of the QGROUNDCONTROL project @@ -47,6 +47,7 @@ This file is part of the QGROUNDCONTROL project
#include "MainWindow.h"
#include "QGCWelcomeMainWindow.h"
#include "GAudioOutput.h"
#include "CmdLineOptParser.h"
#ifdef QGC_RTLAB_ENABLED
#include "OpalLink.h"
@ -83,11 +84,24 @@ QGCCore::QGCCore(bool firstStart, int &argc, char* argv[]) : QApplication(argc, @@ -83,11 +84,24 @@ QGCCore::QGCCore(bool firstStart, int &argc, char* argv[]) : QApplication(argc,
// Set settings format
QSettings::setDefaultFormat(QSettings::IniFormat);
// Check application settings
// clear them if they mismatch
// QGC then falls back to default
// Parse command line options
bool fClearSettingsOptions = false; // Clear stored settings
CmdLineOpt_t rgCmdLineOptions[] = {
{ "--clear-settings", &fClearSettingsOptions },
// Add additional command line option flags here
};
ParseCmdLineOptions(argc, argv, rgCmdLineOptions, sizeof(rgCmdLineOptions)/sizeof(rgCmdLineOptions[0]), false);
QSettings settings;
if (fClearSettingsOptions) {
// User requested settings to be cleared on command line
settings.clear();
}
// Show user an upgrade message if QGC got upgraded (see code below, after splash screen)
bool upgraded = false;
enum MainWindow::CUSTOM_MODE mode = MainWindow::CUSTOM_MODE_NONE;
@ -98,7 +112,7 @@ QGCCore::QGCCore(bool firstStart, int &argc, char* argv[]) : QApplication(argc, @@ -98,7 +112,7 @@ QGCCore::QGCCore(bool firstStart, int &argc, char* argv[]) : QApplication(argc,
if (qgcVersion != QGC_APPLICATION_VERSION)
{
lastApplicationVersion = qgcVersion;
settings.clear();
settings.clear(); // Clear settings from different version
// Write current application version
settings.setValue("QGC_APPLICATION_VERSION", QGC_APPLICATION_VERSION);
upgraded = true;

2
src/comm/LinkInterface.h

@ -36,6 +36,7 @@ along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>. @@ -36,6 +36,7 @@ along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
#include <QDateTime>
#include <QMutex>
#include <QMutexLocker>
#include <QMetaType>
/**
* The link interface defines the interface for all links used to communicate
@ -62,6 +63,7 @@ public: @@ -62,6 +63,7 @@ public:
outDataWriteTimes[i] = 0;
}
qRegisterMetaType<LinkInterface*>("LinkInterface*");
}
virtual ~LinkInterface() {

30
src/comm/MAVLinkProtocol.cc

@ -44,7 +44,7 @@ Q_DECLARE_METATYPE(mavlink_message_t) @@ -44,7 +44,7 @@ Q_DECLARE_METATYPE(mavlink_message_t)
* the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
*/
MAVLinkProtocol::MAVLinkProtocol() :
heartbeatTimer(),
heartbeatTimer(NULL),
heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
m_heartbeatsEnabled(true),
m_multiplexingEnabled(false),
@ -58,17 +58,14 @@ MAVLinkProtocol::MAVLinkProtocol() : @@ -58,17 +58,14 @@ MAVLinkProtocol::MAVLinkProtocol() :
m_actionGuardEnabled(false),
m_actionRetransmissionTimeout(100),
versionMismatchIgnore(false),
systemId(QGC::defaultSystemId)
systemId(QGC::defaultSystemId),
_should_exit(false)
{
qRegisterMetaType<mavlink_message_t>("mavlink_message_t");
m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
loadSettings();
moveToThread(this);
heartbeatTimer.moveToThread(this);
// Start heartbeat timer, emitting a heartbeat at the configured rate
connect(&heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat()));
heartbeatTimer.start(1000/heartbeatRate);
// All the *Counter variables are not initialized here, as they should be initialized
// on a per-link basis before those links are used. @see resetMetadataForLink().
@ -171,7 +168,7 @@ MAVLinkProtocol::~MAVLinkProtocol() @@ -171,7 +168,7 @@ MAVLinkProtocol::~MAVLinkProtocol()
}
// Tell the thread to exit
quit();
_should_exit = true;
// Wait for it to exit
wait();
}
@ -182,7 +179,22 @@ MAVLinkProtocol::~MAVLinkProtocol() @@ -182,7 +179,22 @@ MAVLinkProtocol::~MAVLinkProtocol()
**/
void MAVLinkProtocol::run()
{
exec();
heartbeatTimer = new QTimer();
heartbeatTimer->moveToThread(this);
// Start heartbeat timer, emitting a heartbeat at the configured rate
connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat()));
heartbeatTimer->start(1000/heartbeatRate);
while(!_should_exit) {
if (isFinished()) {
qDebug() << "MAVLINK WORKER DONE!";
return;
}
QCoreApplication::processEvents();
QGC::SLEEP::msleep(2);
}
}
QString MAVLinkProtocol::getLogfileName()
@ -782,7 +794,7 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled) @@ -782,7 +794,7 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled)
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
heartbeatRate = rate;
heartbeatTimer.setInterval(1000/heartbeatRate);
heartbeatTimer->setInterval(1000/heartbeatRate);
}
/** @return heartbeat rate in Hertz */

4
src/comm/MAVLinkProtocol.h

@ -214,7 +214,7 @@ public slots: @@ -214,7 +214,7 @@ public slots:
void storeSettings();
protected:
QTimer heartbeatTimer; ///< Timer to emit heartbeats
QTimer *heartbeatTimer; ///< Timer to emit heartbeats
int heartbeatRate; ///< Heartbeat rate, controls the timer interval
bool m_heartbeatsEnabled; ///< Enabled/disable heartbeat emission
bool m_multiplexingEnabled; ///< Enable/disable packet multiplexing
@ -237,6 +237,8 @@ protected: @@ -237,6 +237,8 @@ protected:
int currLossCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< Lost messages during this sample time window. Used for calculating loss %.
bool versionMismatchIgnore;
int systemId;
bool _should_exit;
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
mavlink::ProtobufManager protobufManager;
#endif

10
src/comm/QGCXPlaneLink.cc

@ -57,7 +57,8 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress @@ -57,7 +57,8 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress
simUpdateLastText(QGC::groundTimeMilliseconds()),
simUpdateLastGroundTruth(QGC::groundTimeMilliseconds()),
simUpdateHz(0),
_sensorHilEnabled(true)
_sensorHilEnabled(true),
_should_exit(false)
{
// We're doing it wrong - because the Qt folks got the API wrong:
// http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/
@ -75,7 +76,7 @@ QGCXPlaneLink::~QGCXPlaneLink() @@ -75,7 +76,7 @@ QGCXPlaneLink::~QGCXPlaneLink()
{
storeSettings();
// Tell the thread to exit
quit();
_should_exit = true;
// Wait for it to exit
wait();
@ -216,7 +217,10 @@ void QGCXPlaneLink::run() @@ -216,7 +217,10 @@ void QGCXPlaneLink::run()
writeBytes((const char*)&ip, sizeof(ip));
exec();
while(!_should_exit) {
QCoreApplication::processEvents();
QGC::SLEEP::msleep(5);
}
}
void QGCXPlaneLink::setPort(int localPort)

1
src/comm/QGCXPlaneLink.h

@ -210,6 +210,7 @@ protected: @@ -210,6 +210,7 @@ protected:
quint64 simUpdateLastGroundTruth;
float simUpdateHz;
bool _sensorHilEnabled;
bool _should_exit;
void setName(QString name);
};

2
src/configuration.h

@ -4,7 +4,7 @@ @@ -4,7 +4,7 @@
#include <QString>
/** @brief Polling interval in ms */
#define SERIAL_POLL_INTERVAL 5
#define SERIAL_POLL_INTERVAL 4
/** @brief Heartbeat emission rate, in Hertz (times per second) */
#define MAVLINK_HEARTBEAT_DEFAULT_RATE 1

45
src/main.cc

@ -36,6 +36,10 @@ This file is part of the QGROUNDCONTROL project @@ -36,6 +36,10 @@ This file is part of the QGROUNDCONTROL project
#include "TCPLink.h"
#ifdef QT_DEBUG
#include "AutoTest.h"
#include "CmdLineOptParser.h"
#ifdef Q_OS_WIN
#include <crtdbg.h>
#endif
#endif
/* SDL does ugly things to main() */
@ -44,10 +48,10 @@ This file is part of the QGROUNDCONTROL project @@ -44,10 +48,10 @@ This file is part of the QGROUNDCONTROL project
#endif
// Install a message handler so you do not need
// the MSFT debug tools installed to se
// qDebug(), qWarning(), qCritical and qAbort
#ifdef Q_OS_WIN
/// @brief Message handler which is installed using qInstallMsgHandler so you do not need
/// the MSFT debug tools installed to see qDebug(), qWarning(), qCritical and qAbort
void msgHandler( QtMsgType type, const char* msg )
{
const char symbols[] = { 'I', 'E', '!', 'X' };
@ -56,6 +60,17 @@ void msgHandler( QtMsgType type, const char* msg ) @@ -56,6 +60,17 @@ void msgHandler( QtMsgType type, const char* msg )
if( type == QtFatalMsg ) abort();
}
/// @brief CRT Report Hook installed using _CrtSetReportHook. We install this hook when
/// we don't want asserts to pop a dialog on windows.
int WindowsCrtReportHook(int reportType, char* message, int* returnValue)
{
Q_UNUSED(reportType);
std::cerr << message << std::endl; // Output message to stderr
*returnValue = 0; // Don't break into debugger
return true; // We handled this fully ourselves
}
#endif
/**
@ -81,13 +96,27 @@ int main(int argc, char *argv[]) @@ -81,13 +96,27 @@ int main(int argc, char *argv[])
qRegisterMetaType<QAbstractSocket::SocketError>();
#ifdef QT_DEBUG
if (argc > 1 && QString(argv[1]).compare("--unittest", Qt::CaseInsensitive) == 0) {
// Strip off extra command line args so QTest doesn't complain
for (int i=1; i<argc-1; i++)
{
argv[i] = argv[i+1];
// We parse a small set of command line options here prior to QGCCore in order to handle the ones
// which need to be handled before a QApplication object is started.
bool runUnitTests = false; // Run unit test
bool quietWindowsAsserts = false; // Don't let asserts pop dialog boxes
CmdLineOpt_t rgCmdLineOptions[] = {
{ "--unittest", &runUnitTests },
{ "--no-windows-assert-ui", &quietWindowsAsserts },
// Add additional command line option flags here
};
ParseCmdLineOptions(argc, argv, rgCmdLineOptions, sizeof(rgCmdLineOptions)/sizeof(rgCmdLineOptions[0]), true);
if (quietWindowsAsserts) {
#ifdef Q_OS_WIN
_CrtSetReportHook(WindowsCrtReportHook);
#endif
}
if (runUnitTests) {
// Run the test
int failures = AutoTest::run(argc-1, argv);
if (failures == 0)

10
src/qgcunittest/UASUnitTest.cc

@ -1,6 +1,8 @@ @@ -1,6 +1,8 @@
#include "UASUnitTest.h"
#include <stdio.h>
#include <QObject>
#include <QThread>
UASUnitTest::UASUnitTest()
{
}
@ -8,7 +10,7 @@ UASUnitTest::UASUnitTest() @@ -8,7 +10,7 @@ UASUnitTest::UASUnitTest()
void UASUnitTest::init()
{
mav = new MAVLinkProtocol();
uas = new UAS(mav, UASID);
uas = new UAS(mav, QThread::currentThread(), UASID);
uas->deleteSettings();
}
//this function is called after every test
@ -24,7 +26,7 @@ void UASUnitTest::cleanup() @@ -24,7 +26,7 @@ void UASUnitTest::cleanup()
void UASUnitTest::getUASID_test()
{
// Test a default ID of zero is assigned
UAS* uas2 = new UAS(mav);
UAS* uas2 = new UAS(mav, QThread::currentThread());
QCOMPARE(uas2->getUASID(), 0);
delete uas2;
@ -49,7 +51,7 @@ void UASUnitTest::getUASName_test() @@ -49,7 +51,7 @@ void UASUnitTest::getUASName_test()
void UASUnitTest::getUpTime_test()
{
UAS* uas2 = new UAS(mav);
UAS* uas2 = new UAS(mav, QThread::currentThread());
// Test that the uptime starts at zero to a
// precision of seconds
QCOMPARE(floor(uas2->getUptime()/1000.0), 0.0);
@ -281,7 +283,7 @@ void UASUnitTest::signalWayPoint_test() @@ -281,7 +283,7 @@ void UASUnitTest::signalWayPoint_test()
delete uas;// delete(destroyed) uas for validating
uas = NULL;
QCOMPARE(spyDestroyed.count(), 1);// count destroyed uas should are 1
uas = new UAS(mav,UASID);
uas = new UAS(mav, QThread::currentThread(), UASID);
QSignalSpy spy2(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
QCOMPARE(spy2.count(), 0);
Waypoint* wp2 = new Waypoint(0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah");

18
src/uas/QGCMAVLinkUASFactory.cc

@ -1,5 +1,6 @@ @@ -1,5 +1,6 @@
#include "QGCMAVLinkUASFactory.h"
#include "UASManager.h"
#include "QGCUASWorker.h"
QGCMAVLinkUASFactory::QGCMAVLinkUASFactory(QObject *parent) :
QObject(parent)
@ -21,7 +22,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte @@ -21,7 +22,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
UASInterface* uas;
QThread* worker = new QThread();
QGCUASWorker* worker = new QGCUASWorker();
switch (heartbeat->autopilot)
{
@ -31,8 +32,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte @@ -31,8 +32,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Set the system type
mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
// Connect this robot to the UAS object
connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
#ifdef QGC_PROTOBUF_ENABLED
@ -47,8 +46,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte @@ -47,8 +46,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Set the system type
mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
@ -66,8 +63,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte @@ -66,8 +63,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Set the system type
mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
@ -82,8 +77,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte @@ -82,8 +77,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Set the system type
mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
@ -120,6 +113,10 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte @@ -120,6 +113,10 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
break;
}
// Get the UAS ready
worker->start(QThread::HighPriority);
connect(uas, SIGNAL(destroyed()), worker, SLOT(quit()));
// Set the autopilot type
uas->setAutopilotType((int)heartbeat->autopilot);
@ -129,8 +126,5 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte @@ -129,8 +126,5 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Now add UAS to "official" list, which makes the whole application aware of it
UASManager::instance()->addUAS(uas);
worker->start(QThread::HighPriority);
connect(uas, SIGNAL(destroyed()), worker, SLOT(quit()));
return uas;
}

24
src/uas/QGCUASWorker.cc

@ -0,0 +1,24 @@ @@ -0,0 +1,24 @@
#include "QGCUASWorker.h"
#include <QGC.h>
#include <QCoreApplication>
#include <QDebug>
QGCUASWorker::QGCUASWorker() : QThread(),
_should_exit(false)
{
}
void QGCUASWorker::quit()
{
_should_exit = true;
}
void QGCUASWorker::run()
{
while(!_should_exit) {
QCoreApplication::processEvents();
QGC::SLEEP::msleep(2);
}
}

20
src/uas/QGCUASWorker.h

@ -0,0 +1,20 @@ @@ -0,0 +1,20 @@
#ifndef QGCUASWORKER_H
#define QGCUASWORKER_H
#include <QThread>
class QGCUASWorker : public QThread
{
public:
QGCUASWorker();
public slots:
void quit();
protected:
void run();
bool _should_exit;
};
#endif // QGCUASWORKER_H

37
src/uas/UAS.cc

@ -51,7 +51,7 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(), @@ -51,7 +51,7 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
commStatus(COMM_DISCONNECTED),
receiveDropRate(0),
sendDropRate(0),
statusTimeout(new QTimer(this)),
statusTimeout(thread),
name(""),
type(MAV_TYPE_GENERIC),
@ -155,6 +155,7 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(), @@ -155,6 +155,7 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
paramsOnceRequested(false),
paramMgr(this),
simulation(0),
_thread(thread),
// The protected members.
connectionLost(false),
@ -167,9 +168,6 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(), @@ -167,9 +168,6 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
lastSendTimeSensors(0)
{
moveToThread(thread);
waypointManager.moveToThread(thread);
paramMgr.moveToThread(thread);
statusTimeout->moveToThread(thread);
for (unsigned int i = 0; i<255;++i)
{
@ -180,66 +178,66 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(), @@ -180,66 +178,66 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
// Store a list of available actions for this UAS.
// Basically everything exposed as a SLOT with no return value or arguments.
QAction* newAction = new QAction(tr("Arm"), this);
QAction* newAction = new QAction(tr("Arm"), thread);
newAction->setToolTip(tr("Enable the UAS so that all actuators are online"));
connect(newAction, SIGNAL(triggered()), this, SLOT(armSystem()));
actions.append(newAction);
newAction = new QAction(tr("Disarm"), this);
newAction = new QAction(tr("Disarm"), thread);
newAction->setToolTip(tr("Disable the UAS so that all actuators are offline"));
connect(newAction, SIGNAL(triggered()), this, SLOT(disarmSystem()));
actions.append(newAction);
newAction = new QAction(tr("Toggle armed"), this);
newAction = new QAction(tr("Toggle armed"), thread);
newAction->setToolTip(tr("Toggle between armed and disarmed"));
connect(newAction, SIGNAL(triggered()), this, SLOT(toggleAutonomy()));
actions.append(newAction);
newAction = new QAction(tr("Go home"), this);
newAction = new QAction(tr("Go home"), thread);
newAction->setToolTip(tr("Command the UAS to return to its home position"));
connect(newAction, SIGNAL(triggered()), this, SLOT(home()));
actions.append(newAction);
newAction = new QAction(tr("Land"), this);
newAction = new QAction(tr("Land"), thread);
newAction->setToolTip(tr("Command the UAS to land"));
connect(newAction, SIGNAL(triggered()), this, SLOT(land()));
actions.append(newAction);
newAction = new QAction(tr("Launch"), this);
newAction = new QAction(tr("Launch"), thread);
newAction->setToolTip(tr("Command the UAS to launch itself and begin its mission"));
connect(newAction, SIGNAL(triggered()), this, SLOT(launch()));
actions.append(newAction);
newAction = new QAction(tr("Resume"), this);
newAction = new QAction(tr("Resume"), thread);
newAction->setToolTip(tr("Command the UAS to continue its mission"));
connect(newAction, SIGNAL(triggered()), this, SLOT(go()));
actions.append(newAction);
newAction = new QAction(tr("Stop"), this);
newAction = new QAction(tr("Stop"), thread);
newAction->setToolTip(tr("Command the UAS to halt and hold position"));
connect(newAction, SIGNAL(triggered()), this, SLOT(halt()));
actions.append(newAction);
newAction = new QAction(tr("Go autonomous"), this);
newAction = new QAction(tr("Go autonomous"), thread);
newAction->setToolTip(tr("Set the UAS into an autonomous control mode"));
connect(newAction, SIGNAL(triggered()), this, SLOT(goAutonomous()));
actions.append(newAction);
newAction = new QAction(tr("Go manual"), this);
newAction = new QAction(tr("Go manual"), thread);
newAction->setToolTip(tr("Set the UAS into a manual control mode"));
connect(newAction, SIGNAL(triggered()), this, SLOT(goManual()));
actions.append(newAction);
newAction = new QAction(tr("Toggle autonomy"), this);
newAction = new QAction(tr("Toggle autonomy"), thread);
newAction->setToolTip(tr("Toggle between manual and full-autonomy"));
connect(newAction, SIGNAL(triggered()), this, SLOT(toggleAutonomy()));
actions.append(newAction);
color = UASInterface::getNextColor();
setBatterySpecs(QString(""));
connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
connect(&statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
statusTimeout->start(500);
statusTimeout.start(500);
readSettings();
//need to init paramMgr after readSettings have been loaded, to properly set autopilot and so forth
paramMgr.initWithUAS(this);
@ -255,8 +253,11 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(), @@ -255,8 +253,11 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
UAS::~UAS()
{
writeSettings();
_thread->quit();
_thread->wait();
delete links;
delete statusTimeout;
delete simulation;
}

3
src/uas/UAS.h

@ -382,7 +382,7 @@ protected: //COMMENTS FOR TEST UNIT @@ -382,7 +382,7 @@ protected: //COMMENTS FOR TEST UNIT
float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs)
float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS
quint64 lastHeartbeat; ///< Time of the last heartbeat message
QTimer* statusTimeout; ///< Timer for various status timeouts
QTimer statusTimeout; ///< Timer for various status timeouts
/// BASIC UAS TYPE, NAME AND STATE
QString name; ///< Human-friendly name of the vehicle, e.g. bravo
@ -526,6 +526,7 @@ protected: //COMMENTS FOR TEST UNIT @@ -526,6 +526,7 @@ protected: //COMMENTS FOR TEST UNIT
/// SIMULATION
QGCHilLink* simulation; ///< Hardware in the loop simulation link
QThread* _thread;
public:
/** @brief Set the current battery type */

3
src/ui/MainWindow.cc

@ -760,6 +760,7 @@ void MainWindow::loadDockWidget(const QString& name) @@ -760,6 +760,7 @@ void MainWindow::loadDockWidget(const QString& name)
{
if(menuActionHelper->containsDockWidget(currentView, name))
return;
if (name.startsWith("HIL_CONFIG"))
{
//It's a HIL widget.
@ -826,7 +827,7 @@ void MainWindow::loadDockWidget(const QString& name) @@ -826,7 +827,7 @@ void MainWindow::loadDockWidget(const QString& name)
}
else if (name == "HEAD_UP_DISPLAY_DOCKWIDGET")
{
createDockWidget(centerStack->currentWidget(),new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
createDockWidget(centerStack->currentWidget(),new HUD(320,240,this),tr("Video Downlink"),"HEAD_UP_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
}
else if (name == "UAS_INFO_QUICKVIEW_DOCKWIDGET")
{

60
src/ui/PrimaryFlightDisplay.cc

@ -110,6 +110,9 @@ const QString PrimaryFlightDisplay::compassWindNames[] = { @@ -110,6 +110,9 @@ const QString PrimaryFlightDisplay::compassWindNames[] = {
PrimaryFlightDisplay::PrimaryFlightDisplay(int width, int height, QWidget *parent) :
QWidget(parent),
_valuesChanged(false),
_valuesLastPainted(QGC::groundTimeMilliseconds()),
uas(NULL),
roll(0),
@ -159,7 +162,7 @@ PrimaryFlightDisplay::PrimaryFlightDisplay(int width, int height, QWidget *paren @@ -159,7 +162,7 @@ PrimaryFlightDisplay::PrimaryFlightDisplay(int width, int height, QWidget *paren
// Refresh timer
refreshTimer->setInterval(updateInterval);
// connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD()));
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(update()));
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(checkUpdate()));
}
PrimaryFlightDisplay::~PrimaryFlightDisplay()
@ -224,6 +227,15 @@ void PrimaryFlightDisplay::paintEvent(QPaintEvent *event) @@ -224,6 +227,15 @@ void PrimaryFlightDisplay::paintEvent(QPaintEvent *event)
doPaint();
}
void PrimaryFlightDisplay::checkUpdate()
{
if (uas && (_valuesChanged || (QGC::groundTimeMilliseconds() - _valuesLastPainted) > 260)) {
update();
_valuesChanged = false;
_valuesLastPainted = QGC::groundTimeMilliseconds();
}
}
///*
// * Interface towards qgroundcontrol
// */
@ -280,24 +292,45 @@ void PrimaryFlightDisplay::updateAttitude(UASInterface* uas, double roll, double @@ -280,24 +292,45 @@ void PrimaryFlightDisplay::updateAttitude(UASInterface* uas, double roll, double
{
Q_UNUSED(uas);
Q_UNUSED(timestamp);
// Called from UAS.cc l. 616
if (isinf(roll)) {
this->roll = std::numeric_limits<double>::quiet_NaN();
} else {
this->roll = roll * (180.0 / M_PI);
float rolldeg = roll * (180.0 / M_PI);
if (fabsf(roll - rolldeg) > 2.5f) {
_valuesChanged = true;
}
this->roll = rolldeg;
}
if (isinf(pitch)) {
this->pitch = std::numeric_limits<double>::quiet_NaN();
} else {
this->pitch = pitch * (180.0 / M_PI);
float pitchdeg = pitch * (180.0 / M_PI);
if (fabsf(pitch - pitchdeg) > 2.5f) {
_valuesChanged = true;
}
this->pitch = pitchdeg;
}
if (isinf(yaw)) {
this->heading = std::numeric_limits<double>::quiet_NaN();
} else {
yaw = yaw * (180.0 / M_PI);
if (yaw<0) yaw+=360;
if (fabsf(heading - yaw) > 10.0f) {
_valuesChanged = true;
}
this->heading = yaw;
}
@ -314,6 +347,14 @@ void PrimaryFlightDisplay::updateSpeed(UASInterface* uas, double _groundSpeed, d @@ -314,6 +347,14 @@ void PrimaryFlightDisplay::updateSpeed(UASInterface* uas, double _groundSpeed, d
Q_UNUSED(uas);
Q_UNUSED(timestamp);
if (fabsf(groundSpeed - _groundSpeed) > 0.5f) {
_valuesChanged = true;
}
if (fabsf(airSpeed - _airSpeed) > 1.0f) {
_valuesChanged = true;
}
groundSpeed = _groundSpeed;
airSpeed = _airSpeed;
}
@ -321,6 +362,19 @@ void PrimaryFlightDisplay::updateSpeed(UASInterface* uas, double _groundSpeed, d @@ -321,6 +362,19 @@ void PrimaryFlightDisplay::updateSpeed(UASInterface* uas, double _groundSpeed, d
void PrimaryFlightDisplay::updateAltitude(UASInterface* uas, double _altitudeAMSL, double _altitudeRelative, double _climbRate, quint64 timestamp) {
Q_UNUSED(uas);
Q_UNUSED(timestamp);
if (fabsf(altitudeAMSL - _altitudeAMSL) > 0.5f) {
_valuesChanged = true;
}
if (fabsf(altitudeRelative - _altitudeRelative) > 0.5f) {
_valuesChanged = true;
}
if (fabsf(climbRate - _climbRate) > 0.5f) {
_valuesChanged = true;
}
altitudeAMSL = _altitudeAMSL;
altitudeRelative = _altitudeRelative;
climbRate = _climbRate;

6
src/ui/PrimaryFlightDisplay.h

@ -27,7 +27,13 @@ public slots: @@ -27,7 +27,13 @@ public slots:
void forgetUAS(UASInterface* uas);
void setActiveUAS(UASInterface* uas);
void checkUpdate();
protected:
bool _valuesChanged;
quint64 _valuesLastPainted;
enum Layout {
COMPASS_INTEGRATED,
COMPASS_SEPARATED // For a very high container. Feature panels are at bottom.

3
src/ui/QGCHilXPlaneConfiguration.cc

@ -25,8 +25,9 @@ QGCHilXPlaneConfiguration::QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget * @@ -25,8 +25,9 @@ QGCHilXPlaneConfiguration::QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget *
{
// connect(ui->randomAttitudeButton, SIGNAL(clicked()), link, SLOT(setRandomAttitude()));
// connect(ui->randomPositionButton, SIGNAL(clicked()), link, SLOT(setRandomPosition()));
connect(ui->airframeComboBox, SIGNAL(activated(QString)), link, SLOT(selectAirframe(QString)));
ui->airframeComboBox->setCurrentIndex(link->getAirFrameIndex());
connect(ui->airframeComboBox, SIGNAL(activated(QString)), link, SLOT(selectAirframe(QString)));
// XXX not implemented yet
ui->airframeComboBox->hide();
ui->sensorHilCheckBox->setChecked(xplane->sensorHilEnabled());

1
src/ui/QGCMAVLinkLogPlayer.cc

@ -575,6 +575,7 @@ void QGCMAVLinkLogPlayer::logLoop() @@ -575,6 +575,7 @@ void QGCMAVLinkLogPlayer::logLoop()
// have at least 3ms until the next one.
int nextExecutionTime = 0;
mavlink_message_t msg;
msg.len = 0; // FIXME: Hack, remove once Issue #647 is fixed
while (nextExecutionTime < 3) {
// Now we're sitting at the start of a MAVLink message, so read it all into a byte array for feeding to our parser.

Loading…
Cancel
Save