diff --git a/src/AirLink/AirlinkLink.cc b/src/AirLink/AirlinkLink.cc index 706fe98106f..aefc1c11470 100644 --- a/src/AirLink/AirlinkLink.cc +++ b/src/AirLink/AirlinkLink.cc @@ -149,7 +149,7 @@ void AirlinkLink::_configureUdpSettings() QUdpSocket udpSocket; while (!udpSocket.bind(QHostAddress::LocalHost, availablePort)) availablePort++; - UDPConfiguration* udpConfig = dynamic_cast(UDPLink::_config.get()); + UDPConfiguration* udpConfig = dynamic_cast(UDPLink::m_config.get()); udpConfig->addHost(AirLinkManager::airlinkHost, AirLinkManager::airlinkPort); udpConfig->setLocalPort(availablePort); udpConfig->setDynamic(false); @@ -160,7 +160,7 @@ void AirlinkLink::_sendLoginMsgToAirLink() __mavlink_airlink_auth_t auth; uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; mavlink_message_t mavmsg; - AirlinkConfiguration* config = dynamic_cast(_config.get()); + AirlinkConfiguration* config = dynamic_cast(m_config.get()); QString login = config->modemName(); ///< Connect not to account but to specific modem QString pass = config->password(); diff --git a/src/Comms/BluetoothLink.cc b/src/Comms/BluetoothLink.cc index 58ef8f8c79c..e2436da9b40 100644 --- a/src/Comms/BluetoothLink.cc +++ b/src/Comms/BluetoothLink.cc @@ -45,7 +45,7 @@ void BluetoothLink::run() } -void BluetoothLink::_writeBytes(const QByteArray bytes) +void BluetoothLink::_writeBytes(const QByteArray &bytes) { if (_targetSocket) { if(_targetSocket->write(bytes) > 0) { diff --git a/src/Comms/BluetoothLink.h b/src/Comms/BluetoothLink.h index 81ed7ebaf7b..30f166c22f9 100644 --- a/src/Comms/BluetoothLink.h +++ b/src/Comms/BluetoothLink.h @@ -137,7 +137,7 @@ public slots: private slots: // LinkInterface overrides - void _writeBytes(const QByteArray bytes) override; + void _writeBytes(const QByteArray &bytes) override; private: diff --git a/src/Comms/LinkConfiguration.cc b/src/Comms/LinkConfiguration.cc index a060b26fcb2..d0724a13c9f 100644 --- a/src/Comms/LinkConfiguration.cc +++ b/src/Comms/LinkConfiguration.cc @@ -24,138 +24,164 @@ #include "AirlinkLink.h" #endif -#define LINK_SETTING_ROOT "LinkConfigurations" - -LinkConfiguration::LinkConfiguration(const QString& name) - : _name (name) - , _dynamic (false) - , _autoConnect (false) - , _highLatency (false) +LinkConfiguration::LinkConfiguration(const QString &name, QObject *parent) + : QObject(parent) + , m_name(name) { - + // qCDebug(AudioOutputLog) << Q_FUNC_INFO << this; } -LinkConfiguration::LinkConfiguration(LinkConfiguration* copy) +LinkConfiguration::LinkConfiguration(LinkConfiguration *copy, QObject *parent) + : QObject(parent) + , m_link(copy->m_link) + , m_name(copy->name()) + , m_dynamic(copy->isDynamic()) + , m_autoConnect(copy->isAutoConnect()) + , m_highLatency(copy->isHighLatency()) { - _link = copy->_link; - _name = copy->name(); - _dynamic = copy->isDynamic(); - _autoConnect= copy->isAutoConnect(); - _highLatency= copy->isHighLatency(); - Q_ASSERT(!_name.isEmpty()); + // qCDebug(AudioOutputLog) << Q_FUNC_INFO << this; + + LinkConfiguration::copyFrom(copy); + + Q_ASSERT(!m_name.isEmpty()); } -void LinkConfiguration::copyFrom(LinkConfiguration* source) +LinkConfiguration::~LinkConfiguration() { - Q_ASSERT(source != nullptr); - _link = source->_link; - _name = source->name(); - _dynamic = source->isDynamic(); - _autoConnect= source->isAutoConnect(); - _highLatency= source->isHighLatency(); + // qCDebug(AudioOutputLog) << Q_FUNC_INFO << this; } -/*! - Where the settings are saved - @return The root path of the setting. -*/ -const QString LinkConfiguration::settingsRoot() +void LinkConfiguration::copyFrom(LinkConfiguration *source) { - return QString(LINK_SETTING_ROOT); + Q_CHECK_PTR(source); + + m_link = source->m_link; + m_name = source->name(); + m_dynamic = source->isDynamic(); + m_autoConnect = source->isAutoConnect(); + m_highLatency = source->isHighLatency(); } -/*! - Configuration Factory - @return A new instance of the given type -*/ -LinkConfiguration* LinkConfiguration::createSettings(int type, const QString& name) +LinkConfiguration *LinkConfiguration::createSettings(int type, const QString &name) { - LinkConfiguration* config = nullptr; - switch(type) { + LinkConfiguration *config = nullptr; + + switch(static_cast(type)) { #ifndef NO_SERIAL_LINK - case LinkConfiguration::TypeSerial: - config = new SerialConfiguration(name); - break; + case TypeSerial: + config = new SerialConfiguration(name); + break; #endif - case LinkConfiguration::TypeUdp: - config = new UDPConfiguration(name); - break; - case LinkConfiguration::TypeTcp: - config = new TCPConfiguration(name); - break; + case TypeUdp: + config = new UDPConfiguration(name); + break; + case TypeTcp: + config = new TCPConfiguration(name); + break; #ifdef QGC_ENABLE_BLUETOOTH - case LinkConfiguration::TypeBluetooth: + case TypeBluetooth: config = new BluetoothConfiguration(name); break; #endif - case LinkConfiguration::TypeLogReplay: - config = new LogReplayLinkConfiguration(name); - break; + case TypeLogReplay: + config = new LogReplayLinkConfiguration(name); + break; #ifdef QT_DEBUG - case LinkConfiguration::TypeMock: - config = new MockConfiguration(name); - break; + case TypeMock: + config = new MockConfiguration(name); + break; #endif #ifndef QGC_AIRLINK_DISABLED - case LinkConfiguration::Airlink: - config = new AirlinkConfiguration(name); - break; + case Airlink: + config = new AirlinkConfiguration(name); + break; #endif + case TypeLast: + default: + break; } + return config; } -/*! - Duplicate link settings - @return A new copy of the given settings instance -*/ -LinkConfiguration* LinkConfiguration::duplicateSettings(LinkConfiguration* source) +LinkConfiguration *LinkConfiguration::duplicateSettings(LinkConfiguration *source) { - LinkConfiguration* dupe = nullptr; + LinkConfiguration *dupe = nullptr; + switch(source->type()) { #ifndef NO_SERIAL_LINK - case TypeSerial: - dupe = new SerialConfiguration(qobject_cast(source)); - break; + case TypeSerial: + dupe = new SerialConfiguration(qobject_cast(source)); + break; #endif - case TypeUdp: - dupe = new UDPConfiguration(qobject_cast(source)); - break; - case TypeTcp: - dupe = new TCPConfiguration(qobject_cast(source)); - break; + case TypeUdp: + dupe = new UDPConfiguration(qobject_cast(source)); + break; + case TypeTcp: + dupe = new TCPConfiguration(qobject_cast(source)); + break; #ifdef QGC_ENABLE_BLUETOOTH - case TypeBluetooth: - dupe = new BluetoothConfiguration(qobject_cast(source)); - break; + case TypeBluetooth: + dupe = new BluetoothConfiguration(qobject_cast(source)); + break; #endif - case TypeLogReplay: - dupe = new LogReplayLinkConfiguration(qobject_cast(source)); - break; + case TypeLogReplay: + dupe = new LogReplayLinkConfiguration(qobject_cast(source)); + break; #ifdef QT_DEBUG - case TypeMock: - dupe = new MockConfiguration(qobject_cast(source)); - break; + case TypeMock: + dupe = new MockConfiguration(qobject_cast(source)); + break; #endif #ifndef QGC_AIRLINK_DISABLED - case Airlink: - dupe = new AirlinkConfiguration(qobject_cast(source)); - break; + case Airlink: + dupe = new AirlinkConfiguration(qobject_cast(source)); + break; #endif - case TypeLast: - break; + case TypeLast: + default: + break; } + return dupe; } -void LinkConfiguration::setName(const QString name) +void LinkConfiguration::setName(const QString &name) { - _name = name; - emit nameChanged(name); + if (name != m_name) { + m_name = name; + emit nameChanged(name); + } } void LinkConfiguration::setLink(SharedLinkInterfacePtr link) { - _link = link; - emit linkChanged(); + if (link.get() != this->link()) { + m_link = link; + emit linkChanged(); + } +} + +void LinkConfiguration::setDynamic(bool dynamic) +{ + if (dynamic != m_dynamic) { + m_dynamic = dynamic; + emit dynamicChanged(); + } +} + +void LinkConfiguration::setAutoConnect(bool autoc) +{ + if (autoc != m_autoConnect) { + m_autoConnect = autoc; + emit autoConnectChanged(); + } +} + +void LinkConfiguration::setHighLatency(bool hl) +{ + if (hl != m_highLatency) { + m_highLatency = hl; + emit highLatencyChanged(); + } } diff --git a/src/Comms/LinkConfiguration.h b/src/Comms/LinkConfiguration.h index 99203f44c18..039b70ece3c 100644 --- a/src/Comms/LinkConfiguration.h +++ b/src/Comms/LinkConfiguration.h @@ -20,30 +20,52 @@ class LinkConfiguration : public QObject Q_OBJECT Q_MOC_INCLUDE("LinkInterface.h") + Q_PROPERTY(QString name READ name WRITE setName NOTIFY nameChanged) + Q_PROPERTY(LinkInterface* link READ link NOTIFY linkChanged) + Q_PROPERTY(LinkType linkType READ type CONSTANT) + Q_PROPERTY(bool dynamic READ isDynamic WRITE setDynamic NOTIFY dynamicChanged) + Q_PROPERTY(bool autoConnect READ isAutoConnect WRITE setAutoConnect NOTIFY autoConnectChanged) + Q_PROPERTY(QString settingsURL READ settingsURL CONSTANT) + Q_PROPERTY(QString settingsTitle READ settingsTitle CONSTANT) + Q_PROPERTY(bool highLatency READ isHighLatency WRITE setHighLatency NOTIFY highLatencyChanged) + public: - LinkConfiguration(const QString& name); - LinkConfiguration(LinkConfiguration* copy); - virtual ~LinkConfiguration() {} + LinkConfiguration(const QString &name, QObject *parent = nullptr); + LinkConfiguration(LinkConfiguration *copy, QObject *parent = nullptr); + virtual ~LinkConfiguration(); + + QString name() const { return m_name; } + void setName(const QString &name); + + LinkInterface *link() { return m_link.lock().get(); } + void setLink(std::shared_ptr link); + + /// Is this a dynamic configuration? + /// @return True if not persisted + bool isDynamic() const { return m_dynamic; } - Q_PROPERTY(QString name READ name WRITE setName NOTIFY nameChanged) - Q_PROPERTY(LinkInterface* link READ link NOTIFY linkChanged) - Q_PROPERTY(LinkType linkType READ type CONSTANT) - Q_PROPERTY(bool dynamic READ isDynamic WRITE setDynamic NOTIFY dynamicChanged) - Q_PROPERTY(bool autoConnect READ isAutoConnect WRITE setAutoConnect NOTIFY autoConnectChanged) - Q_PROPERTY(QString settingsURL READ settingsURL CONSTANT) - Q_PROPERTY(QString settingsTitle READ settingsTitle CONSTANT) - Q_PROPERTY(bool highLatency READ isHighLatency WRITE setHighLatency NOTIFY highLatencyChanged) + /// Set if this is this a dynamic configuration. (decided at runtime) + void setDynamic(bool dynamic = true); - // Property accessors + bool isAutoConnect() const { return m_autoConnect; } - QString name(void) const { return _name; } - LinkInterface* link(void) { return _link.lock().get(); } + /// Set if this is this an Auto Connect configuration. + void setAutoConnect(bool autoc = true); - void setName(const QString name); - void setLink(std::shared_ptr link); + /// Is this a High Latency configuration? + /// @return True if this is an High Latency configuration (link with large delays). + bool isHighLatency() const{ return m_highLatency; } - /// The link types supported by QGC - /// Any changes here MUST be reflected in LinkManager::linkTypeStrings() + /// Set if this is this an High Latency configuration. + void setHighLatency(bool hl = false); + + /// Copy instance data, When manipulating data, you create a copy of the configuration using the copy constructor, + /// edit it and then transfer its content to the original using this method. + /// @param[in] source The source instance (the edited copy) + virtual void copyFrom(LinkConfiguration *source); + + /// The link types supported by QGC + /// Any changes here MUST be reflected in LinkManager::linkTypeStrings() enum LinkType { #ifndef NO_SERIAL_LINK TypeSerial, ///< Serial Link @@ -64,124 +86,54 @@ class LinkConfiguration : public QObject }; Q_ENUM(LinkType) - bool isDynamic () const{ return _dynamic; } ///< Not persisted - bool isAutoConnect () const{ return _autoConnect; } - - /*! - * - * Is this a High Latency configuration? - * @return True if this is an High Latency configuration (link with large delays). - */ - bool isHighLatency() const{ return _highLatency; } - - /*! - * Set if this is this a dynamic configuration. (decided at runtime) - */ - void setDynamic(bool dynamic = true) { _dynamic = dynamic; emit dynamicChanged(); } - - /*! - * Set if this is this an Auto Connect configuration. - */ - void setAutoConnect(bool autoc = true) { _autoConnect = autoc; emit autoConnectChanged(); } - - /*! - * Set if this is this an High Latency configuration. - */ - void setHighLatency(bool hl = false) { _highLatency = hl; emit highLatencyChanged(); } - - /// Virtual Methods - - /*! - * @brief Connection type - * - * Pure virtual method returning one of the -TypeXxx types above. - * @return The type of links these settings belong to. - */ + /// Connection type, pure virtual method returning one of the -TypeXxx types above. + /// @return The type of links these settings belong to. virtual LinkType type() = 0; - /*! - * @brief Load settings - * - * Pure virtual method telling the instance to load its configuration. - * @param[in] settings The QSettings instance to use - * @param[in] root The root path of the setting. - */ - virtual void loadSettings(QSettings& settings, const QString& root) = 0; - - /*! - * @brief Save settings - * - * Pure virtual method telling the instance to save its configuration. - * @param[in] settings The QSettings instance to use - * @param[in] root The root path of the setting. - */ - virtual void saveSettings(QSettings& settings, const QString& root) = 0; - - /*! - * @brief Settings URL - * - * Pure virtual method providing the URL for the (QML) settings dialog - */ - virtual QString settingsURL () = 0; - - /*! - * @brief Settings Title - * - * Pure virtual method providing the Title for the (QML) settings dialog - */ - virtual QString settingsTitle () = 0; - - /*! - * @brief Copy instance data - * - * When manipulating data, you create a copy of the configuration using the copy constructor, - * edit it and then transfer its content to the original using this method. - * @param[in] source The source instance (the edited copy) - */ - virtual void copyFrom(LinkConfiguration* source); - - /// Helper static methods - - /*! - * @brief Root path for QSettings - * - * @return The root path of the settings. - */ - static const QString settingsRoot(); - - /*! - * @brief Create new link configuration instance - * - * Configuration Factory. Creates an appropriate configuration instance based on the given type. - * @return A new instance of the given type - */ - static LinkConfiguration* createSettings(int type, const QString& name); - - /*! - * @brief Duplicate configuration instance - * - * Helper method to create a new instance copy for editing. - * @return A new copy of the given settings instance - */ - static LinkConfiguration* duplicateSettings(LinkConfiguration *source); + /// Load settings, Pure virtual method telling the instance to load its configuration. + /// @param[in] settings The QSettings instance to use + /// @param[in] root The root path of the setting. + virtual void loadSettings(QSettings &settings, const QString &root) = 0; + + /// Save settings, Pure virtual method telling the instance to save its configuration. + /// @param[in] settings The QSettings instance to use + /// @param[in] root The root path of the setting. + virtual void saveSettings(QSettings &settings, const QString &root) = 0; + + /// Settings URL, Pure virtual method providing the URL for the (QML) settings dialog + virtual QString settingsURL() = 0; + + /// Settings Title, Pure virtual method providing the Title for the (QML) settings dialog + virtual QString settingsTitle() = 0; + + /// Configuration Factory to create new link configuration instance based on the given type. + /// @return A new instance of the given type + static LinkConfiguration *createSettings(int type, const QString &name); + + /// Duplicate configuration instance. Helper method to create a new instance copy for editing. + /// @return A new copy of the given settings instance + static LinkConfiguration *duplicateSettings(LinkConfiguration *source); + + /// Root path for QSettings + /// @return The root path of the settings. + static QString settingsRoot() { return QStringLiteral("LinkConfigurations"); } signals: - void nameChanged (const QString& name); - void dynamicChanged (); - void autoConnectChanged (); - void highLatencyChanged (); - void linkChanged (); + void nameChanged(const QString &name); + void linkChanged(); + void dynamicChanged(); + void autoConnectChanged(); + void highLatencyChanged(); protected: - std::weak_ptr _link; ///< Link currently using this configuration (if any) + std::weak_ptr m_link; ///< Link currently using this configuration (if any) private: - QString _name; - bool _dynamic; ///< A connection added automatically and not persistent (unless it's edited). - bool _autoConnect; ///< This connection is started automatically at boot - bool _highLatency; + QString m_name; + bool m_dynamic = false; ///< A connection added automatically and not persistent (unless it's edited). + bool m_autoConnect = false; ///< This connection is started automatically at boot + bool m_highLatency = false; }; -typedef std::shared_ptr SharedLinkConfigurationPtr; -typedef std::weak_ptr WeakLinkConfigurationPtr; - +typedef std::shared_ptr SharedLinkConfigurationPtr; +typedef std::weak_ptr WeakLinkConfigurationPtr; diff --git a/src/Comms/LinkInterface.cc b/src/Comms/LinkInterface.cc index 999b2df7cf9..6c76754c599 100644 --- a/src/Comms/LinkInterface.cc +++ b/src/Comms/LinkInterface.cc @@ -16,109 +16,91 @@ QGC_LOGGING_CATEGORY(LinkInterfaceLog, "LinkInterfaceLog") -// The LinkManager is only forward declared in the header, so the static_assert is here instead. -static_assert(LinkManager::invalidMavlinkChannel() == std::numeric_limits::max(), "update LinkInterface::_mavlinkChannel"); - -LinkInterface::LinkInterface(SharedLinkConfigurationPtr& config, bool isPX4Flow) - : QThread (0) - , _config (config) - , _isPX4Flow(isPX4Flow) +LinkInterface::LinkInterface(SharedLinkConfigurationPtr &config, bool isPX4Flow, QObject *parent) + : QThread(parent) + , m_config(config) + , m_isPX4Flow(isPX4Flow) { QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); - qRegisterMetaType("LinkInterface*"); - - // This will cause the writeBytes calls to end up on the thread of the link - QObject::connect(this, &LinkInterface::_invokeWriteBytes, this, &LinkInterface::_writeBytes); } LinkInterface::~LinkInterface() { - if (_vehicleReferenceCount != 0) { - qCWarning(LinkInterfaceLog) << "~LinkInterface still have vehicle references:" << _vehicleReferenceCount; + if (m_vehicleReferenceCount != 0) { + qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "still have vehicle references:" << m_vehicleReferenceCount; } - _config.reset(); + + m_config.reset(); } -uint8_t LinkInterface::mavlinkChannel(void) const +uint8_t LinkInterface::mavlinkChannel() const { if (!mavlinkChannelIsSet()) { - qCWarning(LinkInterfaceLog) << "mavlinkChannel isSet() == false"; + qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "mavlinkChannelIsSet() == false"; } - return _mavlinkChannel; + + return m_mavlinkChannel; } -bool LinkInterface::mavlinkChannelIsSet(void) const +bool LinkInterface::mavlinkChannelIsSet() const { - return (LinkManager::invalidMavlinkChannel() != _mavlinkChannel); + return (LinkManager::invalidMavlinkChannel() != m_mavlinkChannel); } bool LinkInterface::_allocateMavlinkChannel() { - // should only be called by the LinkManager during setup Q_ASSERT(!mavlinkChannelIsSet()); + if (mavlinkChannelIsSet()) { - qCWarning(LinkInterfaceLog) << "_allocateMavlinkChannel already have " << _mavlinkChannel; + qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "already have" << m_mavlinkChannel; return true; } - auto mgr = qgcApp()->toolbox()->linkManager(); - _mavlinkChannel = mgr->allocateMavlinkChannel(); + m_mavlinkChannel = qgcApp()->toolbox()->linkManager()->allocateMavlinkChannel(); + if (!mavlinkChannelIsSet()) { - qCWarning(LinkInterfaceLog) << "_allocateMavlinkChannel failed"; + qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "failed"; return false; } - qCDebug(LinkInterfaceLog) << "_allocateMavlinkChannel" << _mavlinkChannel; + + qCDebug(LinkInterfaceLog) << Q_FUNC_INFO << m_mavlinkChannel; return true; } void LinkInterface::_freeMavlinkChannel() { - qCDebug(LinkInterfaceLog) << "_freeMavlinkChannel" << _mavlinkChannel; - if (LinkManager::invalidMavlinkChannel() == _mavlinkChannel) { + qCDebug(LinkInterfaceLog) << Q_FUNC_INFO << m_mavlinkChannel; + + if (!mavlinkChannelIsSet()) { return; } - auto mgr = qgcApp()->toolbox()->linkManager(); - mgr->freeMavlinkChannel(_mavlinkChannel); - _mavlinkChannel = LinkManager::invalidMavlinkChannel(); + qgcApp()->toolbox()->linkManager()->freeMavlinkChannel(m_mavlinkChannel); + m_mavlinkChannel = LinkManager::invalidMavlinkChannel(); } void LinkInterface::writeBytesThreadSafe(const char *bytes, int length) { - emit _invokeWriteBytes(QByteArray(bytes, length)); -} - -void LinkInterface::addVehicleReference(void) -{ - _vehicleReferenceCount++; + const QByteArray data(bytes, length); + (void) QMetaObject::invokeMethod(this, "_writeBytes", Qt::AutoConnection, data); } -void LinkInterface::removeVehicleReference(void) +void LinkInterface::removeVehicleReference() { - if (_vehicleReferenceCount != 0) { - _vehicleReferenceCount--; - if (_vehicleReferenceCount == 0) { - disconnect(); - } + if (m_vehicleReferenceCount != 0) { + m_vehicleReferenceCount--; + _connectionRemoved(); } else { - qCWarning(LinkInterfaceLog) << "removeVehicleReference called with no vehicle references"; + qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "called with no vehicle references"; } } -void LinkInterface::_connectionRemoved(void) +void LinkInterface::_connectionRemoved() { - if (_vehicleReferenceCount == 0) { + if (m_vehicleReferenceCount == 0) { // Since there are no vehicles on the link we can disconnect it right now disconnect(); } else { // If there are still vehicles on this link we allow communication lost to trigger and don't automatically disconect until all the vehicles go away } } - -#ifdef UNITTEST_BUILD -#include "MockLink.h" -bool LinkInterface::isMockLink(void) -{ - return dynamic_cast(this); -} -#endif diff --git a/src/Comms/LinkInterface.h b/src/Comms/LinkInterface.h index e3b0fa50ad4..d0ba7ff107e 100644 --- a/src/Comms/LinkInterface.h +++ b/src/Comms/LinkInterface.h @@ -9,96 +9,76 @@ #pragma once -#include "LinkConfiguration.h" - #include #include +#include "LinkConfiguration.h" + class LinkManager; Q_DECLARE_LOGGING_CATEGORY(LinkInterfaceLog) -/** -* @brief The link interface defines the interface for all links used to communicate -* with the ground station application. -**/ +/// The link interface defines the interface for all links used to communicate with the ground station application. class LinkInterface : public QThread { Q_OBJECT + Q_PROPERTY(bool isPX4Flow READ isPX4Flow CONSTANT) + friend class LinkManager; public: - virtual ~LinkInterface(); - Q_PROPERTY(bool isPX4Flow READ isPX4Flow CONSTANT) - Q_PROPERTY(bool isMockLink READ isMockLink CONSTANT) - - // Property accessors - bool isPX4Flow(void) const { return _isPX4Flow; } -#ifdef UNITTEST_BUILD - bool isMockLink(void); -#else - bool isMockLink(void) { return false; } -#endif + Q_INVOKABLE virtual void disconnect() = 0; - SharedLinkConfigurationPtr linkConfiguration(void) { return _config; } + virtual bool isConnected() const = 0; + virtual bool isLogReplay() { return false; } - Q_INVOKABLE virtual void disconnect (void) = 0; - - virtual bool isConnected (void) const = 0; - virtual bool isLogReplay (void) { return false; } - - uint8_t mavlinkChannel (void) const; - bool mavlinkChannelIsSet (void) const; - - bool decodedFirstMavlinkPacket (void) const { return _decodedFirstMavlinkPacket; } - bool setDecodedFirstMavlinkPacket(bool decodedFirstMavlinkPacket) { return _decodedFirstMavlinkPacket = decodedFirstMavlinkPacket; } - void writeBytesThreadSafe (const char *bytes, int length); - void addVehicleReference (void); - void removeVehicleReference (void); + SharedLinkConfigurationPtr linkConfiguration() { return m_config; } + uint8_t mavlinkChannel() const; + bool mavlinkChannelIsSet() const; + bool isPX4Flow() const { return m_isPX4Flow; } + bool decodedFirstMavlinkPacket(void) const { return m_decodedFirstMavlinkPacket; } + void setDecodedFirstMavlinkPacket(bool decodedFirstMavlinkPacket) { m_decodedFirstMavlinkPacket = decodedFirstMavlinkPacket; } + void writeBytesThreadSafe(const char *bytes, int length); + void addVehicleReference() { ++m_vehicleReferenceCount; } + void removeVehicleReference(); signals: - void bytesReceived (LinkInterface* link, QByteArray data); - void bytesSent (LinkInterface* link, QByteArray data); - void connected (void); - void disconnected (void); - void communicationError (const QString& title, const QString& error); - void _invokeWriteBytes (QByteArray); + void bytesReceived(LinkInterface *link, const QByteArray &data); + void bytesSent(LinkInterface *link, const QByteArray &data); + void connected(); + void disconnected(); + void communicationError(const QString &title, const QString &error); protected: - // Links are only created by LinkManager so constructor is not public - LinkInterface(SharedLinkConfigurationPtr& config, bool isPX4Flow = false); + /// Links are only created by LinkManager so constructor is not public + LinkInterface(SharedLinkConfigurationPtr &config, bool isPX4Flow = false, QObject *parent = nullptr); - void _connectionRemoved(void); + /// Called by the LinkManager during LinkInterface construction instructing the link to setup channels. + /// Default implementation allocates a single channel. But some link types (such as MockLink) need more than one. + virtual bool _allocateMavlinkChannel(); - SharedLinkConfigurationPtr _config; + virtual void _freeMavlinkChannel(); - /// - /// \brief _allocateMavlinkChannel - /// Called by the LinkManager during LinkInterface construction - /// instructing the link to setup channels. - /// - /// Default implementation allocates a single channel. But some link types - /// (such as MockLink) need more than one. - /// - virtual bool _allocateMavlinkChannel(); - virtual void _freeMavlinkChannel (); + void _connectionRemoved(); + + SharedLinkConfigurationPtr m_config; private slots: - virtual void _writeBytes(const QByteArray) = 0; // Not thread safe if called directly, only writeBytesThreadSafe is thread safe + /// Not thread safe if called directly, only writeBytesThreadSafe is thread safe + virtual void _writeBytes(const QByteArray &bytes) = 0; private: - // connect is private since all links should be created through LinkManager::createConnectedLink calls - virtual bool _connect(void) = 0; + /// connect is private since all links should be created through LinkManager::createConnectedLink calls + virtual bool _connect() = 0; - uint8_t _mavlinkChannel = std::numeric_limits::max(); - bool _decodedFirstMavlinkPacket = false; - bool _isPX4Flow = false; - int _vehicleReferenceCount = 0; + uint8_t m_mavlinkChannel = std::numeric_limits::max(); + bool m_decodedFirstMavlinkPacket = false; + bool m_isPX4Flow = false; + int m_vehicleReferenceCount = 0; }; -typedef std::shared_ptr SharedLinkInterfacePtr; -typedef std::weak_ptr WeakLinkInterfacePtr; - +typedef std::shared_ptr SharedLinkInterfacePtr; +typedef std::weak_ptr WeakLinkInterfacePtr; diff --git a/src/Comms/LinkManager.cc b/src/Comms/LinkManager.cc index 063661eb800..b6d0f48f895 100644 --- a/src/Comms/LinkManager.cc +++ b/src/Comms/LinkManager.cc @@ -76,6 +76,7 @@ LinkManager::LinkManager(QGCApplication* app, QGCToolbox* toolbox) qmlRegisterType ("QGroundControl", 1, 0, "LogReplayLinkController"); qRegisterMetaType(); + qRegisterMetaType("LinkInterface*"); } LinkManager::~LinkManager() diff --git a/src/Comms/LogReplayLink.cc b/src/Comms/LogReplayLink.cc index 6f3b0029cce..b0112b6a0d1 100644 --- a/src/Comms/LogReplayLink.cc +++ b/src/Comms/LogReplayLink.cc @@ -151,7 +151,7 @@ void LogReplayLink::_replayError(const QString& errorMsg) } /// Since this is log replay, we just drops writes on the floor -void LogReplayLink::_writeBytes(const QByteArray bytes) +void LogReplayLink::_writeBytes(const QByteArray &bytes) { Q_UNUSED(bytes); } diff --git a/src/Comms/LogReplayLink.h b/src/Comms/LogReplayLink.h index 94e3912547f..8034f0afb9a 100644 --- a/src/Comms/LogReplayLink.h +++ b/src/Comms/LogReplayLink.h @@ -90,7 +90,7 @@ public slots: private slots: // LinkInterface overrides - void _writeBytes(const QByteArray bytes) override; + void _writeBytes(const QByteArray &bytes) override; void _readNextLogEntry (void); void _play (void); diff --git a/src/Comms/MockLink/MockLink.cc b/src/Comms/MockLink/MockLink.cc index 63cab5ef849..405103feebb 100644 --- a/src/Comms/MockLink/MockLink.cc +++ b/src/Comms/MockLink/MockLink.cc @@ -69,7 +69,7 @@ MockLink::MockLink(SharedLinkConfigurationPtr& config) { qCDebug(MockLinkLog) << "MockLink" << this; - MockConfiguration* mockConfig = qobject_cast(_config.get()); + MockConfiguration* mockConfig = qobject_cast(m_config.get()); _firmwareType = mockConfig->firmwareType(); _vehicleType = mockConfig->vehicleType(); _sendStatusText = mockConfig->sendStatusText(); @@ -537,7 +537,7 @@ void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg) } /// @brief Called when QGC wants to write bytes to the MAV -void MockLink::_writeBytes(const QByteArray bytes) +void MockLink::_writeBytes(const QByteArray &bytes) { // This prevents the responses to mavlink messages from being sent until the _writeBytes returns. emit writeBytesQueuedSignal(bytes); diff --git a/src/Comms/MockLink/MockLink.h b/src/Comms/MockLink/MockLink.h index 4266e8654e8..fa3dc084fea 100644 --- a/src/Comms/MockLink/MockLink.h +++ b/src/Comms/MockLink/MockLink.h @@ -192,7 +192,7 @@ class MockLink : public LinkInterface private slots: // LinkInterface overrides - void _writeBytes(const QByteArray bytes) final; + void _writeBytes(const QByteArray &bytes) final; void _writeBytesQueued (const QByteArray bytes); void _run1HzTasks (void); diff --git a/src/Comms/SerialLink.cc b/src/Comms/SerialLink.cc index db0cf434499..1a8ac0f58d0 100644 --- a/src/Comms/SerialLink.cc +++ b/src/Comms/SerialLink.cc @@ -57,7 +57,7 @@ bool SerialLink::_isBootloader() return false; } -void SerialLink::_writeBytes(const QByteArray data) +void SerialLink::_writeBytes(const QByteArray &data) { if(_port && _port->isOpen()) { emit bytesSent(this, data); @@ -65,7 +65,7 @@ void SerialLink::_writeBytes(const QByteArray data) } else { // Error occurred qWarning() << "Serial port not writeable"; - _emitLinkError(tr("Could not send data - link %1 is disconnected!").arg(_config->name())); + _emitLinkError(tr("Could not send data - link %1 is disconnected!").arg(m_config->name())); } } @@ -103,7 +103,7 @@ bool SerialLink::_connect(void) // Initialize the connection if (!_hardwareConnect(error, errorString)) { - if (_config->isAutoConnect()) { + if (m_config->isAutoConnect()) { // Be careful with spitting out open error related to trying to open a busy port using autoconnect if (error == QSerialPort::PermissionError) { // Device already open, ignore and fail connect @@ -195,7 +195,7 @@ bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString& } #endif if (!_port->isOpen() ) { - qDebug() << "open failed" << _port->errorString() << _port->error() << _config->name() << "autconnect:" << _config->isAutoConnect(); + qDebug() << "open failed" << _port->errorString() << _port->error() << m_config->name() << "autconnect:" << m_config->isAutoConnect(); error = _port->error(); errorString = _port->errorString(); _port->close(); @@ -234,7 +234,7 @@ void SerialLink::_readBytes(void) } else { // Error occurred qWarning() << "Serial port not readable"; - _emitLinkError(tr("Could not read data - link %1 is disconnected!").arg(_config->name())); + _emitLinkError(tr("Could not read data - link %1 is disconnected!").arg(m_config->name())); } } @@ -272,7 +272,7 @@ void SerialLink::_emitLinkError(const QString& errorMsg) { QString msg("Error on link %1. %2"); qDebug() << errorMsg; - emit communicationError(tr("Link Error"), msg.arg(_config->name()).arg(errorMsg)); + emit communicationError(tr("Link Error"), msg.arg(m_config->name()).arg(errorMsg)); } //-------------------------------------------------------------------------- diff --git a/src/Comms/SerialLink.h b/src/Comms/SerialLink.h index 9b4bea0d608..93c9f75380a 100644 --- a/src/Comms/SerialLink.h +++ b/src/Comms/SerialLink.h @@ -115,7 +115,7 @@ class SerialLink : public LinkInterface QSerialPort* _hackAccessToPort(void) { return _port; } private slots: - void _writeBytes(const QByteArray data) override; + void _writeBytes(const QByteArray &data) override; public slots: void linkError(QSerialPort::SerialPortError error); diff --git a/src/Comms/TCPLink.cc b/src/Comms/TCPLink.cc index a2be088ee41..6731f94d47d 100644 --- a/src/Comms/TCPLink.cc +++ b/src/Comms/TCPLink.cc @@ -51,7 +51,7 @@ void TCPLink::_writeDebugBytes(const QByteArray data) } #endif -void TCPLink::_writeBytes(const QByteArray data) +void TCPLink::_writeBytes(const QByteArray &data) { #ifdef TCPLINK_READWRITE_DEBUG _writeDebugBytes(data); @@ -120,7 +120,7 @@ bool TCPLink::_hardwareConnect() // Whether a failed connection emits an error signal or not is platform specific. // So in cases where it is not emitted, we emit one ourselves. if (errorSpy.count() == 0) { - emit communicationError(tr("Link Error"), tr("Error on link %1. Connection failed").arg(_config->name())); + emit communicationError(tr("Link Error"), tr("Error on link %1. Connection failed").arg(m_config->name())); } delete _socket; _socket = nullptr; @@ -134,7 +134,7 @@ bool TCPLink::_hardwareConnect() void TCPLink::_socketError(QAbstractSocket::SocketError socketError) { Q_UNUSED(socketError); - emit communicationError(tr("Link Error"), tr("Error on link %1. Error on socket: %2.").arg(_config->name()).arg(_socket->errorString())); + emit communicationError(tr("Link Error"), tr("Error on link %1. Error on socket: %2.").arg(m_config->name()).arg(_socket->errorString())); } /** diff --git a/src/Comms/TCPLink.h b/src/Comms/TCPLink.h index 21185872e45..b5ee942c4bc 100644 --- a/src/Comms/TCPLink.h +++ b/src/Comms/TCPLink.h @@ -79,7 +79,7 @@ private slots: void _readBytes (void); // LinkInterface overrides - void _writeBytes(const QByteArray data) override; + void _writeBytes(const QByteArray &data) override; private: // LinkInterface overrides diff --git a/src/Comms/UDPLink.cc b/src/Comms/UDPLink.cc index b3c2afa4600..b129dcb4705 100644 --- a/src/Comms/UDPLink.cc +++ b/src/Comms/UDPLink.cc @@ -131,7 +131,7 @@ bool UDPLink::_isIpLocal(const QHostAddress& add) return false; } -void UDPLink::_writeBytes(const QByteArray data) +void UDPLink::_writeBytes(const QByteArray &data) { if (!_socket) { return; diff --git a/src/Comms/UDPLink.h b/src/Comms/UDPLink.h index 3cc6fe94d79..8f16c691977 100644 --- a/src/Comms/UDPLink.h +++ b/src/Comms/UDPLink.h @@ -109,7 +109,7 @@ public slots: private slots: // LinkInterface overrides - void _writeBytes(const QByteArray data) override; + void _writeBytes(const QByteArray &data) override; private: