Commit 8e681c09 authored by Don Gagne's avatar Don Gagne

Merge pull request #2234 from DonLakeFlyer/ACWork

Auto connect support [merge after Stable 2.8]
parents 0c215d46 0bcbd19d
......@@ -270,7 +270,6 @@ HEADERS += \
src/QmlControls/QGCQGeoCoordinate.h \
src/QmlControls/QGroundControlQmlGlobal.h \
src/QmlControls/QmlObjectListModel.h \
src/SerialPortIds.h \
src/uas/FileManager.h \
src/uas/UAS.h \
src/uas/UASInterface.h \
......
......@@ -28,7 +28,6 @@
<file alias="PowerComponent.qml">src/AutoPilotPlugins/PX4/PowerComponent.qml</file>
<file alias="PowerComponentSummary.qml">src/AutoPilotPlugins/PX4/PowerComponentSummary.qml</file>
<file alias="PX4FlowSensor.qml">src/VehicleSetup/PX4FlowSensor.qml</file>
<file alias="QGroundControl/Controls/ClickableColor.qml">src/QmlControls/ClickableColor.qml</file>
<file alias="QGroundControl/Controls/DropButton.qml">src/QmlControls/DropButton.qml</file>
<file alias="QGroundControl/Controls/ExclusiveGroupItem.qml">src/QmlControls/ExclusiveGroupItem.qml</file>
......@@ -42,7 +41,6 @@
<file alias="QGroundControl/Controls/ParameterEditor.qml">src/QmlControls/ParameterEditor.qml</file>
<file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file>
<file alias="QGroundControl/Controls/QGCButton.qml">src/QmlControls/QGCButton.qml</file>
<file alias="QGroundControl/Controls/QGCCanvas.qml">src/QmlControls/QGCCanvas.qml</file>
<file alias="QGroundControl/Controls/QGCCheckBox.qml">src/QmlControls/QGCCheckBox.qml</file>
<file alias="QGroundControl/Controls/QGCColoredImage.qml">src/QmlControls/QGCColoredImage.qml</file>
<file alias="QGroundControl/Controls/QGCComboBox.qml">src/QmlControls/QGCComboBox.qml</file>
......@@ -62,20 +60,17 @@
<file alias="QGroundControl/Controls/VehicleRotationCal.qml">src/QmlControls/VehicleRotationCal.qml</file>
<file alias="QGroundControl/Controls/VehicleSummaryRow.qml">src/QmlControls/VehicleSummaryRow.qml</file>
<file alias="QGroundControl/Controls/ViewWidget.qml">src/ViewWidgets/ViewWidget.qml</file>
<file alias="QGroundControl/FactControls/FactCheckBox.qml">src/FactSystem/FactControls/FactCheckBox.qml</file>
<file alias="QGroundControl/FactControls/FactComboBox.qml">src/FactSystem/FactControls/FactComboBox.qml</file>
<file alias="QGroundControl/FactControls/FactLabel.qml">src/FactSystem/FactControls/FactLabel.qml</file>
<file alias="QGroundControl/FactControls/FactPanel.qml">src/FactSystem/FactControls/FactPanel.qml</file>
<file alias="QGroundControl/FactControls/FactTextField.qml">src/FactSystem/FactControls/FactTextField.qml</file>
<file alias="QGroundControl/FactControls/qmldir">src/FactSystem/FactControls/qmldir</file>
<file alias="QGroundControl/FlightDisplay/FlightDisplayView.qml">src/FlightDisplay/FlightDisplayView.qml</file>
<file alias="QGroundControl/FlightDisplay/FlightDisplayViewMap.qml">src/FlightDisplay/FlightDisplayViewMap.qml</file>
<file alias="QGroundControl/FlightDisplay/FlightDisplayViewVideo.qml">src/FlightDisplay/FlightDisplayViewVideo.qml</file>
<file alias="QGroundControl/FlightDisplay/FlightDisplayViewWidgets.qml">src/FlightDisplay/FlightDisplayViewWidgets.qml</file>
<file alias="QGroundControl/FlightDisplay/qmldir">src/FlightDisplay/qmldir</file>
<file alias="QGroundControl/FlightMap/FlightMap.qml">src/FlightMap/FlightMap.qml</file>
<file alias="QGroundControl/FlightMap/MissionItemIndicator.qml">src/FlightMap/MapItems/MissionItemIndicator.qml</file>
<file alias="QGroundControl/FlightMap/MissionItemView.qml">src/FlightMap/MapItems/MissionItemView.qml</file>
......@@ -90,10 +85,8 @@
<file alias="QGroundControl/FlightMap/QGCVideoBackground.qml">src/FlightMap/QGCVideoBackground.qml</file>
<file alias="QGroundControl/FlightMap/qmldir">src/FlightMap/qmldir</file>
<file alias="QGroundControl/FlightMap/VehicleMapItem.qml">src/FlightMap/MapItems/VehicleMapItem.qml</file>
<file alias="QGroundControl/ScreenTools/qmldir">src/QmlControls/QGroundControl.ScreenTools.qmldir</file>
<file alias="QGroundControl/ScreenTools/ScreenTools.qml">src/QmlControls/ScreenTools.qml</file>
<file alias="QmlTest.qml">src/QmlControls/QmlTest.qml</file>
<file alias="RadioComponent.qml">src/AutoPilotPlugins/PX4/RadioComponent.qml</file>
<file alias="RadioComponentSummary.qml">src/AutoPilotPlugins/PX4/RadioComponentSummary.qml</file>
......
......@@ -139,7 +139,7 @@ void AirframeComponentController::_rebootAfterStackUnwind(void)
QGC::SLEEP::usleep(500);
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
}
qgcApp()->toolbox()->linkManager()->disconnectAll();
qgcApp()->toolbox()->linkManager()->disconnectAll(false /* disconnectAutoconnectLink */);
qgcApp()->restoreOverrideCursor();
}
......
......@@ -50,14 +50,13 @@ HomePositionManager::HomePositionManager(QGCApplication* app)
, homeLon(8.549444)
, homeAlt(470.0)
{
qmlRegisterUncreatableType<HomePositionManager> ("QGroundControl", 1, 0, "HomePositionManager", "Reference only");
}
void HomePositionManager::setToolbox(QGCToolbox *toolbox)
{
QGCTool::setToolbox(toolbox);
qmlRegisterUncreatableType<HomePositionManager> ("QGroundControl", 1, 0, "HomePositionManager", "Reference only");
_loadSettings();
}
......
......@@ -184,7 +184,7 @@ Item {
id: dropDownItem
visible: checked
QGCCanvas {
Canvas {
id: arrowCanvas
anchors.fill: parent
......
import QtQuick 2.2
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0
/// Canvas has some sort of bug in it which can cause it to not paint when top level Views
/// are switched. In order to fix this we ahve a signal hacked into ScreenTools to force
/// a repaint.
Canvas {
id: _root
Connections {
target: ScreenTools
onRepaintRequested: _root.requestPaint()
}
}
......@@ -9,7 +9,6 @@ QGCComboBox 1.0 QGCComboBox.qml
QGCColoredImage 1.0 QGCColoredImage.qml
QGCToolBarButton 1.0 QGCToolBarButton.qml
QGCMovableItem 1.0 QGCMovableItem.qml
QGCCanvas 1.0 QGCCanvas.qml
SubMenuButton 1.0 SubMenuButton.qml
IndicatorButton 1.0 IndicatorButton.qml
......
......@@ -33,6 +33,8 @@ static const char* kQmlGlobalKeyName = "QGCQml";
QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCToolbox* toolbox, QObject* parent)
: QObject(parent)
, _multiVehicleManager(toolbox->multiVehicleManager())
, _linkManager(toolbox->linkManager())
, _homePositionManager(toolbox->homePositionManager())
, _flightMapSettings(toolbox->flightMapSettings())
{
......@@ -70,25 +72,25 @@ bool QGroundControlQmlGlobal::loadBoolGlobalSetting (const QString& key, bool de
#ifdef QT_DEBUG
void QGroundControlQmlGlobal::_startMockLink(MockConfiguration* mockConfig)
{
MockLink* mockLink = new MockLink(mockConfig);
LinkManager* linkManager = qgcApp()->toolbox()->linkManager();
linkManager->_addLink(mockLink);
linkManager->connectLink(mockLink);
mockConfig->setDynamic(true);
linkManager->linkConfigurations()->append(mockConfig);
linkManager->createConnectedLink(mockConfig, false /* autoconnectLink */);
}
#endif
void QGroundControlQmlGlobal::startPX4MockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
MockConfiguration mockConfig("PX4 MockLink");
MockConfiguration* mockConfig = new MockConfiguration("PX4 MockLink");
mockConfig.setFirmwareType(MAV_AUTOPILOT_PX4);
mockConfig.setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig.setSendStatusText(sendStatusText);
mockConfig->setFirmwareType(MAV_AUTOPILOT_PX4);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
_startMockLink(&mockConfig);
_startMockLink(mockConfig);
#else
Q_UNUSED(sendStatusText);
#endif
......@@ -97,13 +99,13 @@ void QGroundControlQmlGlobal::startPX4MockLink(bool sendStatusText)
void QGroundControlQmlGlobal::startGenericMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
MockConfiguration mockConfig("Generic MockLink");
MockConfiguration* mockConfig = new MockConfiguration("Generic MockLink");
mockConfig.setFirmwareType(MAV_AUTOPILOT_GENERIC);
mockConfig.setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig.setSendStatusText(sendStatusText);
mockConfig->setFirmwareType(MAV_AUTOPILOT_GENERIC);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
_startMockLink(&mockConfig);
_startMockLink(mockConfig);
#else
Q_UNUSED(sendStatusText);
#endif
......@@ -112,13 +114,13 @@ void QGroundControlQmlGlobal::startGenericMockLink(bool sendStatusText)
void QGroundControlQmlGlobal::startAPMArduCopterMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
MockConfiguration mockConfig("APM ArduCopter MockLink");
MockConfiguration* mockConfig = new MockConfiguration("APM ArduCopter MockLink");
mockConfig.setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig.setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig.setSendStatusText(sendStatusText);
mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
_startMockLink(&mockConfig);
_startMockLink(mockConfig);
#else
Q_UNUSED(sendStatusText);
#endif
......@@ -127,13 +129,13 @@ void QGroundControlQmlGlobal::startAPMArduCopterMockLink(bool sendStatusText)
void QGroundControlQmlGlobal::startAPMArduPlaneMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
MockConfiguration mockConfig("APM ArduPlane MockLink");
MockConfiguration* mockConfig = new MockConfiguration("APM ArduPlane MockLink");
mockConfig.setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig.setVehicleType(MAV_TYPE_FIXED_WING);
mockConfig.setSendStatusText(sendStatusText);
mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig->setVehicleType(MAV_TYPE_FIXED_WING);
mockConfig->setSendStatusText(sendStatusText);
_startMockLink(&mockConfig);
_startMockLink(mockConfig);
#else
Q_UNUSED(sendStatusText);
#endif
......@@ -144,12 +146,12 @@ void QGroundControlQmlGlobal::stopAllMockLinks(void)
#ifdef QT_DEBUG
LinkManager* linkManager = qgcApp()->toolbox()->linkManager();
QList<LinkInterface*> links = linkManager->getLinks();
for (int i=0; i<links.count(); i++) {
LinkInterface* link = links[i];
for (int i=0; i<linkManager->links()->count(); i++) {
LinkInterface* link = linkManager->links()->value<LinkInterface*>(i);
MockLink* mockLink = qobject_cast<MockLink*>(link);
if (mockLink) {
linkManager->disconnectLink(mockLink);
linkManager->disconnectLink(mockLink, false /* disconnectAutoconnectLink */);
}
}
#endif
......
......@@ -31,6 +31,7 @@
#include "QGCApplication.h"
#include "MainWindow.h"
#include "LinkManager.h"
#include "HomePositionManager.h"
#include "FlightMapSettings.h"
......@@ -47,6 +48,8 @@ class QGroundControlQmlGlobal : public QObject
public:
QGroundControlQmlGlobal(QGCToolbox* toolbox, QObject* parent = NULL);
Q_PROPERTY(LinkManager* linkManager READ linkManager CONSTANT)
Q_PROPERTY(MultiVehicleManager* multiVehicleManager READ multiVehicleManager CONSTANT)
Q_PROPERTY(HomePositionManager* homePositionManager READ homePositionManager CONSTANT)
Q_PROPERTY(FlightMapSettings* flightMapSettings READ flightMapSettings CONSTANT)
......@@ -81,6 +84,8 @@ public:
// Property accesors
LinkManager* linkManager () { return _linkManager; }
MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; }
HomePositionManager* homePositionManager () { return _homePositionManager; }
FlightMapSettings* flightMapSettings () { return _flightMapSettings; }
......@@ -124,6 +129,8 @@ private:
void _startMockLink(MockConfiguration* mockConfig);
#endif
MultiVehicleManager* _multiVehicleManager;
LinkManager* _linkManager;
HomePositionManager* _homePositionManager;
FlightMapSettings* _flightMapSettings;
};
......
......@@ -197,11 +197,6 @@ int QmlObjectListModel::count(void) const
return rowCount();
}
QObject* QmlObjectListModel::get(int index)
{
return _objectList[index];
}
void QmlObjectListModel::setDirty(bool dirty)
{
_dirty = dirty;
......
......@@ -34,14 +34,14 @@ public:
QmlObjectListModel(QObject* parent = NULL);
~QmlObjectListModel();
Q_INVOKABLE QObject* get(int index);
Q_PROPERTY(int count READ count NOTIFY countChanged)
/// Returns true if any of the items in the list are dirty. Requires each object to have
/// a dirty property and dirtyChanged signal.
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_INVOKABLE QObject* get(int index) { return _objectList[index]; }
// Property accessors
int count(void) const;
......@@ -52,12 +52,13 @@ public:
void append(QObject* object);
void clear(void);
QObject* removeAt(int i);
QObject* removeOne(QObject* object) { return removeAt(indexOf(object)); }
void insert(int i, QObject* object);
QObject* operator[](int i);
const QObject* operator[](int i) const;
template <class T>
const QList<T*>& list(void) { return *((QList<T*>*)((void*)(&_objectList))); }
bool contains(QObject* object) { return _objectList.indexOf(object) != -1; }
int indexOf(QObject* object) { return _objectList.indexOf(object); }
template<class T> T value(int index) { return qobject_cast<T>(_objectList[index]); }
signals:
void countChanged(int count);
......
......@@ -47,9 +47,4 @@ Item {
property real fontWidth: contentWidth * (ScreenToolsController.testHighDPI ? 2 : 1)
property real fontHeight: contentHeight * (ScreenToolsController.testHighDPI ? 2 : 1)
}
Connections {
target: ScreenToolsController
onRepaintRequested: repaintRequested()
}
}
......@@ -43,15 +43,5 @@ const double ScreenToolsController::_largeFontPixelSizeRatio = 1.66;
ScreenToolsController::ScreenToolsController()
{
MainWindow* mainWindow = MainWindow::instance();
// Unit tests can run Qml without MainWindow
if (mainWindow) {
connect(mainWindow, &MainWindow::repaintCanvas, this, &ScreenToolsController::_updateCanvas);
}
}
void ScreenToolsController::_updateCanvas()
{
emit repaintRequested();
}
......@@ -114,12 +114,6 @@ public:
bool testHighDPI () { return false; }
#endif
signals:
void repaintRequested();
private slots:
void _updateCanvas();
private:
static const double _defaultFontPixelSizeRatio;
static const double _smallFontPixelSizeRatio;
......
......@@ -57,33 +57,26 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<MultiVehicleManager>("QGroundControl.MultiVehicleManager", 1, 0, "MultiVehicleManager", "Reference only");
connect(_toolbox->linkManager(), &LinkManager::linkActive, this, &MultiVehicleManager::_linkActive);
}
bool MultiVehicleManager::notifyHeartbeatInfo(LinkInterface* link, int vehicleId, mavlink_heartbeat_t& heartbeat)
void MultiVehicleManager::_linkActive(LinkInterface* link, int vehicleId, int vehicleFirmwareType, int vehicleType)
{
if (!getVehicleById(vehicleId) && !_ignoreVehicleIds.contains(vehicleId)) {
if (vehicleId == _mavlinkProtocol->getSystemId()) {
_app->showToolBarMessage(QString("Warning: A vehicle is using the same system id as QGroundControl: %1").arg(vehicleId));
}
QSettings settings;
bool mavlinkVersionCheck = settings.value("VERSION_CHECK_ENABLED", true).toBool();
if (mavlinkVersionCheck && heartbeat.mavlink_version != MAVLINK_VERSION) {
_ignoreVehicleIds += vehicleId;
_app->showToolBarMessage(QString("The MAVLink protocol version on vehicle #%1 and QGroundControl differ! "
"It is unsafe to use different MAVLink versions. "
"QGroundControl therefore refuses to connect to vehicle #%1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(vehicleId).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION));
return false;
}
if (!getVehicleById(vehicleId)) {
qCDebug(MultiVehicleManagerLog) << "Adding new vehicle linkName:vehicleId:vehicleFirmwareType:vehicleType"
<< link->getName()
<< vehicleId
<< vehicleFirmwareType
<< vehicleType;
Vehicle* vehicle = new Vehicle(link, vehicleId, (MAV_AUTOPILOT)heartbeat.autopilot, (MAV_TYPE)heartbeat.type, _firmwarePluginManager, _autopilotPluginManager, _joystickManager);
Vehicle* vehicle = new Vehicle(link, vehicleId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _autopilotPluginManager, _joystickManager);
if (!vehicle) {
qWarning() << "New Vehicle allocation failed";
return false;
return;
}
connect(vehicle, &Vehicle::allLinksDisconnected, this, &MultiVehicleManager::_deleteVehiclePhase1);
connect(vehicle, &Vehicle::allLinksInactive, this, &MultiVehicleManager::_deleteVehiclePhase1);
connect(vehicle->autopilotPlugin(), &AutoPilotPlugin::parametersReadyChanged, this, &MultiVehicleManager::_autopilotParametersReadyChanged);
_vehicles.append(vehicle);
......@@ -92,22 +85,20 @@ bool MultiVehicleManager::notifyHeartbeatInfo(LinkInterface* link, int vehicleId
setActiveVehicle(vehicle);
}
return true;
}
/// This slot is connected to the Vehicle::allLinksDestroyed signal such that the Vehicle is deleted
/// and all other right things happen when the Vehicle goes away.
void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle)
{
qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase1";
qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase1" << vehicle;
_vehicleBeingDeleted = vehicle;
_vehiclesBeingDeleted << vehicle;
// Remove from map
bool found = false;
for (int i=0; i<_vehicles.count(); i++) {
if (_vehicles[i] == _vehicleBeingDeleted) {
if (_vehicles[i] == vehicle) {
_vehicles.removeAt(i);
found = true;
break;
......@@ -136,9 +127,9 @@ void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle)
QTimer::singleShot(20, this, &MultiVehicleManager::_deleteVehiclePhase2);
}
void MultiVehicleManager::_deleteVehiclePhase2 (void)
void MultiVehicleManager::_deleteVehiclePhase2(void)
{
qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase2";
qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase2" << _vehiclesBeingDeleted[0];
/// Qml has been notified of vehicle about to go away and should be disconnected from it by now.
/// This means we can now clear the active vehicle property and delete the Vehicle for real.
......@@ -159,7 +150,8 @@ void MultiVehicleManager::_deleteVehiclePhase2 (void)
}
}
_vehicleBeingDeleted->deleteLater();
delete _vehiclesBeingDeleted[0];
_vehiclesBeingDeleted.removeAt(0);
}
void MultiVehicleManager::setActiveVehicle(Vehicle* vehicle)
......@@ -189,7 +181,7 @@ void MultiVehicleManager::setActiveVehicle(Vehicle* vehicle)
void MultiVehicleManager::_setActiveVehiclePhase2(void)
{
qCDebug(MultiVehicleManagerLog) << "_setActiveVehiclePhase2";
qCDebug(MultiVehicleManagerLog) << "_setActiveVehiclePhase2 _vehicleBeingSetActive" << _vehicleBeingSetActive;
// Now we signal the new active vehicle
_activeVehicle = _vehicleBeingSetActive;
......
......@@ -58,14 +58,6 @@ public:
// Methods
/// Called to notify that a heartbeat was received with the specified information. MultiVehicleManager
/// will create/update Vehicles as necessary.
/// @param link Heartbeat came through on this link
/// @param vehicleId Mavlink system id for vehicle
/// @param heartbeat Mavlink heartbeat message
/// @return true: continue further processing of this message, false: disregard this message
bool notifyHeartbeatInfo(LinkInterface* link, int vehicleId, mavlink_heartbeat_t& heartbeat);
Q_INVOKABLE Vehicle* getVehicleById(int vehicleId);
UAS* activeUas(void) { return _activeVehicle ? _activeVehicle->uas() : NULL; }
......@@ -98,6 +90,7 @@ private slots:
void _deleteVehiclePhase2(void);
void _setActiveVehiclePhase2(void);
void _autopilotParametersReadyChanged(bool parametersReady);
void _linkActive(LinkInterface* link, int vehicleId, int vehicleFirmwareType, int vehicleType);
private:
bool _vehicleExists(int vehicleId);
......@@ -106,7 +99,7 @@ private:
bool _parameterReadyVehicleAvailable; ///< true: An active vehicle with ready parameters is available
Vehicle* _activeVehicle; ///< Currently active vehicle from a ui perspective
Vehicle* _vehicleBeingDeleted; ///< Vehicle being deleted in queued phases
QList<Vehicle*> _vehiclesBeingDeleted; ///< List of Vehicles being deleted in queued phases
Vehicle* _vehicleBeingSetActive; ///< Vehicle being set active in queued phases
QList<int> _ignoreVehicleIds; ///< List of vehicle id for which we ignore further communication
......
......@@ -93,6 +93,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _satelliteCount(-1)
, _satelliteLock(0)
, _updateCount(0)
, _rcRSSI(0)
, _rcRSSIstore(100.0)
, _missionManager(NULL)
, _missionManagerInitialRequestComplete(false)
, _parameterLoader(NULL)
......@@ -105,6 +107,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _autopilotPluginManager(autopilotPluginManager)
, _joystickManager(joystickManager)
, _flowImageIndex(0)
, _allLinksInactiveSent(false)
{
_addLink(link);
......@@ -121,6 +124,7 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_uas, &UAS::latitudeChanged, this, &Vehicle::setLatitude);
connect(_uas, &UAS::longitudeChanged, this, &Vehicle::setLongitude);
connect(_uas, &UAS::imageReady, this, &Vehicle::_imageReady);
connect(_uas, &UAS::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged);
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
_autopilotPlugin = _autopilotPluginManager->newAutopilotPluginForVehicle(this);
......@@ -186,6 +190,8 @@ Vehicle::Vehicle(LinkInterface* link,
Vehicle::~Vehicle()
{
qCDebug(VehicleLog) << "~Vehicle" << this;
delete _missionManager;
_missionManager = NULL;
......@@ -285,38 +291,29 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message)
bool Vehicle::_containsLink(LinkInterface* link)
{
foreach (SharedLinkInterface sharedLink, _links) {
if (sharedLink.data() == link) {
return true;
}
}
return false;
return _links.contains(link);
}
void Vehicle::_addLink(LinkInterface* link)
{
if (!_containsLink(link)) {
_links += qgcApp()->toolbox()->linkManager()->sharedPointerForLink(link);
_links += link;
qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((ulong)link, 0, 16);
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDisconnected, this, &Vehicle::_linkDisconnected);
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
}
}
void Vehicle::_linkDisconnected(LinkInterface* link)
void Vehicle::_linkInactiveOrDeleted(LinkInterface* link)
{
qCDebug(VehicleLog) << "_linkDisconnected:" << link->getName();
qCDebug(VehicleLog) << "link count:" << _links.count();
qCDebug(VehicleLog) << "_linkInactiveOrDeleted linkCount" << _links.count();
for (int i=0; i<_links.count(); i++) {
if (_links[i].data() == link) {
_links.removeAt(i);
break;
}
}
_links.removeOne(link);
if (_links.count() == 0) {
emit allLinksDisconnected(this);
if (_links.count() == 0 && !_allLinksInactiveSent) {
// Make sure to not send this more than one time
_allLinksInactiveSent = true;
emit allLinksInactive(this);
}
}
......@@ -328,10 +325,7 @@ void Vehicle::sendMessage(mavlink_message_t message)
void Vehicle::_sendMessage(mavlink_message_t message)
{
// Emit message on all links that are currently connected
foreach (SharedLinkInterface sharedLink, _links) {
LinkInterface* link = sharedLink.data();
Q_ASSERT(link);
foreach (LinkInterface* link, _links) {
if (link->isConnected()) {
MAVLinkProtocol* mavlink = _mavlink;
......@@ -350,17 +344,6 @@ void Vehicle::_sendMessage(mavlink_message_t message)
}
}
QList<LinkInterface*> Vehicle::links(void)
{
QList<LinkInterface*> list;
foreach (SharedLinkInterface sharedLink, _links) {
list += sharedLink.data();
}
return list;
}
void Vehicle::setLatitude(double latitude)
{
_coordinate.setLatitude(latitude);
......@@ -1054,11 +1037,11 @@ void Vehicle::_parametersReady(bool parametersReady)
void Vehicle::_communicationInactivityTimedOut(void)
{
// Vechile is no longer communicating with us, disconnect all links
// Vehicle is no longer communicating with us, disconnect all links inactive
LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
for (int i=0; i<_links.count(); i++) {
linkMgr->disconnectLink(_links[i].data());
linkMgr->disconnectLink(_links[i], false /* disconnectAutoconnectLink */);
}
}
......@@ -1077,3 +1060,17 @@ void Vehicle::_imageReady(UASInterface*)
emit flowImageIndexChanged();
}
}
void Vehicle::_remoteControlRSSIChanged(uint8_t rssi)
{
// Low pass to git rid of jitter
_rcRSSIstore = (_rcRSSIstore * 0.9f) + ((float)rssi * 0.1);
uint8_t filteredRSSI = (uint8_t)ceil(_rcRSSIstore);
if(_rcRSSIstore < 0.1) {
filteredRSSI = 0;
}
if(_rcRSSI != filteredRSSI) {
_rcRSSI = filteredRSSI;
emit rcRSSIChanged(_rcRSSI);
}
}
......@@ -111,6 +111,7 @@ public:
Q_PROPERTY(bool joystickEnabled READ joystickEnabled WRITE setJoystickEnabled NOTIFY joystickEnabledChanged)
Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged)
Q_PROPERTY(int flowImageIndex READ flowImageIndex NOTIFY flowImageIndexChanged)
Q_PROPERTY(int rcRSSI READ rcRSSI NOTIFY rcRSSIChanged)
/// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink
/// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
......@@ -173,8 +174,6 @@ public:
/// Provides access to the Firmware Plugin for this Vehicle
FirmwarePlugin* firmwarePlugin(void) { return _firmwarePlugin; }
QList<LinkInterface*> links(void);
int manualControlReservedButtonCount(void);
MissionManager* missionManager(void) { return _missionManager; }
......@@ -251,6 +250,7 @@ public:
QString currentState () { return _currentState; }
int satelliteLock () { return _satelliteLock; }
unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; }
int rcRSSI () { return _rcRSSI; }
ParameterLoader* getParameterLoader(void);
......@@ -259,7 +259,7 @@ public slots:
void setLongitude(double longitude);
signals:
void allLinksDisconnected(Vehicle* vehicle);
void allLinksInactive(Vehicle* vehicle);
void coordinateChanged(QGeoCoordinate coordinate);
void coordinateValidChanged(bool coordinateValid);
void joystickModeChanged(int mode);
......@@ -301,15 +301,17 @@ signals:
void currentStateChanged ();
void satelliteLockChanged ();
void flowImageIndexChanged ();
void rcRSSIChanged (int rcRSSI);
private slots:
void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
void _linkDisconnected(LinkInterface* link);
void _linkInactiveOrDeleted(LinkInterface* link);
void _sendMessage(mavlink_message_t message);
void _sendMessageMultipleNext(void);
void _addNewMapTrajectoryPoint(void);
void _parametersReady(bool parametersReady);
void _communicationInactivityTimedOut(void);
void _remoteControlRSSIChanged(uint8_t rssi);
void _handleTextMessage (int newCount);
void _handletextMessageReceived (UASMessage* message);
......@@ -356,10 +358,7 @@ private:
AutoPilotPlugin* _autopilotPlugin;
MAVLinkProtocol* _mavlink;
/// List of all links associated with this vehicle. We keep SharedLinkInterface objects
/// which are QSharedPointer's in order to maintain reference counts across threads.
/// This way Link deletion works correctly.
QList<SharedLinkInterface> _links;
QList<LinkInterface*> _links;
JoystickMode_t _joystickMode;
bool _joystickEnabled;
......@@ -404,6 +403,8 @@ private:
int _satelliteLock;
int _updateCount;
QString _formatedMessage;
int _rcRSSI;
double _rcRSSIstore;
MissionManager* _missionManager;
bool _missionManagerInitialRequestComplete;
......@@ -444,6 +445,8 @@ private:
int _flowImageIndex;
bool _allLinksInactiveSent; ///< true: allLinkInactive signal already sent one time
// Settings keys
static const char* _settingsGroup;
static const char* _joystickModeSettingsKey;
......
......@@ -26,6 +26,7 @@ import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QtQuick.Dialogs 1.2
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
......@@ -43,8 +44,7 @@ QGCView {
readonly property string highlightSuffix: "</font>"
readonly property string welcomeText: "QGroundControl can upgrade the firmware on Pixhawk devices, 3DR Radios and PX4 Flow Smart Cameras."
readonly property string plugInText: highlightPrefix + "Plug in your device" + highlightSuffix + " via USB to " + highlightPrefix + "start" + highlightSuffix + " firmware upgrade"
readonly property string qgcDisconnectText: "All QGroundControl connections to vehicles must be disconnected prior to firmware upgrade. " +
"Click " + highlightPrefix + "Disconnect" + highlightSuffix + " in the toolbar above."
readonly property string qgcDisconnectText: "All QGroundControl connections to vehicles must be disconnected prior to firmware upgrade."
property string usbUnplugText: "Device must be disconnected from USB to start firmware upgrade. " +
highlightPrefix + "Disconnect {0}" + highlightSuffix + " from usb."
......@@ -88,7 +88,7 @@ QGCView {
onBoardFound: {
if (initialBoardSearch) {
// Board was found right away, so something is already plugged in before we've started upgrade
if (controller.qgcConnections) {
if (QGroundControl.linkManager.anyActiveLinks) {
statusTextArea.append(qgcDisconnectText)
} else {
statusTextArea.append(usbUnplugText.replace('{0}', controller.boardType))
......
......@@ -68,13 +68,17 @@ FirmwareUpgradeController::FirmwareUpgradeController(void) :
connect(_threadController, &PX4FirmwareUpgradeThreadController::flashComplete, this, &FirmwareUpgradeController::_flashComplete);
connect(_threadController, &PX4FirmwareUpgradeThreadController::updateProgress, this, &FirmwareUpgradeController::_updateProgress);
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDisconnected, this, &FirmwareUpgradeController::_linkDisconnected);
connect(&_eraseTimer, &QTimer::timeout, this, &FirmwareUpgradeController::_eraseProgressTick);
}
FirmwareUpgradeController::~FirmwareUpgradeController()
{
qgcApp()->toolbox()->linkManager()->setConnectionsAllowed();
}
void FirmwareUpgradeController::startBoardSearch(void)
{
qgcApp()->toolbox()->linkManager()->setConnectionsSuspended(tr("Connect not allowed during Firmware Upgrade."));
_bootloaderFound = false;
_startFlashWhenBootloaderFound = false;
_threadController->startFindBoardLoop();
......@@ -505,6 +509,7 @@ void FirmwareUpgradeController::_flashComplete(void)
_appendStatusLog("Upgrade complete", true);
_appendStatusLog("------------------------------------------", false);
emit flashComplete();
qgcApp()->toolbox()->linkManager()->setConnectionsAllowed();
}
void FirmwareUpgradeController::_error(const QString& errorString)
......@@ -556,17 +561,6 @@ void FirmwareUpgradeController::_appendStatusLog(const QString& text, bool criti
Q_ARG(QVariant, varText));
}
bool FirmwareUpgradeController::qgcConnections(void)
{
return qgcApp()->toolbox()->linkManager()->anyConnectedLinks();
}
void FirmwareUpgradeController::_linkDisconnected(LinkInterface* link)
{
Q_UNUSED(link);
emit qgcConnectionsChanged(qgcConnections());
}
void FirmwareUpgradeController::_errorCancel(const QString& msg)
{
_appendStatusLog(msg, false);
......@@ -574,6 +568,7 @@ void FirmwareUpgradeController::_errorCancel(const QString& msg)
_appendStatusLog("------------------------------------------", false);
emit error();
cancel();
qgcApp()->toolbox()->linkManager()->setConnectionsAllowed();
}
void FirmwareUpgradeController::_eraseStarted(void)
......
......@@ -104,6 +104,7 @@ public:
};
FirmwareUpgradeController(void);
~FirmwareUpgradeController();
Q_PROPERTY(QString boardPort READ boardPort NOTIFY boardFound)
Q_PROPERTY(QString boardDescription READ boardDescription NOTIFY boardFound)
......@@ -115,9 +116,6 @@ public:
/// Progress bar for you know what
Q_PROPERTY(QQuickItem* progressBar READ progressBar WRITE setProgressBar)
/// Returns true if there are active QGC connections
Q_PROPERTY(bool qgcConnections READ qgcConnections NOTIFY qgcConnectionsChanged)
/// Starts searching for boards on the background thread
Q_INVOKABLE void startBoardSearch(void);
......@@ -140,8 +138,6 @@ public:
QQuickItem* statusLog(void) { return _statusLog; }
void setStatusLog(QQuickItem* statusLog) { _statusLog = statusLog; }
bool qgcConnections(void);
QString boardPort(void) { return _foundBoardInfo.portName(); }
QString boardDescription(void) { return _foundBoardInfo.description(); }
......@@ -151,7 +147,6 @@ signals:
void boardGone(void);
void flashComplete(void);
void flashCancelled(void);
void qgcConnectionsChanged(bool connections);
void error(void);
private slots:
......@@ -170,7 +165,6 @@ private slots:
void _eraseStarted(void);
void _eraseComplete(void);
void _eraseProgressTick(void);
void _linkDisconnected(LinkInterface* link);
private:
void _getFirmwareFile(FirmwareIdentifier firmwareId);
......
......@@ -42,19 +42,20 @@ This file is part of the QGROUNDCONTROL project
#define LINK_SETTING_ROOT "LinkConfigurations"
LinkConfiguration::LinkConfiguration(const QString& name)
: _preferred(false)
: _link(NULL)
, _name(name)
, _dynamic(false)
{
_link = NULL;
_name = name;
Q_ASSERT(!_name.isEmpty());
if (_name.isEmpty()) {
qWarning() << "Internal error";
}
}
LinkConfiguration::LinkConfiguration(LinkConfiguration* copy)
{
_link = copy->getLink();
_link = copy->link();
_name = copy->name();
_preferred = copy->isPreferred();
_dynamic = copy->isDynamic();
Q_ASSERT(!_name.isEmpty());
}
......@@ -62,9 +63,8 @@ LinkConfiguration::LinkConfiguration(LinkConfiguration* copy)
void LinkConfiguration::copyFrom(LinkConfiguration* source)
{
Q_ASSERT(source != NULL);
_link = source->getLink();
_link = source->link();
_name = source->name();
_preferred = source->isPreferred();
_dynamic = source->isDynamic();
}
......@@ -138,3 +138,15 @@ LinkConfiguration* LinkConfiguration::duplicateSettings(LinkConfiguration* sourc
}
return dupe;
}
void LinkConfiguration::setName(const QString name)
{
_name = name;
emit nameChanged(name);
}
void LinkConfiguration::setLink(LinkInterface* link)
{
_link = link;
emit linkChanged(link);
}
......@@ -30,13 +30,26 @@ class LinkInterface;
/// Interface holding link specific settings.
class LinkConfiguration
class LinkConfiguration : public QObject
{
Q_OBJECT
public:
LinkConfiguration(const QString& name);
LinkConfiguration(LinkConfiguration* copy);
virtual ~LinkConfiguration() {}
Q_PROPERTY(QString name READ name WRITE setName NOTIFY nameChanged)
Q_PROPERTY(LinkInterface* link READ link WRITE setLink NOTIFY linkChanged)
// Property accessors
const QString name(void) { return _name; }
LinkInterface* link(void) { return _link; }
void setName(const QString name);
void setLink(LinkInterface* link);
/// The link types supported by QGC
enum {
#ifndef __ios__
......@@ -55,48 +68,6 @@ public:
TypeLast // Last type value (type >= TypeLast == invalid)
};
/*!
* @brief Get configuration name
*
* This is the user friendly name shown in the connection drop down box and the name used to save the configuration in the settings.
* @return The name of this link.
*/
const QString name() { return _name; }
/*!
* @brief Set the name of this link configuration.
*
* This is the user friendly name shown in the connection drop down box and the name used to save the configuration in the settings.
* @param[in] name The configuration name
*/
void setName(const QString name) {_name = name; }
/*!
* @brief Set the link this configuration is currently attched to.
*
* @param[in] link The pointer to the current LinkInterface instance (if any)
*/
void setLink(LinkInterface* link) { _link = link; }
/*!
* @brief Get the link this configuration is currently attched to.
*
* @return The pointer to the current LinkInterface instance (if any)
*/
LinkInterface* getLink() { return _link; }
/*!
*
* Is this a preferred configuration? (decided at runtime)
* @return True if this is a known configuration (PX4, etc.)
*/
bool isPreferred() { return _preferred; }
/*!
* Set if this is this a preferred configuration. (decided at runtime)
*/
void setPreferred(bool preferred = true) { _preferred = preferred; }
/*!
*
* Is this a dynamic configuration? (non persistent)
......@@ -178,11 +149,14 @@ public:
*/
static LinkConfiguration* duplicateSettings(LinkConfiguration *source);
signals:
void nameChanged(const QString& name);
void linkChanged(LinkInterface* link);
protected:
LinkInterface* _link; ///< Link currently using this configuration (if any)
private:
QString _name;
bool _preferred; ///< Determined internally if this is a preferred connection. It comes up first in the drop down box.
bool _dynamic; ///< A connection added automatically and not persistent (unless it's edited).
};
......
......@@ -57,6 +57,15 @@ class LinkInterface : public QThread
friend class LinkManager;
public:
Q_PROPERTY(bool autoconnect READ autoconnect WRITE setAutoconnect NOTIFY autoconnectChanged)
Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged)
// Property accessors
bool autoconnect(void) { return _autoconnect; }
void setAutoconnect(bool autoconnect) { _autoconnect = autoconnect; emit autoconnectChanged(autoconnect); }
bool active(void) { return _active; }
void setActive(bool active) { _active = active; emit activeChanged(active); }
/**
* @brief Get link configuration (if used)
* @return A pointer to the instance of LinkConfiguration if supported. NULL otherwise.
......@@ -128,6 +137,7 @@ public:
/// @return true: "sh /etc/init.d/rc.usb" must be sent on link to start mavlink
virtual bool requiresUSBMavlinkStart(void) const { return false; }
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of
// connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
bool connect(void);
......@@ -148,6 +158,8 @@ public slots:
virtual void writeBytes(const char *bytes, qint64 length) = 0;
signals:
void autoconnectChanged(bool autoconnect);
void activeChanged(bool active);
/**
* @brief New data arrived
......@@ -184,8 +196,10 @@ signals:
protected:
// Links are only created by LinkManager so constructor is not public
LinkInterface() :
QThread(0),
_mavlinkChannelSet(false)
QThread(0)
, _mavlinkChannelSet(false)
, _autoconnect(false)
, _active(false)
{
// Initialize everything for the data rate calculation buffers.
_inDataIndex = 0;
......@@ -321,12 +335,7 @@ private:
**/
virtual bool _connect(void) = 0;
/**
* @brief Disconnect this interface logically
*
* @return True if connection could be terminated, false otherwise
**/
virtual bool _disconnect(void) = 0;
virtual void _disconnect(void) = 0;
/// Sets the mavlink channel to use for this link
void _setMavlinkChannel(uint8_t channel) { Q_ASSERT(!_mavlinkChannelSet); _mavlinkChannelSet = true; _mavlinkChannel = channel; }
......@@ -351,6 +360,9 @@ private:
qint64 _outDataWriteTimes[_dataRateBufferSize]; // in ms
mutable QMutex _dataRateMutex; // Mutex for accessing the data rate member variables
bool _autoconnect; ///< true: Link is an autoconnect connection and should never be disconnected
bool _active; ///< true: link is actively receiving mavlink messages
};
typedef QSharedPointer<LinkInterface> SharedLinkInterface;
......
This diff is collapsed.
This diff is collapsed.
......@@ -102,7 +102,7 @@ LogReplayLink::~LogReplayLink(void)
bool LogReplayLink::_connect(void)
{
// Disallow replay when any links are connected
if (qgcApp()->toolbox()->linkManager()->anyConnectedLinks()) {
if (qgcApp()->toolbox()->linkManager()->anyActiveLinks()) {
emit communicationError(_errorTitle, "You must close all connections prior to replaying a log.");
return false;
}
......@@ -115,7 +115,7 @@ bool LogReplayLink::_connect(void)
return true;
}
bool LogReplayLink::_disconnect(void)
void LogReplayLink::_disconnect(void)
{
if (_connected) {
quit();
......@@ -123,7 +123,6 @@ bool LogReplayLink::_disconnect(void)
_connected = false;
emit disconnected();
}
return true;
}
void LogReplayLink::run(void)
......@@ -366,7 +365,6 @@ void LogReplayLink::_readNextLogEntry(void)
void LogReplayLink::_play(void)
{
// FIXME: With move to link I don't think this is needed any more? Except for the replay widget handling multi-uas?
qgcApp()->toolbox()->linkManager()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay."));
#ifndef __mobile__
qgcApp()->toolbox()->mavlinkProtocol()->suspendLogForReplay(true);
......
......@@ -33,6 +33,8 @@
class LogReplayLinkConfiguration : public LinkConfiguration
{
Q_OBJECT
public:
LogReplayLinkConfiguration(const QString& name);
LogReplayLinkConfiguration(LogReplayLinkConfiguration* copy);
......@@ -130,7 +132,7 @@ private:
// Virtuals from LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
virtual void _disconnect(void);
// Virtuals from QThread
virtual void run(void);
......
......@@ -193,13 +193,6 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected)
Q_ASSERT(link);
if (connected) {
foreach (SharedLinkInterface sharedLink, _connectedLinks) {
Q_ASSERT(sharedLink.data() != link);
}
// Use the same shared pointer as LinkManager
_connectedLinks.append(_linkMgr->sharedPointerForLink(link));
if (link->requiresUSBMavlinkStart()) {
// Send command to start MAVLink
// XXX hacky but safe
......@@ -210,17 +203,6 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected)
link->writeBytes(cmd, strlen(cmd));
link->writeBytes(init, 4);
}
} else {
bool found = false;
for (int i=0; i<_connectedLinks.count(); i++) {
if (_connectedLinks[i].data() == link) {
found = true;
_connectedLinks.removeAt(i);
break;
}
}
Q_UNUSED(found);
Q_ASSERT(found);
}
}
......@@ -236,7 +218,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// Since receiveBytes signals cross threads we can end up with signals in the queue
// that come through after the link is disconnected. For these we just drop the data
// since the link is closed.
if (!_linkMgr->containsLink(link)) {
if (!_linkMgr->links()->contains(link)) {
return;
}
......@@ -300,7 +282,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{
mavlink_message_t msg;
mavlink_msg_ping_pack(getSystemId(), getComponentId(), &msg, ping.time_usec, ping.seq, message.sysid, message.compid);
sendMessage(msg);
_sendMessage(msg);
}
}
......@@ -359,12 +341,9 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
_startLogging();
#endif
// Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed.
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&message, &heartbeat);
if (!_multiVehicleManager->notifyHeartbeatInfo(link, message.sysid, heartbeat)) {
continue;
}
emit vehicleHeartbeatInfo(link, message.sysid, heartbeat.mavlink_version, heartbeat.autopilot, heartbeat.type);
}
// Increase receive counter
......@@ -417,15 +396,13 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// Multiplex message if enabled
if (m_multiplexingEnabled)
{
// Get all links connected to this unit
QList<LinkInterface*> links = _linkMgr->getLinks();
// Emit message on all links that are currently connected
foreach (LinkInterface* currLink, links)
{
for (int i=0; i<_linkMgr->links()->count(); i++) {
LinkInterface* currLink = _linkMgr->links()->value<LinkInterface*>(i);
// Only forward this message to the other links,
// not the link the message was received on
if (currLink != link) sendMessage(currLink, message, message.sysid, message.compid);
if (currLink && currLink != link) _sendMessage(currLink, message, message.sysid, message.compid);
}
}
}
......@@ -460,17 +437,11 @@ int MAVLinkProtocol::getComponentId()
/**
* @param message message to send
*/
void MAVLinkProtocol::sendMessage(mavlink_message_t message)
void MAVLinkProtocol::_sendMessage(mavlink_message_t message)
{
// Get all links connected to this unit
QList<LinkInterface*> links = _linkMgr->getLinks();
// Emit message on all links that are currently connected
QList<LinkInterface*>::iterator i;
for (i = links.begin(); i != links.end(); ++i)
{
sendMessage(*i, message);
// qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
for (int i=0; i<_linkMgr->links()->count(); i++) {
LinkInterface* link = _linkMgr->links()->value<LinkInterface*>(i);
_sendMessage(link, message);
}
}
......@@ -478,7 +449,7 @@ void MAVLinkProtocol::sendMessage(mavlink_message_t message)
* @param link the link to send the message over
* @param message message to send
*/
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message)
void MAVLinkProtocol::_sendMessage(LinkInterface* link, mavlink_message_t message)
{
// Create buffer
static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
......@@ -501,7 +472,7 @@ void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message
* @param systemid id of the system the message is originating from
* @param componentid id of the component the message is originating from
*/
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid)
void MAVLinkProtocol::_sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid)
{
// Create buffer
static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
......@@ -529,7 +500,7 @@ void MAVLinkProtocol::sendHeartbeat()
{
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);
sendMessage(beat);
_sendMessage(beat);
}
if (m_authEnabled)
{
......@@ -538,7 +509,7 @@ void MAVLinkProtocol::sendHeartbeat()
memset(&auth, 0, sizeof(auth));
memcpy(auth.key, m_authKey.toStdString().c_str(), qMin(m_authKey.length(), MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN));
mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
sendMessage(msg);
_sendMessage(msg);
}
}
......
......@@ -158,12 +158,6 @@ public slots:
void linkConnected(void);
void linkDisconnected(void);
/** @brief Send MAVLink message through serial interface */
void sendMessage(mavlink_message_t message);
/** @brief Send MAVLink message */
void sendMessage(LinkInterface* link, mavlink_message_t message);
/** @brief Send MAVLink message with correct system / component ID */
void sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid);
/** @brief Set the rate at which heartbeats are emitted */
void setHeartbeatRate(int rate);
/** @brief Set the system id of this application */
......@@ -238,6 +232,9 @@ protected:
int systemId;
signals:
/// Heartbeat received on link
void vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType);
/** @brief Message received and directly copied via signal */
void messageReceived(LinkInterface* link, mavlink_message_t message);
/** @brief Emitted if heartbeat emission mode is changed */
......@@ -289,6 +286,9 @@ private slots:
private:
void _linkStatusChanged(LinkInterface* link, bool connected);
void _sendMessage(mavlink_message_t message);
void _sendMessage(LinkInterface* link, mavlink_message_t message);
void _sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid);
#ifndef __mobile__
bool _closeLogFile(void);
......@@ -304,11 +304,6 @@ private:
static const char* _logFileExtension; ///< Extension for log files
#endif
/// List of all links connected to protocol. We keep SharedLinkInterface objects
/// which are QSharedPointer's in order to maintain reference counts across threads.
/// This way Link deletion works correctly.
QList<SharedLinkInterface> _connectedLinks;
QTimer _heartbeatTimer; ///< Timer to emit heartbeats
int _heartbeatRate; ///< Heartbeat rate, controls the timer interval
bool _heartbeatsEnabled; ///< Enabled/disable heartbeat emission
......
......@@ -98,6 +98,7 @@ MockLink::MockLink(MockConfiguration* config)
_firmwareType = config->firmwareType();
_vehicleType = config->vehicleType();
_sendStatusText = config->sendStatusText();
_config->setLink(this);
}
union px4_custom_mode px4_cm;
......@@ -136,7 +137,7 @@ bool MockLink::_connect(void)
return true;
}
bool MockLink::_disconnect(void)
void MockLink::_disconnect(void)
{
if (_connected) {
_connected = false;
......@@ -144,8 +145,6 @@ bool MockLink::_disconnect(void)
wait();
emit disconnected();
}
return true;
}
void MockLink::run(void)
......
......@@ -37,6 +37,8 @@ Q_DECLARE_LOGGING_CATEGORY(MockLinkVerboseLog)
class MockConfiguration : public LinkConfiguration
{
Q_OBJECT
public:
MockConfiguration(const QString& name);
MockConfiguration(MockConfiguration* source);
......@@ -146,7 +148,7 @@ private slots:
private:
// From LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
virtual void _disconnect(void);
// QThread override
virtual void run(void);
......
......@@ -84,6 +84,13 @@ QGCSerialPortInfo::BoardType_t QGCSerialPortInfo::boardType(void) const
} else if (description() == "FT231X USB UART") {
qCDebug(QGCSerialPortInfoLog) << "Found possible Radio (by name matching fallback)";
boardType = BoardType3drRadio;
#ifdef __android__
} else if (description().endsWith("USB UART")) {
// This is a fairly broad fallbacks for radios which will also catch most FTDI devices. That would
// cause problems on desktop due to incorrect connections. Since mobile is more anal about connecting
// it will work fine here.
boardType = BoardType3drRadio;
#endif
}
}
......
......@@ -124,7 +124,7 @@ void SerialLink::readBytes()
*
* @return True if connection has been disconnected, false if connection couldn't be disconnected.
**/
bool SerialLink::_disconnect(void)
void SerialLink::_disconnect(void)
{
if (_port) {
_port->close();
......@@ -135,7 +135,6 @@ bool SerialLink::_disconnect(void)
#ifdef __android__
qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(false);
#endif
return true;
}
/**
......
......@@ -59,6 +59,8 @@ Q_DECLARE_LOGGING_CATEGORY(SerialLinkLog)
class SerialConfiguration : public LinkConfiguration
{
Q_OBJECT
public:
SerialConfiguration(const QString& name);
......@@ -158,7 +160,7 @@ private:
// From LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
virtual void _disconnect(void);
// Internal methods
void _emitLinkError(const QString& errorMsg);
......
......@@ -124,18 +124,16 @@ void TCPLink::readBytes()
*
* @return True if connection has been disconnected, false if connection couldn't be disconnected.
**/
bool TCPLink::_disconnect(void)
void TCPLink::_disconnect(void)
{
quit();
wait();
if (_socket)
{
if (_socket) {
_socketIsConnected = false;
_socket->deleteLater(); // Make sure delete happens on correct thread
_socket = NULL;
emit disconnected();
}
return true;
}
/**
......
......@@ -52,6 +52,8 @@ class TCPLinkUnitTest;
class TCPConfiguration : public LinkConfiguration
{
Q_OBJECT
public:
/*!
......@@ -164,7 +166,7 @@ private:
// From LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
virtual void _disconnect(void);
bool _hardwareConnect();
void _restartConnection();
......
......@@ -281,7 +281,7 @@ void UDPLink::readBytes()
*
* @return True if connection has been disconnected, false if connection couldn't be disconnected.
**/
bool UDPLink::_disconnect(void)
void UDPLink::_disconnect(void)
{
_running = false;
quit();
......@@ -293,7 +293,6 @@ bool UDPLink::_disconnect(void)
emit disconnected();
}
_connectState = false;
return true;
}
/**
......
......@@ -52,6 +52,8 @@ This file is part of the QGROUNDCONTROL project
class UDPConfiguration : public LinkConfiguration
{
Q_OBJECT
public:
/*!
......@@ -203,7 +205,7 @@ private:
// From LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
virtual void _disconnect(void);
bool _hardwareConnect();
void _restartConnection();
......
......@@ -158,7 +158,7 @@ bool XbeeLink::_connect(void)
return true;
}
bool XbeeLink::_disconnect(void)
void XbeeLink::_disconnect(void)
{
if(this->isRunning()) this->terminate(); //stop running the thread, restart it upon connect
......@@ -170,7 +170,6 @@ bool XbeeLink::_disconnect(void)
this->m_connected = false;
emit disconnected();
return true;
}
void XbeeLink::writeBytes(const char *bytes, qint64 length) // TO DO: delete the data array
......
......@@ -67,7 +67,7 @@ protected:
private:
// From LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
virtual void _disconnect(void);
bool hardwareConnect();
//void CALLTYPE portCallback(xbee_con *XbeeCon, xbee_pkt *XbeePkt);
......
......@@ -71,30 +71,29 @@ void LinkManagerTest::cleanup(void)
void LinkManagerTest::_add_test(void)
{
Q_ASSERT(_linkMgr);
Q_ASSERT(_linkMgr->getLinks().count() == 0);
Q_ASSERT(_linkMgr->links()->count() == 0);
_connectMockLink();
QList<LinkInterface*> links = _linkMgr->getLinks();
QCOMPARE(links.count(), 1);
QCOMPARE(dynamic_cast<MockLink*>(links[0]), _mockLink);
QCOMPARE(_linkMgr->links()->count(), 1);
QCOMPARE(_linkMgr->links()->value<MockLink*>(0), _mockLink);
}
void LinkManagerTest::_delete_test(void)
{
Q_ASSERT(_linkMgr);
Q_ASSERT(_linkMgr->getLinks().count() == 0);
Q_ASSERT(_linkMgr->links()->count() == 0);
_connectMockLink();
_disconnectMockLink();
QCOMPARE(_linkMgr->getLinks().count(), 0);
QCOMPARE(_linkMgr->links()->count(), 0);
}
void LinkManagerTest::_addSignals_test(void)
{
Q_ASSERT(_linkMgr);
Q_ASSERT(_linkMgr->getLinks().count() == 0);
Q_ASSERT(_linkMgr->links()->count() == 0);
Q_ASSERT(_multiSpy->checkNoSignals() == true);
_connectMockLink();
......@@ -114,7 +113,7 @@ void LinkManagerTest::_addSignals_test(void)
void LinkManagerTest::_deleteSignals_test(void)
{
Q_ASSERT(_linkMgr);
Q_ASSERT(_linkMgr->getLinks().count() == 0);
Q_ASSERT(_linkMgr->links()->count() == 0);
Q_ASSERT(_multiSpy->checkNoSignals() == true);
_connectMockLink();
......
......@@ -387,7 +387,7 @@ void UnitTest::_disconnectMockLink(void)
if (_mockLink) {
QSignalSpy linkSpy(_linkManager, SIGNAL(linkDeleted(LinkInterface*)));
_linkManager->disconnectLink(_mockLink);
_linkManager->disconnectLink(_mockLink, false /* disconnectAutoconnectLink */);
// Wait for link to go away
linkSpy.wait(1000);
......
......@@ -141,12 +141,14 @@ void MAVLinkSettingsWidget::enableDroneOS(bool enable)
QString hostString = m_ui->droneOSComboBox->currentText();
//QString host = hostString.split(":").first();
// Delete from all lists first
LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
UDPLink* firstUdp = NULL;
QList<LinkInterface*> links = qgcApp()->toolbox()->linkManager()->getLinks();
foreach (LinkInterface* link, links)
{
UDPLink* udp = dynamic_cast<UDPLink*>(link);
// Delete from all lists first
for (int i=0; i<linkMgr->links()->count(); i++) {
LinkInterface* link = linkMgr->links()->value<LinkInterface*>(i);
UDPLink* udp = qobject_cast<UDPLink*>(link);
if (udp)
{
if (!firstUdp) firstUdp = udp;
......
......@@ -129,8 +129,7 @@ void MainWindow::deleteInstance(void)
/// by MainWindow::_create method. Hence no other code should have access to
/// constructor.
MainWindow::MainWindow()
: _autoReconnect(false)
, _lowPowerMode(false)
: _lowPowerMode(false)
, _showStatusBar(false)
, _mainQmlWidgetHolder(NULL)
{
......@@ -208,16 +207,6 @@ MainWindow::MainWindow()
connect(this, SIGNAL(x11EventOccured(XEvent*)), mouse, SLOT(handleX11Event(XEvent*)));
#endif //QGC_MOUSE_ENABLED_LINUX
// These also cause the screen to redraw so we need to update any OpenGL canvases in QML controls
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkConnected, this, &MainWindow::_linkStateChange);
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDisconnected, this, &MainWindow::_linkStateChange);
// Connect link
if (_autoReconnect)
{
restoreLastUsedConnection();
}
// Set low power mode
enableLowPowerMode(_lowPowerMode);
emit initStatusChanged(tr("Restoring last view state"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141));
......@@ -445,7 +434,7 @@ void MainWindow::closeEvent(QCloseEvent *event)
QMessageBox::Yes | QMessageBox::Cancel,
QMessageBox::Cancel);
if (button == QMessageBox::Yes) {
qgcApp()->toolbox()->linkManager()->disconnectAll();
qgcApp()->toolbox()->linkManager()->shutdown();
// The above disconnect causes a flurry of activity as the vehicle components are removed. This in turn
// causes the Windows Version of Qt to crash if you allow the close event to be accepted. In order to prevent
// the crash, we ignore the close event and setup a delayed timer to close the window after things settle down.
......@@ -456,11 +445,17 @@ void MainWindow::closeEvent(QCloseEvent *event)
return;
}
// We still need to shutdown LinkManager even though no active connections so that we don't get any
// more auto-connect links during shutdown.
qgcApp()->toolbox()->linkManager()->shutdown();
// This will process any remaining flight log save dialogs
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
// Should not be any active connections
Q_ASSERT(!qgcApp()->toolbox()->linkManager()->anyConnectedLinks());
if (qgcApp()->toolbox()->linkManager()->anyActiveLinks()) {
qWarning() << "All links should be disconnected by now";
}
// We have to pull out the QmlWidget from the main window and delete it here, before
// the MainWindow ends up getting deleted. Otherwise the Qml has a reference to MainWindow
......@@ -494,7 +489,6 @@ void MainWindow::loadSettings()
// Why the screaming?
QSettings settings;
settings.beginGroup(MAIN_SETTINGS_GROUP);
_autoReconnect = settings.value("AUTO_RECONNECT", _autoReconnect).toBool();
_lowPowerMode = settings.value("LOW_POWER_MODE", _lowPowerMode).toBool();
_showStatusBar = settings.value("SHOW_STATUSBAR", _showStatusBar).toBool();
settings.endGroup();
......@@ -504,7 +498,6 @@ void MainWindow::storeSettings()
{
QSettings settings;
settings.beginGroup(MAIN_SETTINGS_GROUP);
settings.setValue("AUTO_RECONNECT", _autoReconnect);
settings.setValue("LOW_POWER_MODE", _lowPowerMode);
settings.setValue("SHOW_STATUSBAR", _showStatusBar);
settings.endGroup();
......@@ -541,11 +534,6 @@ void MainWindow::configureWindowName()
setWindowTitle(windowname);
}
void MainWindow::enableAutoReconnect(bool enabled)
{
_autoReconnect = enabled;
}
/**
* @brief Create all actions associated to the main window
*
......@@ -632,28 +620,6 @@ void MainWindow::saveLastUsedConnection(const QString connection)
settings.setValue(key, connection);
}
/// @brief Restore (and connects) the last used connection (if any)
void MainWindow::restoreLastUsedConnection()
{
// TODO This should check and see of the port/whatever is present
// first. That is, if the last connection was to a PX4 on some serial
// port, it should check and see if the port is present before making
// the connection.
QSettings settings;
QString key(MAIN_SETTINGS_GROUP);
key += "/LAST_CONNECTION";
if(settings.contains(key)) {
QString connection = settings.value(key).toString();
// Create a link for it
qgcApp()->toolbox()->linkManager()->createConnectedLink(connection);
}
}
void MainWindow::_linkStateChange(LinkInterface*)
{
emit repaintCanvas();
}
#ifdef QGC_MOUSE_ENABLED_LINUX
bool MainWindow::x11Event(XEvent *event)
{
......
......@@ -80,12 +80,6 @@ public:
~MainWindow();
/** @brief Get auto link reconnect setting */
bool autoReconnectEnabled() const
{
return _autoReconnect;
}
/** @brief Get low power mode setting */
bool lowPowerModeEnabled() const
{
......@@ -95,18 +89,12 @@ public:
/// @brief Saves the last used connection
void saveLastUsedConnection(const QString connection);
/// @brief Restore (and connects) the last used connection (if any)
void restoreLastUsedConnection();
public slots:
/** @brief Show the application settings */
void showSettings();
void manageLinks();
/** @brief Automatically reconnect last link */
void enableAutoReconnect(bool enabled);
/** @brief Save power by reducing update rates */
void enableLowPowerMode(bool enabled) { _lowPowerMode = enabled; }
......@@ -159,8 +147,6 @@ signals:
void initStatusChanged(const QString& message, int alignment, const QColor &color);
/** Emitted when any value changes from any source */
void valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant& value, const quint64 msec);
/** Emitted when any the Canvas elements within QML wudgets need updating */
void repaintCanvas();
// Used for unit tests to know when the main window closes
void mainWindowClosed(void);
......@@ -213,7 +199,6 @@ protected:
QTimer windowNameUpdateTimer;
private slots:
void _linkStateChange(LinkInterface*);
void _closeWindow(void) { close(); }
void _vehicleAdded(Vehicle* vehicle);
......@@ -254,7 +239,6 @@ private:
void _storeVisibleWidgetsSettings(void);
#endif
bool _autoReconnect;
bool _lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets
bool _showStatusBar;
QVBoxLayout* _centralLayout;
......
......@@ -32,6 +32,8 @@ This file is part of the QGROUNDCONTROL project
#include "ui_QGCLinkConfiguration.h"
#include "QGCCommConfiguration.h"
#include "QGCMessageBox.h"
#include "UDPLink.h"
#include "TCPLink.h"
QGCLinkConfiguration::QGCLinkConfiguration(QWidget *parent) :
QWidget(parent),
......@@ -69,14 +71,17 @@ void QGCLinkConfiguration::on_delLinkButton_clicked()
QMessageBox::Cancel);
if (button == QMessageBox::Yes) {
// Get link attached to this configuration (if any)
LinkInterface* iface = config->getLink();
LinkInterface* iface = config->link();
if(iface) {
// Disconnect it (if connected)
qgcApp()->toolbox()->linkManager()->disconnectLink(iface);
qgcApp()->toolbox()->linkManager()->disconnectLink(iface, false /* disconnectAutoconnectLink */);
}
_viewModel->beginChange();
// Remove configuration
qgcApp()->toolbox()->linkManager()->removeLinkConfiguration(config);
QmlObjectListModel* linkConfigurations = qgcApp()->toolbox()->linkManager()->linkConfigurations();
linkConfigurations->removeOne(config);
delete config;
// Save list
qgcApp()->toolbox()->linkManager()->saveLinkConfigurationList();
_viewModel->endChange();
......@@ -97,11 +102,11 @@ void QGCLinkConfiguration::on_connectLinkButton_clicked()
if(index.row() >= 0) {
LinkConfiguration* config = _viewModel->getConfiguration(index.row());
if(config) {
LinkInterface* link = config->getLink();
LinkInterface* link = config->link();
if(link) {
// Disconnect Link
if (link->isConnected()) {
qgcApp()->toolbox()->linkManager()->disconnectLink(link);
qgcApp()->toolbox()->linkManager()->disconnectLink(link, false /* disconnectAutoconnectLink */);
}
} else {
LinkInterface* link = qgcApp()->toolbox()->linkManager()->createConnectedLink(config);
......@@ -186,7 +191,7 @@ void QGCLinkConfiguration::on_addLinkButton_clicked()
if(config) {
_fixUnnamed(config);
_viewModel->beginChange();
qgcApp()->toolbox()->linkManager()->addLinkConfiguration(commDialog->getConfig());
qgcApp()->toolbox()->linkManager()->linkConfigurations()->append(commDialog->getConfig());
qgcApp()->toolbox()->linkManager()->saveLinkConfigurationList();
_viewModel->endChange();
}
......@@ -240,7 +245,7 @@ void QGCLinkConfiguration::_updateButtons()
if(config->isDynamic()) {
deleteEnabled = false;
}
LinkInterface* link = config->getLink();
LinkInterface* link = config->link();
if(link) {
_ui->connectLinkButton->setText("Disconnect");
} else {
......@@ -261,16 +266,13 @@ LinkViewModel::LinkViewModel(QObject *parent) : QAbstractListModel(parent)
int LinkViewModel::rowCount( const QModelIndex & parent) const
{
Q_UNUSED(parent);
QList<LinkConfiguration*> cfgList = qgcApp()->toolbox()->linkManager()->getLinkConfigurationList();
int count = cfgList.count();
return count;
return qgcApp()->toolbox()->linkManager()->linkConfigurations()->count();
}
QVariant LinkViewModel::data( const QModelIndex & index, int role) const
{
QList<LinkConfiguration*> cfgList = qgcApp()->toolbox()->linkManager()->getLinkConfigurationList();
if (role == Qt::DisplayRole && index.row() < cfgList.count()) {
QString name(cfgList.at(index.row())->name());
if (role == Qt::DisplayRole && index.row() < rowCount()) {
QString name(qgcApp()->toolbox()->linkManager()->linkConfigurations()->value<LinkConfiguration*>(index.row())->name());
return name;
}
return QVariant();
......@@ -278,9 +280,8 @@ QVariant LinkViewModel::data( const QModelIndex & index, int role) const
LinkConfiguration* LinkViewModel::getConfiguration(int row)
{
QList<LinkConfiguration*> cfgList = qgcApp()->toolbox()->linkManager()->getLinkConfigurationList();
if(row < cfgList.count()) {
return cfgList.at(row);
if(row < rowCount()) {
return qgcApp()->toolbox()->linkManager()->linkConfigurations()->value<LinkConfiguration*>(row);
}
return NULL;
}
......
......@@ -490,7 +490,10 @@ void QGCMAVLinkInspector::changeStreamInterval(int msgid, int interval)
mavlink_message_t msg;
mavlink_msg_request_data_stream_encode(_protocol->getSystemId(), _protocol->getComponentId(), &msg, &stream);
#if 0
// FIXME: Is this really used?
_protocol->sendMessage(msg);
#endif
}
void QGCMAVLinkInspector::rateTreeItemChanged(QTreeWidgetItem* paramItem, int column)
......
......@@ -60,7 +60,7 @@ void QGCMAVLinkLogPlayer::_pause(void)
void QGCMAVLinkLogPlayer::_selectLogFileForPlayback(void)
{
// Disallow replay when any links are connected
if (qgcApp()->toolbox()->linkManager()->anyConnectedLinks()) {
if (qgcApp()->toolbox()->linkManager()->anyActiveLinks()) {
QGCMessageBox::information(tr("Log Replay"), tr("You must close all connections prior to replaying a log."));
return;
}
......
......@@ -181,6 +181,34 @@ Rectangle {
}
}
}
//-----------------------------------------------------------------
//-- Autoconnect settings
QGCLabel { text: "Autoconnect to the following devices:" }
QGCCheckBox {
text: "Pixhawk"
checked: QGroundControl.linkManager.autoconnectPixhawk
onClicked: QGroundControl.linkManager.autoconnectPixhawk = checked
}
QGCCheckBox {
text: "3DR Radio"
checked: QGroundControl.linkManager.autoconnect3DRRadio
onClicked: QGroundControl.linkManager.autoconnect3DRRadio = checked
}
QGCCheckBox {
text: "PX4 Flow"
checked: QGroundControl.linkManager.autoconnectPX4Flow
onClicked: QGroundControl.linkManager.autoconnectPX4Flow = checked
}
QGCCheckBox {
text: "UDP"
checked: QGroundControl.linkManager.autoconnectUDP
onClicked: QGroundControl.linkManager.autoconnectUDP = checked
}
}
}
}
......@@ -31,6 +31,7 @@ import QtQuick 2.5
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
......@@ -176,7 +177,7 @@ Rectangle {
}
function showMavStatus() {
return (multiVehicleManager.activeVehicleAvailable && activeVehicle.heartbeatTimeout === 0 && _controller.connectionCount > 0);
return (multiVehicleManager.activeVehicleAvailable && activeVehicle.heartbeatTimeout === 0);
}
Component.onCompleted: {
......@@ -275,7 +276,7 @@ Rectangle {
id: vehicleIndicators
visible: showMavStatus() && !connectionStatus.visible
height: mainWindow.tbCellHeight
width: (toolBar.width - viewRow.width - connectRow.width)
width: (toolBar.width - viewRow.width)
anchors.left: viewRow.right
anchors.leftMargin: mainWindow.tbSpacing * 2
anchors.verticalCenter: parent.verticalCenter
......@@ -347,125 +348,6 @@ Rectangle {
anchors.verticalCenter: parent.verticalCenter
}
Row {
id: connectRow
height: mainWindow.tbCellHeight
spacing: mainWindow.tbSpacing
anchors.rightMargin: mainWindow.tbSpacing
anchors.right: parent.right
anchors.verticalCenter: parent.verticalCenter
Menu {
id: connectMenu
Component.onCompleted: {
_controller.configListChanged.connect(connectMenu.updateConnectionList);
connectMenu.updateConnectionList();
}
function addMenuEntry(name) {
var label = "Add Connection"
if(name !== "")
label = name;
var mItem = connectMenu.addItem(label);
var menuSlot = function() {_controller.onConnect(name)};
mItem.triggered.connect(menuSlot);
}
function updateConnectionList() {
connectMenu.clear();
for(var i = 0; i < _controller.configList.length; i++) {
connectMenu.addMenuEntry(_controller.configList[i]);
}
if(_controller.configList.length > 0) {
connectMenu.addSeparator();
}
// Add "Add Connection" to the list
connectMenu.addMenuEntry("");
}
}
Rectangle {
height: mainWindow.tbCellHeight
width: 1
color: Qt.rgba(1,1,1,0.45)
}
QGCToolBarButton {
id: connectButton
width: mainWindow.tbButtonWidth
height: mainWindow.tbCellHeight
visible: _controller.connectionCount === 0
source: "/qmlimages/Connect.svg"
checked: false
onClicked: {
checked = false
connectMenu.popup()
/*
console.log("Main Window Width: " + mainWindow.width)
console.log("Toolbar height: " + toolBar.height)
console.log("Default font: " + ScreenTools.defaultFontPixelSize)
console.log("Font (.75): " + ScreenTools.defaultFontPixelSize * 0.75)
console.log("Font (.85): " + ScreenTools.defaultFontPixelSize * 0.85)
console.log("Font 1.5): " + ScreenTools.defaultFontPixelSize * 1.5)
console.log("Default Font Width: " + ScreenTools.defaultFontPixelWidth)
console.log("Default Font Height: " + ScreenTools.defaultFontPixelHeight)
console.log("--")
console.log("Real Font Height: " + ScreenTools.realFontHeight)
console.log("fontHRatio: " + ScreenTools.fontHRatio)
console.log("--")
console.log("cellHeight: " + cellHeight)
console.log("tbFontSmall: " + tbFontSmall);
console.log("tbFontNormal: " + tbFontNormal);
console.log("tbFontLarge: " + tbFontLarge);
console.log("mainWindow.tbSpacing: " + tbSpacing);
*/
}
}
QGCToolBarButton {
id: disconnectButton
width: mainWindow.tbButtonWidth
height: mainWindow.tbCellHeight
visible: _controller.connectionCount === 1
source: "/qmlimages/Disconnect.svg"
checked: false
onClicked: {
checked = false
_controller.onDisconnect("");
}
}
Menu {
id: disconnectMenu
Component.onCompleted: {
_controller.connectedListChanged.connect(disconnectMenu.onConnectedListChanged)
}
function addMenuEntry(name) {
var mItem = disconnectMenu.addItem(name);
var menuSlot = function() {_controller.onDisconnect(name)};
mItem.triggered.connect(menuSlot);
}
function onConnectedListChanged(conList) {
disconnectMenu.clear();
for(var i = 0; i < conList.length; i++) {
disconnectMenu.addMenuEntry(conList[i]);
}
}
}
QGCToolBarButton {
id: multidisconnectButton
width: mainWindow.tbButtonWidth
height: mainWindow.tbCellHeight
visible: _controller.connectionCount > 1
source: "/qmlimages/Disconnect.svg"
checked: false
onClicked: {
checked = false
disconnectMenu.popup()
}
}
}
// Progress bar
Rectangle {
id: progressBar
......
......@@ -43,23 +43,13 @@ MainToolBarController::MainToolBarController(QObject* parent)
: QObject(parent)
, _vehicle(NULL)
, _mav(NULL)
, _connectionCount(0)
, _progressBarValue(0.0f)
, _remoteRSSI(0)
, _remoteRSSIstore(100.0)
, _telemetryRRSSI(0)
, _telemetryLRSSI(0)
, _toolbarMessageVisible(false)
{
emit configListChanged();
emit connectionCountChanged(_connectionCount);
_activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle());
// Link signals
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkConfigurationChanged, this, &MainToolBarController::_updateConfigurations);
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkConnected, this, &MainToolBarController::_linkConnected);
connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDisconnected, this, &MainToolBarController::_linkDisconnected);
// RSSI (didn't like standard connection)
connect(qgcApp()->toolbox()->mavlinkProtocol(),
SIGNAL(radioStatusChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned)), this,
......@@ -88,59 +78,10 @@ void MainToolBarController::onFlyView()
MainWindow::instance()->showFlyView();
}
void MainToolBarController::onDisconnect(QString conf)
{
if(conf.isEmpty()) {
// Disconnect Only Connected Link
int connectedCount = 0;
LinkInterface* connectedLink = NULL;
QList<LinkInterface*> links = qgcApp()->toolbox()->linkManager()->getLinks();
foreach(LinkInterface* link, links) {
if (link->isConnected()) {
connectedCount++;
connectedLink = link;
}
}
Q_ASSERT(connectedCount == 1);
Q_ASSERT(_connectionCount == 1);
Q_ASSERT(connectedLink);
qgcApp()->toolbox()->linkManager()->disconnectLink(connectedLink);
} else {
// Disconnect Named Connected Link
QList<LinkInterface*> links = qgcApp()->toolbox()->linkManager()->getLinks();
foreach(LinkInterface* link, links) {
if (link->isConnected()) {
if(link->getLinkConfiguration() && link->getLinkConfiguration()->name() == conf) {
qgcApp()->toolbox()->linkManager()->disconnectLink(link);
}
}
}
}
}
void MainToolBarController::onConnect(QString conf)
{
// Connect Link
if(conf.isEmpty()) {
MainWindow::instance()->manageLinks();
} else {
// We don't want the list updating under our feet
qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(true);
// Create a link
LinkInterface* link = qgcApp()->toolbox()->linkManager()->createConnectedLink(conf);
if(link) {
// Save last used connection
MainWindow::instance()->saveLastUsedConnection(conf);
}
qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(false);
}
}
void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle)
{
// Disconnect the previous one (if any)
if (_vehicle) {
disconnect(_mav, &UASInterface::remoteControlRSSIChanged, this, &MainToolBarController::_remoteControlRSSIChanged);
disconnect(_vehicle->autopilotPlugin(), &AutoPilotPlugin::parameterListProgress, this, &MainToolBarController::_setProgressBarValue);
_mav = NULL;
_vehicle = NULL;
......@@ -151,35 +92,12 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle)
{
_vehicle = vehicle;
_mav = vehicle->uas();
connect(_mav, &UASInterface::remoteControlRSSIChanged, this, &MainToolBarController::_remoteControlRSSIChanged);
connect(_vehicle->autopilotPlugin(), &AutoPilotPlugin::parameterListProgress, this, &MainToolBarController::_setProgressBarValue);
}
}
void MainToolBarController::_updateConfigurations()
{
QStringList tmpList;
QList<LinkConfiguration*> configs = qgcApp()->toolbox()->linkManager()->getLinkConfigurationList();
foreach(LinkConfiguration* conf, configs) {
if(conf) {
if(conf->isPreferred()) {
tmpList.insert(0,conf->name());
} else {
tmpList << conf->name();
}
}
}
// Any changes?
if(tmpList != _linkConfigurations) {
_linkConfigurations = tmpList;
emit configListChanged();
}
}
void MainToolBarController::_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned rssi, unsigned remrssi, unsigned, unsigned, unsigned)
{
// We only care if we haveone single connection
if(_connectionCount == 1) {
if((unsigned)_telemetryLRSSI != rssi) {
// According to the Silabs data sheet, the RSSI value is 0.5db per bit
_telemetryLRSSI = rssi >> 1;
......@@ -190,71 +108,6 @@ void MainToolBarController::_telemetryChanged(LinkInterface*, unsigned, unsigned
_telemetryRRSSI = remrssi >> 1;
emit telemetryRRSSIChanged(_telemetryRRSSI);
}
}
}
void MainToolBarController::_remoteControlRSSIChanged(uint8_t rssi)
{
// We only care if we have one single connection
if(_connectionCount == 1) {
// Low pass to git rid of jitter
_remoteRSSIstore = (_remoteRSSIstore * 0.9f) + ((float)rssi * 0.1);
uint8_t filteredRSSI = (uint8_t)ceil(_remoteRSSIstore);
if(_remoteRSSIstore < 0.1) {
filteredRSSI = 0;
}
if(_remoteRSSI != filteredRSSI) {
_remoteRSSI = filteredRSSI;
emit remoteRSSIChanged(_remoteRSSI);
}
}
}
void MainToolBarController::_linkConnected(LinkInterface*)
{
_updateConnection();
}
void MainToolBarController::_linkDisconnected(LinkInterface* link)
{
_updateConnection(link);
}
void MainToolBarController::_updateConnection(LinkInterface *disconnectedLink)
{
QStringList connList;
int oldCount = _connectionCount;
// If there are multiple connected links add/update the connect button menu
_connectionCount = 0;
QList<LinkInterface*> links = qgcApp()->toolbox()->linkManager()->getLinks();
foreach(LinkInterface* link, links) {
if (disconnectedLink != link && link->isConnected()) {
_connectionCount++;
if(link->getLinkConfiguration()) {
connList << link->getLinkConfiguration()->name();
}
}
}
if(oldCount != _connectionCount) {
emit connectionCountChanged(_connectionCount);
}
if(connList != _connectedList) {
_connectedList = connList;
emit connectedListChanged(_connectedList);
}
// Update telemetry RSSI display
if(_connectionCount != 1 && _telemetryRRSSI > 0) {
_telemetryRRSSI = 0;
emit telemetryRRSSIChanged(_telemetryRRSSI);
}
if(_connectionCount != 1 && _telemetryLRSSI > 0) {
_telemetryLRSSI = 0;
emit telemetryLRSSIChanged(_telemetryLRSSI);
}
if(_connectionCount != 1 && _remoteRSSI > 0) {
_remoteRSSI = 0;
emit remoteRSSIChanged(_remoteRSSI);
}
}
void MainToolBarController::_setProgressBarValue(float value)
......@@ -307,3 +160,8 @@ void MainToolBarController::showSettings(void)
{
MainWindow::instance()->showSettings();
}
void MainToolBarController::manageLinks(void)
{
MainWindow::instance()->manageLinks();
}
......@@ -53,34 +53,23 @@ public:
Q_INVOKABLE void onSetupView();
Q_INVOKABLE void onPlanView();
Q_INVOKABLE void onFlyView();
Q_INVOKABLE void onConnect(QString conf);
Q_INVOKABLE void onDisconnect(QString conf);
Q_INVOKABLE void onToolBarMessageClosed(void);
Q_INVOKABLE void showSettings(void);
Q_INVOKABLE void manageLinks(void);
Q_PROPERTY(double height MEMBER _toolbarHeight NOTIFY heightChanged)
Q_PROPERTY(QStringList configList MEMBER _linkConfigurations NOTIFY configListChanged)
Q_PROPERTY(int connectionCount READ connectionCount NOTIFY connectionCountChanged)
Q_PROPERTY(QStringList connectedList MEMBER _connectedList NOTIFY connectedListChanged)
Q_PROPERTY(float progressBarValue MEMBER _progressBarValue NOTIFY progressBarValueChanged)
Q_PROPERTY(int remoteRSSI READ remoteRSSI NOTIFY remoteRSSIChanged)
Q_PROPERTY(int telemetryRRSSI READ telemetryRRSSI NOTIFY telemetryRRSSIChanged)
Q_PROPERTY(int telemetryLRSSI READ telemetryLRSSI NOTIFY telemetryLRSSIChanged)
void viewStateChanged (const QString& key, bool value);
int remoteRSSI () { return _remoteRSSI; }
int telemetryRRSSI () { return _telemetryRRSSI; }
int telemetryLRSSI () { return _telemetryLRSSI; }
int connectionCount () { return _connectionCount; }
void showToolBarMessage(const QString& message);
signals:
void connectionCountChanged (int count);
void configListChanged ();
void connectedListChanged (QStringList connectedList);
void progressBarValueChanged (float value);
void remoteRSSIChanged (int value);
void telemetryRRSSIChanged (int value);
void telemetryLRSSIChanged (int value);
void heightChanged (double height);
......@@ -90,25 +79,14 @@ signals:
private slots:
void _activeVehicleChanged (Vehicle* vehicle);
void _updateConfigurations ();
void _linkConnected (LinkInterface* link);
void _linkDisconnected (LinkInterface* link);
void _setProgressBarValue (float value);
void _remoteControlRSSIChanged (uint8_t rssi);
void _telemetryChanged (LinkInterface* link, unsigned rxerrors, unsigned fixed, unsigned rssi, unsigned remrssi, unsigned txbuf, unsigned noise, unsigned remnoise);
void _delayedShowToolBarMessage (void);
private:
void _updateConnection (LinkInterface *disconnectedLink = NULL);
private:
Vehicle* _vehicle;
UASInterface* _mav;
QStringList _linkConfigurations;
int _connectionCount;
QStringList _connectedList;
float _progressBarValue;
int _remoteRSSI;
double _remoteRSSIstore;
int _telemetryRRSSI;
int _telemetryLRSSI;
......
......@@ -218,12 +218,12 @@ Row {
smooth: true
width: mainWindow.tbCellHeight * 0.65
height: mainWindow.tbCellHeight * 0.5
opacity: _controller.remoteRSSI < 1 ? 0.5 : 1
opacity: activeVehicle.rcRSSI < 1 ? 0.5 : 1
anchors.verticalCenter: parent.verticalCenter
}
SignalStrength {
size: mainWindow.tbCellHeight * 0.5
percent: _controller.remoteRSSI
percent: activeVehicle.rcRSSI
anchors.verticalCenter: parent.verticalCenter
}
}
......@@ -283,10 +283,11 @@ Row {
//-------------------------------------------------------------------------
//-- Vehicle Selector
QGCButton {
id: vehicleSelectorButton
width: ScreenTools.defaultFontPixelSize * 12
height: mainWindow.tbButtonWidth
text: "Vehicle " + activeVehicle.id
visible: vehicleMenuItems.length > 0
visible: QGroundControl.multiVehicleManager.vehicles.count > 1
anchors.verticalCenter: parent.verticalCenter
menu: vehicleMenu
......@@ -330,7 +331,7 @@ Row {
Connections {
target: multiVehicleManager.vehicles
onCountChanged: parent.updateVehicleMenu
onCountChanged: vehicleSelectorButton.updateVehicleMenu
}
}
......
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