Commit 69d26f94 authored by Don Gagne's avatar Don Gagne

Give access to mavlink message stream to core plugin

parent 37df3d36
......@@ -30,6 +30,7 @@
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
#include "QGCQGeoCoordinate.h"
#include "QGCCorePlugin.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
......@@ -79,7 +80,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _autopilotPlugin(NULL)
, _mavlink(NULL)
, _soloFirmware(false)
, _settingsManager(qgcApp()->toolbox()->settingsManager())
, _toolbox(qgcApp()->toolbox())
, _settingsManager(_toolbox->settingsManager())
, _joystickMode(JoystickModeRC)
, _joystickEnabled(false)
, _uas(NULL)
......@@ -166,7 +168,7 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &Vehicle::_activeJoystickChanged);
_mavlink = qgcApp()->toolbox()->mavlinkProtocol();
_mavlink = _toolbox->mavlinkProtocol();
connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
......@@ -183,7 +185,7 @@ Vehicle::Vehicle(LinkInterface* link,
_autopilotPlugin = _firmwarePlugin->autopilotPlugin(this);
// connect this vehicle to the follow me handle manager
connect(this, &Vehicle::flightModeChanged,qgcApp()->toolbox()->followMe(), &FollowMe::followMeHandleManager);
connect(this, &Vehicle::flightModeChanged,_toolbox->followMe(), &FollowMe::followMeHandleManager);
// PreArm Error self-destruct timer
connect(&_prearmErrorTimer, &QTimer::timeout, this, &Vehicle::_prearmErrorTimeout);
......@@ -204,8 +206,8 @@ Vehicle::Vehicle(LinkInterface* link,
_mav = uas();
// Listen for system messages
connect(qgcApp()->toolbox()->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage);
connect(qgcApp()->toolbox()->uasMessageHandler(), &UASMessageHandler::textMessageReceived, this, &Vehicle::_handletextMessageReceived);
connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage);
connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageReceived, this, &Vehicle::_handletextMessageReceived);
// Now connect the new UAS
connect(_mav, SIGNAL(attitudeChanged (UASInterface*,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64)));
connect(_mav, SIGNAL(attitudeChanged (UASInterface*,int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64)));
......@@ -244,7 +246,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _autopilotPlugin(NULL)
, _mavlink(NULL)
, _soloFirmware(false)
, _settingsManager(qgcApp()->toolbox()->settingsManager())
, _toolbox(qgcApp()->toolbox())
, _settingsManager(_toolbox->settingsManager())
, _joystickMode(JoystickModeRC)
, _joystickEnabled(false)
, _uas(NULL)
......@@ -510,6 +513,11 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
return;
}
// Give the Core Plugin access to all mavlink traffic
if (!_toolbox->corePlugin()->mavlinkMessage(this, link, message)) {
return;
}
switch (message.msgid) {
case MAVLINK_MSG_ID_HOME_POSITION:
_handleHomePosition(message);
......@@ -810,7 +818,7 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message)
emit mavCommandResult(_id, message.compid, ack.command, ack.result, false /* noResponsefromVehicle */);
if (showError) {
QString commandName = qgcApp()->toolbox()->missionCommandTree()->friendlyName((MAV_CMD)ack.command);
QString commandName = _toolbox->missionCommandTree()->friendlyName((MAV_CMD)ack.command);
switch (ack.result) {
case MAV_RESULT_TEMPORARILY_REJECTED:
......@@ -1193,8 +1201,8 @@ void Vehicle::_addLink(LinkInterface* link)
qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((ulong)link, 0, 16);
_links += link;
_updatePriorityLink();
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
connect(_toolbox->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
connect(_toolbox->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
}
}
......@@ -1283,7 +1291,7 @@ void Vehicle::_updatePriorityLink(void)
}
if (newPriorityLink) {
_priorityLink = qgcApp()->toolbox()->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
_priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
}
}
......@@ -1360,7 +1368,7 @@ QString Vehicle::getMavIconColor()
QString Vehicle::formatedMessages()
{
QString messages;
foreach(UASMessage* message, qgcApp()->toolbox()->uasMessageHandler()->messages()) {
foreach(UASMessage* message, _toolbox->uasMessageHandler()->messages()) {
messages += message->getFormatedText();
}
return messages;
......@@ -1368,7 +1376,7 @@ QString Vehicle::formatedMessages()
void Vehicle::clearMessages()
{
qgcApp()->toolbox()->uasMessageHandler()->clearMessages();
_toolbox->uasMessageHandler()->clearMessages();
}
void Vehicle::_handletextMessageReceived(UASMessage* message)
......@@ -1396,7 +1404,7 @@ void Vehicle::_handleTextMessage(int newCount)
return;
}
UASMessageHandler* pMh = qgcApp()->toolbox()->uasMessageHandler();
UASMessageHandler* pMh = _toolbox->uasMessageHandler();
MessageType_t type = newCount ? _currentMessageType : MessageNone;
int errorCount = _currentErrorCount;
int warnCount = _currentWarningCount;
......@@ -1482,7 +1490,7 @@ void Vehicle::_loadSettings(void)
}
// Joystick enabled is a global setting so first make sure there are any joysticks connected
if (qgcApp()->toolbox()->joystickManager()->joysticks().count()) {
if (_toolbox->joystickManager()->joysticks().count()) {
setJoystickEnabled(settings.value(_joystickEnabledSettingsKey, false).toBool());
}
}
......@@ -1497,7 +1505,7 @@ void Vehicle::_saveSettings(void)
// The joystick enabled setting should only be changed if a joystick is present
// since the checkbox can only be clicked if one is present
if (qgcApp()->toolbox()->joystickManager()->joysticks().count()) {
if (_toolbox->joystickManager()->joysticks().count()) {
settings.setValue(_joystickEnabledSettingsKey, _joystickEnabled);
}
}
......@@ -1840,11 +1848,11 @@ void Vehicle::disconnectInactiveVehicle(void)
// Vehicle is no longer communicating with us, disconnect all links
LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
LinkManager* linkMgr = _toolbox->linkManager();
for (int i=0; i<_links.count(); i++) {
// FIXME: This linkInUse check is a hack fix for multiple vehicles on the same link.
// The real fix requires significant restructuring which will come later.
if (!qgcApp()->toolbox()->multiVehicleManager()->linkInUse(_links[i], this)) {
if (!_toolbox->multiVehicleManager()->linkInUse(_links[i], this)) {
linkMgr->disconnectLink(_links[i]);
}
}
......@@ -1855,7 +1863,7 @@ void Vehicle::_imageReady(UASInterface*)
if(_uas)
{
QImage img = _uas->getImage();
qgcApp()->toolbox()->imageProvider()->setImage(&img, _id);
_toolbox->imageProvider()->setImage(&img, _id);
_flowImageIndex++;
emit flowImageIndexChanged();
}
......@@ -1920,7 +1928,7 @@ void Vehicle::_connectionActive(void)
void Vehicle::_say(const QString& text)
{
qgcApp()->toolbox()->audioOutput()->say(text.toLower());
_toolbox->audioOutput()->say(text.toLower());
}
bool Vehicle::fixedWing(void) const
......@@ -2021,7 +2029,7 @@ QString Vehicle::vehicleTypeName() const {
/// Returns the string to speak to identify the vehicle
QString Vehicle::_vehicleIdSpeech(void)
{
if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() > 1) {
if (_toolbox->multiVehicleManager()->vehicles()->count() > 1) {
return QString("vehicle %1").arg(id());
} else {
return QString();
......@@ -2232,7 +2240,7 @@ void Vehicle::_sendMavCommandAgain(void)
emit mavCommandResult(_id, queuedCommand.component, queuedCommand.command, MAV_RESULT_FAILED, true /* noResponsefromVehicle */);
if (queuedCommand.showError) {
qgcApp()->showMessage(tr("Vehicle did not respond to command: %1").arg(qgcApp()->toolbox()->missionCommandTree()->friendlyName(queuedCommand.command)));
qgcApp()->showMessage(tr("Vehicle did not respond to command: %1").arg(_toolbox->missionCommandTree()->friendlyName(queuedCommand.command)));
}
_mavCommandQueue.removeFirst();
_sendNextQueuedMavCommand();
......
......@@ -866,6 +866,7 @@ private:
AutoPilotPlugin* _autopilotPlugin;
MAVLinkProtocol* _mavlink;
bool _soloFirmware;
QGCToolbox* _toolbox;
SettingsManager* _settingsManager;
QList<LinkInterface*> _links;
......
......@@ -232,3 +232,12 @@ QQmlApplicationEngine* QGCCorePlugin::createRootWindow(QObject *parent)
pEngine->load(QUrl(QStringLiteral("qrc:/qml/MainWindowNative.qml")));
return pEngine;
}
bool QGCCorePlugin::mavlinkMessage(Vehicle* vehicle, LinkInterface* link, mavlink_message_t message)
{
Q_UNUSED(vehicle);
Q_UNUSED(link);
Q_UNUSED(message);
return true;
}
......@@ -11,6 +11,7 @@
#include "QGCToolbox.h"
#include "QGCPalette.h"
#include "QGCMAVLink.h"
#include <QObject>
#include <QVariantList>
......@@ -28,6 +29,8 @@ class QGCCorePlugin_p;
class FactMetaData;
class QGeoPositionInfoSource;
class QQmlApplicationEngine;
class Vehicle;
class LinkInterface;
class QGCCorePlugin : public QGCTool
{
......@@ -90,6 +93,10 @@ public:
/// Allows the plugin to override the creation of the root (native) window.
virtual QQmlApplicationEngine* createRootWindow(QObject* parent);
/// Allows the plugin to see all mavlink traffic to a vehicle
/// @return true: Allow vehicle to continue processing, false: Vehicle should not process message
virtual bool mavlinkMessage(Vehicle* vehicle, LinkInterface* link, mavlink_message_t message);
bool showTouchAreas(void) const { return _showTouchAreas; }
bool showAdvancedUI(void) const { return _showAdvancedUI; }
void setShowTouchAreas(bool show);
......
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