Commit fc493d75 authored by Don Gagne's avatar Don Gagne
Browse files

Move UAS and MAVLinkProtocol back to main thread

Plus a large number of other changes to allow for orderly shutdown of
objects without crashes or asserts. This is need for unit tests to
create/delete global state around every test.
parent 3b328f36
......@@ -8,7 +8,7 @@ class QGXPX4UAS : public UAS
Q_OBJECT
Q_INTERFACES(UASInterface)
public:
QGXPX4UAS(MAVLinkProtocol* mavlink, QThread* thread, int id);
QGXPX4UAS(MAVLinkProtocol* mavlink, int id);
public slots:
/** @brief Receive a MAVLink message from this MAV */
......
......@@ -32,6 +32,8 @@
#include "AutoPilotPluginManager.h"
#include "QGCMessageBox.h"
Q_LOGGING_CATEGORY(UASLog, "UASLog")
/**
* Gets the settings from the previous UAS (name, airframe, autopilot, battery specs)
* by calling readSettings. This means the new UAS will have the same settings
......@@ -39,17 +41,15 @@
* creating the UAS.
*/
UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lipoFull(4.2f),
lipoEmpty(3.5f),
uasId(id),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
commStatus(COMM_DISCONNECTED),
receiveDropRate(0),
sendDropRate(0),
statusTimeout(thread),
name(""),
type(MAV_TYPE_GENERIC),
......@@ -150,7 +150,6 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
paramsOnceRequested(false),
paramMgr(this),
simulation(0),
_thread(thread),
// The protected members.
connectionLost(false),
......@@ -163,7 +162,6 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
lastSendTimeSensors(0),
lastSendTimeOpticalFlow(0)
{
moveToThread(thread);
for (unsigned int i = 0; i<255;++i)
{
......@@ -176,57 +174,57 @@ 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"), thread);
QAction* newAction = new QAction(tr("Arm"), this);
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"), thread);
newAction = new QAction(tr("Disarm"), this);
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"), thread);
newAction = new QAction(tr("Toggle armed"), this);
newAction->setToolTip(tr("Toggle between armed and disarmed"));
connect(newAction, SIGNAL(triggered()), this, SLOT(toggleAutonomy()));
actions.append(newAction);
newAction = new QAction(tr("Go home"), thread);
newAction = new QAction(tr("Go home"), this);
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"), thread);
newAction = new QAction(tr("Land"), this);
newAction->setToolTip(tr("Command the UAS to land"));
connect(newAction, SIGNAL(triggered()), this, SLOT(land()));
actions.append(newAction);
newAction = new QAction(tr("Launch"), thread);
newAction = new QAction(tr("Launch"), this);
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"), thread);
newAction = new QAction(tr("Resume"), this);
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"), thread);
newAction = new QAction(tr("Stop"), this);
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"), thread);
newAction = new QAction(tr("Go autonomous"), this);
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"), thread);
newAction = new QAction(tr("Go manual"), this);
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"), thread);
newAction = new QAction(tr("Toggle autonomy"), this);
newAction->setToolTip(tr("Toggle between manual and full-autonomy"));
connect(newAction, SIGNAL(triggered()), this, SLOT(toggleAutonomy()));
actions.append(newAction);
......@@ -251,11 +249,6 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
UAS::~UAS()
{
writeSettings();
_thread->quit();
delete links;
delete simulation;
}
/**
......@@ -391,8 +384,7 @@ bool UAS::getSelected() const
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
if (!link) return;
if (!links->contains(link))
if (!links.contains(link))
{
addLink(link);
// qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
......@@ -550,7 +542,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
modechanged = true;
this->base_mode = state.base_mode;
this->custom_mode = state.custom_mode;
shortModeText = getShortModeTextFor(this->base_mode, this->custom_mode, this->autopilot);
shortModeText = getShortModeTextFor(this->base_mode, this->custom_mode);
emit modeChanged(this->getUASID(), shortModeText, "");
......@@ -1738,23 +1730,15 @@ void UAS::sendMessage(mavlink_message_t message)
return;
}
if (links->count() < 1) {
if (links.count() < 1) {
qDebug() << "NO LINK AVAILABLE TO SEND!";
}
// Emit message on all links that are currently connected
foreach (LinkInterface* link, *links)
{
if (LinkManager::instance()->getLinks().contains(link))
{
if (link->isConnected())
foreach (LinkInterface* link, links) {
if (link->isConnected()) {
sendMessage(link, message);
}
else
{
// Remove from list
links->removeAt(links->indexOf(link));
}
}
}
......@@ -1774,9 +1758,9 @@ void UAS::forwardMessage(mavlink_message_t message)
SerialLink* serial = dynamic_cast<SerialLink*>(link);
if(serial != 0)
{
for(int i=0; i<links->size(); i++)
for(int i=0; i<links.size(); i++)
{
if(serial != links->at(i))
if(serial != links.at(i))
{
if (link->isConnected()) {
qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
......@@ -2355,7 +2339,7 @@ void UAS::setParameter(const int compId, const QString& paramId, const QVariant&
//TODO update this to use the parameter manager / param data model instead
void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue)
void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramUnion)
{
int compId = msg.compid;
......@@ -2369,105 +2353,68 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
parameters.value(compId)->remove(paramName);
}
QVariant param;
QVariant paramValue;
// Insert with correct type
// TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling.
switch (rawValue.param_type)
{
switch (rawValue.param_type) {
case MAV_PARAM_TYPE_REAL32:
{
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
param = QVariant(paramValue.param_float);
}
else {
param = QVariant(paramValue.param_float);
}
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
// qDebug() << "RECEIVED PARAM:" << param;
paramValue = QVariant(paramUnion.param_float);
} else {
paramValue = QVariant(paramUnion.param_float);
}
break;
case MAV_PARAM_TYPE_UINT8:
{
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
param = QVariant(QChar((unsigned char)paramValue.param_float));
}
else {
param = QVariant(QChar((unsigned char)paramValue.param_uint8));
}
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
//qDebug() << "RECEIVED PARAM:" << param;
paramValue = QVariant(QChar((unsigned char)paramUnion.param_float));
} else {
paramValue = QVariant(QChar((unsigned char)paramUnion.param_uint8));
}
break;
case MAV_PARAM_TYPE_INT8:
{
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
param = QVariant(QChar((char)paramValue.param_float));
}
else {
param = QVariant(QChar((char)paramValue.param_int8));
}
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
//qDebug() << "RECEIVED PARAM:" << param;
paramValue = QVariant(QChar((char)paramUnion.param_float));
} else {
paramValue = QVariant(QChar((char)paramUnion.param_int8));
}
break;
case MAV_PARAM_TYPE_INT16:
{
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
param = QVariant((short)paramValue.param_float);
}
else {
param = QVariant(paramValue.param_int16);
}
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
//qDebug() << "RECEIVED PARAM:" << param;
paramValue = QVariant((short)paramUnion.param_float);
} else {
paramValue = QVariant(paramUnion.param_int16);
}
break;
case MAV_PARAM_TYPE_UINT32:
{
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
param = QVariant((unsigned int)paramValue.param_float);
}
else {
param = QVariant(paramValue.param_uint32);
}
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
paramValue = QVariant((unsigned int)paramUnion.param_float);
} else {
paramValue = QVariant(paramUnion.param_uint32);
}
break;
case MAV_PARAM_TYPE_INT32:
{
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
param = QVariant((int)paramValue.param_float);
}
else {
param = QVariant(paramValue.param_int32);
}
parameters.value(compId)->insert(paramName, param);
// Emit change
emit parameterChanged(uasId, compId, paramName, param);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param);
// qDebug() << "RECEIVED PARAM:" << param;
paramValue = QVariant((int)paramUnion.param_float);
} else {
paramValue = QVariant(paramUnion.param_int32);
}
break;
default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
} //switch (value.param_type)
}
qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
parameters.value(compId)->insert(paramName, paramValue);
emit parameterChanged(uasId, compId, paramName, paramValue);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, paramValue);
}
/**
......@@ -3290,9 +3237,9 @@ QString UAS::getAudioModeTextFor(int id)
* The mode returned can be auto, stabilized, test, manual, preflight or unknown.
* @return the short text of the mode for the id given.
*/
QString UAS::getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode, int autopilot)
QString UAS::getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode) const
{
QString mode = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(autopilot)->getShortModeText(base_mode, custom_mode);
QString mode = AutoPilotPluginManager::instance()->getShortModeText(base_mode, custom_mode, autopilot);
if (mode.length() == 0)
{
......@@ -3331,29 +3278,33 @@ const QString& UAS::getShortMode() const
*/
void UAS::addLink(LinkInterface* link)
{
if (!links->contains(link))
if (!links.contains(link))
{
links->append(link);
links.append(link);
qCDebug(UASLog) << "addLink:" << QString("%1").arg((ulong)link, 0, 16);
connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
}
}
void UAS::removeLink(QObject* object)
{
qCDebug(UASLog) << "removeLink:" << QString("%1").arg((ulong)object, 0, 16);
qCDebug(UASLog) << "link count:" << links.count();
// Do not dynamic cast or de-reference QObject, since object is either in destructor or may have already
// been destroyed.
LinkInterface* link = (LinkInterface*)object;
int index = links->indexOf(link);
int index = links.indexOf(link);
Q_ASSERT(index != -1);
links->removeAt(index);
links.removeAt(index);
}
/**
* @return the list of links
*/
QList<LinkInterface*>* UAS::getLinks()
QList<LinkInterface*> UAS::getLinks()
{
return links;
}
......
......@@ -32,7 +32,6 @@ This file is part of the QGROUNDCONTROL project
#ifndef _UAS_H_
#define _UAS_H_
#include <QThread>
#include "UASInterface.h"
#include <MAVLinkProtocol.h>
#include <QVector3D>
......@@ -44,6 +43,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCUASParamManager.h"
#include "QGCUASFileManager.h"
Q_DECLARE_LOGGING_CATEGORY(UASLog)
/**
* @brief A generic MAVLINK-connected MAV/UAV
......@@ -57,7 +57,7 @@ class UAS : public UASInterface
{
Q_OBJECT
public:
UAS(MAVLinkProtocol* protocol, QThread* thread, int id = 0);
UAS(MAVLinkProtocol* protocol, int id = 0);
~UAS();
float lipoFull; ///< 100% charged voltage
......@@ -72,7 +72,7 @@ public:
/** @brief Get short mode */
const QString& getShortMode() const;
/** @brief Translate from mode id to text */
static QString getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode, int autopilot);
QString getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode) const;
/** @brief Translate from mode id to audio text */
static QString getAudioModeTextFor(int id);
/** @brief Get the unique system id */
......@@ -92,7 +92,7 @@ public:
/** @brief Add one measurement and get low-passed voltage */
float filterVoltage(float value) const;
/** @brief Get the links associated with this robot */
QList<LinkInterface*>* getLinks();
QList<LinkInterface*> getLinks();
Q_PROPERTY(double localX READ getLocalX WRITE setLocalX NOTIFY localXChanged)
Q_PROPERTY(double localY READ getLocalY WRITE setLocalY NOTIFY localYChanged)
......@@ -341,7 +341,7 @@ protected: //COMMENTS FOR TEST UNIT
/// LINK ID AND STATUS
int uasId; ///< Unique system ID
QMap<int, QString> components;///< IDs and names of all detected onboard components
QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
QList<LinkInterface*> links; ///< List of links this UAS can be reached by
QList<int> unknownPackets; ///< Packet IDs which are unknown and have been received
MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance
CommStatus commStatus; ///< Communication status
......@@ -473,7 +473,6 @@ protected: //COMMENTS FOR TEST UNIT
/// SIMULATION
QGCHilLink* simulation; ///< Hardware in the loop simulation link
QThread* _thread;
public:
/** @brief Set the current battery type */
......@@ -952,13 +951,6 @@ protected slots:
void writeSettings();
/** @brief Read settings from disk */
void readSettings();
// // MESSAGE RECEPTION
// /** @brief Receive a named value message */
// void receiveMessageNamedValue(const mavlink_message_t& message);
private:
// unsigned int mode; ///< The current mode of the MAV
};
......
......@@ -103,7 +103,7 @@ public:
/** @brief Get short mode */
virtual const QString& getShortMode() const = 0;
/** @brief Translate mode id into text */
static QString getShortModeTextFor(int id);
virtual QString getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode) const = 0;
//virtual QColor getColor() = 0;
virtual int getUASID() const = 0; ///< Get the ID of the connected UAS
/** @brief The time interval the robot is switched on **/
......@@ -187,7 +187,7 @@ public:
* based on the fact that a message for this robot has been received through that
* interface. The LinkInterface can support multiple protocols.
**/
virtual QList<LinkInterface*>* getLinks() = 0;
virtual QList<LinkInterface*> getLinks() = 0;
/**
* @brief Get the color for this UAS
......
......@@ -42,10 +42,19 @@ UASManager::UASManager(QObject* parent) :
UASManager::~UASManager()
{
storeSettings();
// Delete all systems
foreach (UASInterface* mav, systems) {
// deleteLater so it ends up on correct thread
mav->deleteLater();
Q_ASSERT_X(systems.count() == 0, "~UASManager", "_shutdown should have already removed all uas");
}
void UASManager::_shutdown(void)
{
QList<UASInterface*> uasList;
foreach(UASInterface* uas, systems) {
uasList.append(uas);
}
foreach(UASInterface* uas, uasList) {
removeUAS(uas);
}
}
......@@ -280,7 +289,8 @@ void UASManager::addUAS(UASInterface* uas)
if (firstUAS)
{
setActiveUAS(uas);
if (offlineUASWaypointManager->getWaypointEditableList().size() > 0)
// Call getActiveUASWaypointManager instead of referencing variable to make sure of creation
if (getActiveUASWaypointManager()->getWaypointEditableList().size() > 0)
{
if (QGCMessageBox::question(tr("Question"), tr("Do you want to append the offline waypoints to the ones currently on the UAV?"), QMessageBox::Yes, QMessageBox::No) == QMessageBox::Yes)
{
......
......@@ -32,7 +32,6 @@ This file is part of the QGROUNDCONTROL project
#define _UASMANAGER_H_
#include "UASManagerInterface.h"
#include <QThread>
#include <QList>
#include <QMutex>
#include <UASInterface.h>
......@@ -242,6 +241,8 @@ public slots:
/** @brief Store settings */
void storeSettings();
void _shutdown(void);
protected:
QList<UASInterface*> systems;
......@@ -262,7 +263,6 @@ protected:
private:
/// @brief All access to UASManager singleton is through UASManager::instance
UASManager(QObject* parent = NULL);
~UASManager();
public:
......
......@@ -31,7 +31,6 @@
#ifndef _UASMANAGERINTERFACE_H_
#define _UASMANAGERINTERFACE_H_
#include <QThread>
#include <QList>
#include <QMutex>
......@@ -91,6 +90,7 @@ public slots:
virtual void uavChangedHomePosition(int uav, double lat, double lon, double alt) = 0;
virtual void loadSettings() = 0;
virtual void storeSettings() = 0;
virtual void _shutdown(void) = 0;
signals:
/** A new system was created */
......
......@@ -71,7 +71,7 @@ void UASParameterCommsMgr::loadParamCommsSettings()
void UASParameterCommsMgr::_sendParamRequestListMsg(void)
{
MAVLinkProtocol* mavlink = LinkManager::instance()->mavlink();
MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
Q_ASSERT(mavlink);
mavlink_message_t msg;
......@@ -411,7 +411,7 @@ void UASParameterCommsMgr::setParameterStatusMsg(const QString& msg, ParamCommsS
void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int paramCount, int paramId, QString paramName, QVariant value)
{
qCDebug(UASParameterCommsMgrLog) << QString("Received parameter update for: name(%1) count(%2) index(%3)").arg(paramName).arg(paramCount).arg(paramId);
qCDebug(UASParameterCommsMgrLog) << "Received parameter update for:" << paramName << "count" << paramCount << "index" << paramId << "value" << value;
Q_UNUSED(uas); //this object is assigned to one UAS only
lastReceiveTime = QGC::groundTimeMilliseconds();
......
......@@ -224,7 +224,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, QWidget *p
connect(ui.linkType,SIGNAL(currentIndexChanged(int)),this,SLOT(linkCurrentIndexChanged(int)));
// Open details pane for MAVLink if necessary
MAVLinkProtocol* mavlink = LinkManager::instance()->mavlink();
MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
QWidget* conf = new MAVLinkSettingsWidget(mavlink, this);
ui.protocolScrollArea->setWidget(conf);
ui.protocolGroupBox->setTitle(mavlink->getName()+" (Global Settings)");
......
......@@ -130,8 +130,8 @@ MainWindow::MainWindow(QSplashScreen* splashScreen, enum MainWindow::CUSTOM_MODE
this->setAttribute(Qt::WA_DeleteOnClose);
connect(menuActionHelper, SIGNAL(needToShowDockWidget(QString,bool)),SLOT(showDockWidget(QString,bool)));
connect(LinkManager::instance()->mavlink(), SIGNAL(protocolStatusMessage(const QString&, const QString&)), this, SLOT(showCriticalMessage(const QString&, const QString&)));
connect(LinkManager::instance()->mavlink(), SIGNAL(saveTempFlightDataLog(QString)), this, SLOT(_saveTempFlightDataLog(QString)));
connect(MAVLinkProtocol::instance(), SIGNAL(protocolStatusMessage(const QString&, const QString&)), this, SLOT(showCriticalMessage(const QString&, const QString&)));
connect(MAVLinkProtocol::instance(), SIGNAL(saveTempFlightDataLog(QString)), this, SLOT(_saveTempFlightDataLog(QString)));
loadSettings();
......@@ -294,7 +294,6 @@ MainWindow::MainWindow(QSplashScreen* splashScreen, enum MainWindow::CUSTOM_MODE
{
// Restore the window geometry
restoreGeometry(settings.value(getWindowGeometryKey()).toByteArray());
show();
}
else
{
......@@ -305,12 +304,10 @@ MainWindow::MainWindow(QSplashScreen* splashScreen, enum MainWindow::CUSTOM_MODE
if (screenWidth < 1500)
{
resize(screenWidth, screenHeight - 80);
show();
}
else
{
resize(screenWidth*0.67f, qMin(screenHeight, (int)(screenWidth*0.67f*0.67f)));
show();
}
}
......@@ -358,7 +355,10 @@ MainWindow::MainWindow(QSplashScreen* splashScreen, enum MainWindow::CUSTOM_MODE
connect(&windowNameUpdateTimer, SIGNAL(timeout()), this, SLOT(configureWindowName()));
windowNameUpdateTimer.start(15000);
emit initStatusChanged(tr("Done"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141));
if (!qgcApp()->runningUnitTests()) {
show();
}
}
MainWindow::~MainWindow()
......@@ -489,12 +489,12 @@ void MainWindow::buildCustomWidget()
void MainWindow::buildCommonWidgets()
{
// Add generic MAVLink decoder
mavlinkDecoder = new MAVLinkDecoder(LinkManager::instance()->mavlink(), this);
mavlinkDecoder = new MAVLinkDecoder(MAVLinkProtocol::instance(), this);
connect(mavlinkDecoder, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)),
this, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)));
// Log player
logPlayer = new QGCMAVLinkLogPlayer(LinkManager::instance()->mavlink(), statusBar());
logPlayer = new QGCMAVLinkLogPlayer(MAVLinkProtocol::instance(), statusBar());
statusBar()->addPermanentWidget(logPlayer);
// Initialize all of the views, if they haven't been already, and add their central widgets
......@@ -581,7 +581,7 @@ void MainWindow::buildCommonWidgets()
createDockWidget(simView, new PrimaryFlightDisplay(this), tr("Primary Flight Display"), "PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET", VIEW_SIMULATION, Qt::RightDockWidgetArea);
// Add dock widgets for the engineering view
createDockWidget(engineeringView, new QGCMAVLinkInspector(LinkManager::instance()->mavlink(), this), tr("MAVLink Inspector"), "MAVLINK_INSPECTOR_DOCKWIDGET", VIEW_ENGINEER, Qt::RightDockWidgetArea);
createDockWidget(engineeringView, new QGCMAVLinkInspector(MAVLinkProtocol::instance(), this), tr("MAVLink Inspector"), "MAVLINK_INSPECTOR_DOCKWIDGET", VIEW_ENGINEER, Qt::RightDockWidgetArea);
createDockWidget(engineeringView, new ParameterInterface(this), tr("Onboard Parameters"), "PARAMETER_INTERFACE_DOCKWIDGET", VIEW_ENGINEER, Qt::RightDockWidgetArea);
createDockWidget(engineeringView, new QGCUASFileViewMulti(this), tr("Onboard Files"), "FILE_VIEW_DOCKWIDGET", VIEW_ENGINEER, Qt::RightDockWidgetArea);
createDockWidget(engineeringView, new HUD(320, 240, this), tr("Video Downlink"), "HEAD_UP_DISPLAY_DOCKWIDGET", VIEW_ENGINEER, Qt::RightDockWidgetArea);
......@@ -662,7 +662,7 @@ void MainWindow::loadDockWidget(const QString& name)
}
else if (name == "MAVLINK_INSPECTOR_DOCKWIDGET")
{
createDockWidget(centerStack->currentWidget(),new QGCMAVLinkInspector(LinkManager::instance()->mavlink(),this),tr("MAVLink Inspector"),"MAVLINK_INSPECTOR_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
createDockWidget(centerStack->currentWidget(),new QGCMAVLinkInspector(MAVLinkProtocol::instance(),this),tr("MAVLink Inspector"),"MAVLINK_INSPECTOR_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
}
else if (name == "PARAMETER_INTERFACE_DOCKWIDGET")
{
......@@ -816,7 +816,7 @@ void MainWindow::connectCommonWidgets()
{
if (infoDockWidget && infoDockWidget->widget())
{
connect(LinkManager::instance()->mavlink(), SIGNAL(receiveLossChanged(int, float)),
connect(MAVLinkProtocol::instance(), SIGNAL(receiveLossChanged(int, float)),
infoDockWidget->widget(), SLOT(updateSendLoss(int, float)));
}
}
......
......@@ -15,7 +15,7 @@ OpalLinkConfigurationWindow::OpalLinkConfigurationWindow(OpalLink* link,
connect(ui.opalInstIDSpinBox, SIGNAL(valueChanged(int)), link, SLOT(setOpalInstID(int)));
connect(link, &LinkInterface::connected, this, OpalLinkConfigurationWindow::_linkConnected);
connect(link, &LinkInterface::disconnected, this, OpalLinkConfigurationWindow::_linkDisConnected);
connect(link, &LinkInterface::disconnected, this, OpalLinkConfigurationWindow::_linkDisconnected);
this->show();
}
......
......@@ -43,10 +43,6 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
connect(ui->positionSlider, &QSlider::valueChanged, this, &QGCMAVLinkLogPlayer::jumpToSliderVal);
connect(ui->positionSlider, &QSlider::sliderPressed, this, &QGCMAVLinkLogPlayer::pause);
// We use this to queue the signal over to mavlink. This way it will be behind any remaining
// bytesReady signals in the queue.
connect(this, &QGCMAVLinkLogPlayer::suspendLogForReplay, mavlink, &MAVLinkProtocol::suspendLogForReplay);
setAccelerationFactorInt(49);
ui->speedSlider->setValue(49);
updatePositionSliderUi(0.0);
......@@ -84,7 +80,7 @@ void QGCMAVLinkLogPlayer::play()
Q_ASSERT(logFile.isOpen());
LinkManager::instance()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay."));
emit suspendLogForReplay(true);
mavlink->suspendLogForReplay(true);
// Disable the log file selector button
ui->selectFileButton->setEnabled(false);
......@@ -122,7 +118,7 @@ void QGCMAVLinkLogPlayer::play()
void QGCMAVLinkLogPlayer::pause()
{
LinkManager::instance()->setConnectionsAllowed();
emit suspendLogForReplay(false);
mavlink->suspendLogForReplay(false);
loopTimer.stop();
isPlaying = false;
......@@ -642,7 +638,7 @@ void QGCMAVLinkLogPlayer::_finishPlayback(void)
emit logFileEndReached();
emit suspendLogForReplay(false);
mavlink->suspendLogForReplay(false);
LinkManager::instance()->setConnectionsAllowed();
}
......
......@@ -60,9 +60,6 @@ signals:
void bytesReady(LinkInterface* link, const QByteArray& bytes);
void logFileEndReached();
/// @brief Connected to the MAVLinkProtocol::suspendLogForReplay
void suspendLogForReplay(bool suspend);
protected:
quint64 playbackStartTime; ///< The time when the logfile was first played back. This is used to pace out replaying the messages to fix long-term drift/skew. 0 indicates that the player hasn't initiated playback of this log file. In units of milliseconds since epoch UTC.
quint64 logCurrentTime; ///< The timestamp of the next message in the log file. In units of microseconds since epoch UTC.
......
......@@ -52,7 +52,7 @@ _ui(new Ui::SettingsDialog)
// Add the joystick settings pane
_ui->tabWidget->addTab(new JoystickWidget(joystick, this), "Controllers");
MAVLinkSettingsWidget* msettings = new MAVLinkSettingsWidget(LinkManager::instance()->mavlink(), this);
MAVLinkSettingsWidget* msettings = new MAVLinkSettingsWidget(MAVLinkProtocol::instance(), this);
_ui->tabWidget->addTab(msettings, "MAVLink");
this->window()->setWindowTitle(tr("QGroundControl Settings"));
......
......@@ -59,23 +59,19 @@ UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent),
void UASControlWidget::updateModesList()
{
// Detect autopilot type
int autopilot = MAV_AUTOPILOT_GENERIC;
if (this->uasID >= 0) {
UASInterface *uas = UASManager::instance()->getUASForId(this->uasID);
if (uas) {
autopilot = UASManager::instance()->getUASForId(this->uasID)->getAutopilotType();
}
if (this->uasID == 0) {
return;
}
AutoPilotPlugin* autopilotPlugin = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(autopilot);
UASInterface*uas = UASManager::instance()->getUASForId(this->uasID);
Q_ASSERT(uas);
_modeList = autopilotPlugin->getModes();
_modeList = AutoPilotPluginManager::instance()->getModes(uas->getAutopilotType());
// Set combobox items
ui.modeComboBox->clear();
foreach (AutoPilotPlugin::FullMode_t fullMode, _modeList) {
ui.modeComboBox->addItem(UAS::getShortModeTextFor(fullMode.baseMode, fullMode.customMode, autopilot).remove(0, 2));
foreach (AutoPilotPluginManager::FullMode_t fullMode, _modeList) {
ui.modeComboBox->addItem(uas->getShortModeTextFor(fullMode.baseMode, fullMode.customMode).remove(0, 2));
}
// Select first mode in list
......@@ -197,7 +193,7 @@ void UASControlWidget::transmitMode()
UASInterface* uas_iface = UASManager::instance()->getUASForId(this->uasID);
if (uas_iface) {
if (modeIdx >= 0 && modeIdx < _modeList.count()) {
AutoPilotPlugin::FullMode_t fullMode = _modeList[modeIdx];
AutoPilotPluginManager::FullMode_t fullMode = _modeList[modeIdx];
// include armed state
if (armed) {
fullMode.baseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
......
......@@ -38,7 +38,7 @@ This file is part of the QGROUNDCONTROL project
#include <QPushButton>
#include <ui_UASControl.h>
#include <UASInterface.h>
#include "AutoPilotPlugin.h"
#include "AutoPilotPluginManager.h"
/**
* @brief Widget controlling one MAV
......@@ -79,7 +79,7 @@ protected slots:
protected:
int uasID; ///< Reference to the current uas
QList<AutoPilotPlugin::FullMode_t> _modeList; ///< Mode list for the current UAS
QList<AutoPilotPluginManager::FullMode_t> _modeList; ///< Mode list for the current UAS
int modeIdx; ///< Current uas mode index
bool armed; ///< Engine state
......
......@@ -124,7 +124,7 @@ void UASListWidget::updateStatus()
if (!link)
continue;
MAVLinkProtocol* mavlink = LinkManager::instance()->mavlink();
MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
// Build the tooltip out of the protocol parsing data: received, dropped, and parsing errors.
QString displayString("");
......@@ -167,10 +167,10 @@ void UASListWidget::addUAS(UASInterface* uas)
if (!uasViews.contains(uas))
{
// Only display the UAS in a single link.
QList<LinkInterface*>* x = uas->getLinks();
if (x->size())
QList<LinkInterface*> x = uas->getLinks();
if (x.size())
{
LinkInterface* li = x->first();
LinkInterface* li = x.first();
// Find an existing QGroupBox for this LinkInterface or create a
// new one.
......
Supports Markdown
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