diff --git a/src/Comms/LinkConfiguration.cc b/src/Comms/LinkConfiguration.cc index d0724a13c9f..9f8df074706 100644 --- a/src/Comms/LinkConfiguration.cc +++ b/src/Comms/LinkConfiguration.cc @@ -26,24 +26,22 @@ LinkConfiguration::LinkConfiguration(const QString &name, QObject *parent) : QObject(parent) - , m_name(name) + , _name(name) { // qCDebug(AudioOutputLog) << Q_FUNC_INFO << this; } 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()) { // qCDebug(AudioOutputLog) << Q_FUNC_INFO << this; - LinkConfiguration::copyFrom(copy); - - Q_ASSERT(!m_name.isEmpty()); + Q_ASSERT(!_name.isEmpty()); } LinkConfiguration::~LinkConfiguration() @@ -55,11 +53,11 @@ void LinkConfiguration::copyFrom(LinkConfiguration *source) { 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(); + _link = source->_link; + _name = source->name(); + _dynamic = source->isDynamic(); + _autoConnect = source->isAutoConnect(); + _highLatency = source->isHighLatency(); } LinkConfiguration *LinkConfiguration::createSettings(int type, const QString &name) @@ -148,8 +146,8 @@ LinkConfiguration *LinkConfiguration::duplicateSettings(LinkConfiguration *sourc void LinkConfiguration::setName(const QString &name) { - if (name != m_name) { - m_name = name; + if (name != _name) { + _name = name; emit nameChanged(name); } } @@ -157,31 +155,31 @@ void LinkConfiguration::setName(const QString &name) void LinkConfiguration::setLink(SharedLinkInterfacePtr link) { if (link.get() != this->link()) { - m_link = link; + _link = link; emit linkChanged(); } } void LinkConfiguration::setDynamic(bool dynamic) { - if (dynamic != m_dynamic) { - m_dynamic = dynamic; + if (dynamic != _dynamic) { + _dynamic = dynamic; emit dynamicChanged(); } } void LinkConfiguration::setAutoConnect(bool autoc) { - if (autoc != m_autoConnect) { - m_autoConnect = autoc; + if (autoc != _autoConnect) { + _autoConnect = autoc; emit autoConnectChanged(); } } void LinkConfiguration::setHighLatency(bool hl) { - if (hl != m_highLatency) { - m_highLatency = hl; + if (hl != _highLatency) { + _highLatency = hl; emit highLatencyChanged(); } } diff --git a/src/Comms/LinkConfiguration.h b/src/Comms/LinkConfiguration.h index 039b70ece3c..aec5ac90d9d 100644 --- a/src/Comms/LinkConfiguration.h +++ b/src/Comms/LinkConfiguration.h @@ -34,27 +34,27 @@ class LinkConfiguration : public QObject LinkConfiguration(LinkConfiguration *copy, QObject *parent = nullptr); virtual ~LinkConfiguration(); - QString name() const { return m_name; } + QString name() const { return _name; } void setName(const QString &name); - LinkInterface *link() { return m_link.lock().get(); } + LinkInterface *link() { return _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; } + bool isDynamic() const { return _dynamic; } /// Set if this is this a dynamic configuration. (decided at runtime) void setDynamic(bool dynamic = true); - bool isAutoConnect() const { return m_autoConnect; } + bool isAutoConnect() const { return _autoConnect; } /// Set if this is this an Auto Connect configuration. void setAutoConnect(bool autoc = true); /// 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; } + bool isHighLatency() const{ return _highLatency; } /// Set if this is this an High Latency configuration. void setHighLatency(bool hl = false); @@ -126,13 +126,13 @@ class LinkConfiguration : public QObject void highLatencyChanged(); protected: - std::weak_ptr m_link; ///< Link currently using this configuration (if any) + std::weak_ptr _link; ///< Link currently using this configuration (if any) private: - 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; + QString _name; + bool _dynamic = false; ///< A connection added automatically and not persistent (unless it's edited). + bool _autoConnect = false; ///< This connection is started automatically at boot + bool _highLatency = false; }; typedef std::shared_ptr SharedLinkConfigurationPtr; diff --git a/src/Comms/LinkInterface.cc b/src/Comms/LinkInterface.cc index bcf6f6c5da9..196b0baea63 100644 --- a/src/Comms/LinkInterface.cc +++ b/src/Comms/LinkInterface.cc @@ -25,19 +25,19 @@ QGC_LOGGING_CATEGORY(LinkInterfaceLog, "LinkInterfaceLog") LinkInterface::LinkInterface(SharedLinkConfigurationPtr &config, bool isPX4Flow, QObject *parent) : QThread(parent) - , m_config(config) - , m_isPX4Flow(isPX4Flow) + , _config(config) + , _isPX4Flow(isPX4Flow) { QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); } LinkInterface::~LinkInterface() { - if (m_vehicleReferenceCount != 0) { - qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "still have vehicle references:" << m_vehicleReferenceCount; + if (_vehicleReferenceCount != 0) { + qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "still have vehicle references:" << _vehicleReferenceCount; } - m_config.reset(); + _config.reset(); } uint8_t LinkInterface::mavlinkChannel() const @@ -46,12 +46,12 @@ uint8_t LinkInterface::mavlinkChannel() const qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "mavlinkChannelIsSet() == false"; } - return m_mavlinkChannel; + return _mavlinkChannel; } bool LinkInterface::mavlinkChannelIsSet() const { - return (LinkManager::invalidMavlinkChannel() != m_mavlinkChannel); + return (LinkManager::invalidMavlinkChannel() != _mavlinkChannel); } bool LinkInterface::initMavlinkSigning(void) @@ -59,14 +59,14 @@ bool LinkInterface::initMavlinkSigning(void) if (!isSecureConnection()) { auto appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); QByteArray signingKeyBytes = appSettings->mavlink2SigningKey()->rawValue().toByteArray(); - if (MAVLinkSigning::initSigning(static_cast(m_mavlinkChannel), signingKeyBytes, MAVLinkSigning::insecureConnectionAccceptUnsignedCallback)) { + if (MAVLinkSigning::initSigning(static_cast(_mavlinkChannel), signingKeyBytes, MAVLinkSigning::insecureConnectionAccceptUnsignedCallback)) { if (signingKeyBytes.isEmpty()) { - qCDebug(LinkInterfaceLog) << "Signing disabled on channel" << m_mavlinkChannel; + qCDebug(LinkInterfaceLog) << "Signing disabled on channel" << _mavlinkChannel; } else { - qCDebug(LinkInterfaceLog) << "Signing enabled on channel" << m_mavlinkChannel; + qCDebug(LinkInterfaceLog) << "Signing enabled on channel" << _mavlinkChannel; } } else { - qWarning() << Q_FUNC_INFO << "Failed To enable Signing on channel" << m_mavlinkChannel; + qWarning() << Q_FUNC_INFO << "Failed To enable Signing on channel" << _mavlinkChannel; // FIXME: What should we do here? return false; } @@ -80,18 +80,18 @@ bool LinkInterface::_allocateMavlinkChannel() Q_ASSERT(!mavlinkChannelIsSet()); if (mavlinkChannelIsSet()) { - qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "already have" << m_mavlinkChannel; + qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "already have" << _mavlinkChannel; return true; } - m_mavlinkChannel = qgcApp()->toolbox()->linkManager()->allocateMavlinkChannel(); + _mavlinkChannel = qgcApp()->toolbox()->linkManager()->allocateMavlinkChannel(); if (!mavlinkChannelIsSet()) { qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "failed"; return false; } - qCDebug(LinkInterfaceLog) << "_allocateMavlinkChannel" << m_mavlinkChannel; + qCDebug(LinkInterfaceLog) << "_allocateMavlinkChannel" << _mavlinkChannel; initMavlinkSigning(); @@ -100,14 +100,14 @@ bool LinkInterface::_allocateMavlinkChannel() void LinkInterface::_freeMavlinkChannel() { - qCDebug(LinkInterfaceLog) << Q_FUNC_INFO << m_mavlinkChannel; + qCDebug(LinkInterfaceLog) << Q_FUNC_INFO << _mavlinkChannel; if (!mavlinkChannelIsSet()) { return; } - qgcApp()->toolbox()->linkManager()->freeMavlinkChannel(m_mavlinkChannel); - m_mavlinkChannel = LinkManager::invalidMavlinkChannel(); + qgcApp()->toolbox()->linkManager()->freeMavlinkChannel(_mavlinkChannel); + _mavlinkChannel = LinkManager::invalidMavlinkChannel(); } void LinkInterface::writeBytesThreadSafe(const char *bytes, int length) @@ -118,8 +118,8 @@ void LinkInterface::writeBytesThreadSafe(const char *bytes, int length) void LinkInterface::removeVehicleReference() { - if (m_vehicleReferenceCount != 0) { - m_vehicleReferenceCount--; + if (_vehicleReferenceCount != 0) { + _vehicleReferenceCount--; _connectionRemoved(); } else { qCWarning(LinkInterfaceLog) << Q_FUNC_INFO << "called with no vehicle references"; @@ -128,7 +128,7 @@ void LinkInterface::removeVehicleReference() void LinkInterface::_connectionRemoved() { - if (m_vehicleReferenceCount == 0) { + if (_vehicleReferenceCount == 0) { // Since there are no vehicles on the link we can disconnect it right now disconnect(); } else { diff --git a/src/Comms/LinkInterface.h b/src/Comms/LinkInterface.h index c8f45e93702..27b78ee21ba 100644 --- a/src/Comms/LinkInterface.h +++ b/src/Comms/LinkInterface.h @@ -36,14 +36,14 @@ class LinkInterface : public QThread virtual bool isLogReplay() { return false; } virtual bool isSecureConnection() { return false; } ///< Returns true if the connection is secure (e.g. USB, wired ethernet) - SharedLinkConfigurationPtr linkConfiguration() { return m_config; } + SharedLinkConfigurationPtr linkConfiguration() { return _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; } + bool isPX4Flow() const { return _isPX4Flow; } + bool decodedFirstMavlinkPacket(void) const { return _decodedFirstMavlinkPacket; } + void setDecodedFirstMavlinkPacket(bool decodedFirstMavlinkPacket) { _decodedFirstMavlinkPacket = decodedFirstMavlinkPacket; } void writeBytesThreadSafe(const char *bytes, int length); - void addVehicleReference() { ++m_vehicleReferenceCount; } + void addVehicleReference() { ++_vehicleReferenceCount; } void removeVehicleReference(); bool initMavlinkSigning(); void setSigningSignatureFailure(bool failure); @@ -67,7 +67,7 @@ class LinkInterface : public QThread void _connectionRemoved(); - SharedLinkConfigurationPtr m_config; + SharedLinkConfigurationPtr _config; private slots: /// Not thread safe if called directly, only writeBytesThreadSafe is thread safe @@ -77,10 +77,10 @@ private slots: /// connect is private since all links should be created through LinkManager::createConnectedLink calls virtual bool _connect() = 0; - uint8_t m_mavlinkChannel = std::numeric_limits::max(); - bool m_decodedFirstMavlinkPacket = false; - bool m_isPX4Flow = false; - int m_vehicleReferenceCount = 0; + uint8_t _mavlinkChannel = std::numeric_limits::max(); + bool _decodedFirstMavlinkPacket = false; + bool _isPX4Flow = false; + int _vehicleReferenceCount = 0; bool _signingSignatureFailure = false; }; diff --git a/src/Comms/MAVLinkProtocol.cc b/src/Comms/MAVLinkProtocol.cc index a653fd62ec1..5c1e6866a4d 100644 --- a/src/Comms/MAVLinkProtocol.cc +++ b/src/Comms/MAVLinkProtocol.cc @@ -37,7 +37,7 @@ static QObject* mavlinkSingletonFactory(QQmlEngine*, QJSEngine*) */ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox) : QGCTool(app, toolbox) - , m_enable_version_check(true) + , _enable_version_check(true) , _message({}) , _status({}) , versionMismatchIgnore(false) @@ -105,7 +105,7 @@ void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox) connect(_multiVehicleManager, &MultiVehicleManager::vehicleAdded, this, &MAVLinkProtocol::_vehicleCountChanged); connect(_multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkProtocol::_vehicleCountChanged); - emit versionCheckChanged(m_enable_version_check); + emit versionCheckChanged(_enable_version_check); } void MAVLinkProtocol::loadSettings() @@ -113,7 +113,7 @@ void MAVLinkProtocol::loadSettings() // Load defaults from settings QSettings settings; settings.beginGroup("QGC_MAVLINK_PROTOCOL"); - enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool()); + enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", _enable_version_check).toBool()); // Only set system id if it was valid int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt(); @@ -128,7 +128,7 @@ void MAVLinkProtocol::storeSettings() // Store settings QSettings settings; settings.beginGroup("QGC_MAVLINK_PROTOCOL"); - settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check); + settings.setValue("VERSION_CHECK_ENABLED", _enable_version_check); settings.setValue("GCS_SYSTEM_ID", systemId); // Parameter interface settings } @@ -413,7 +413,7 @@ int MAVLinkProtocol::getComponentId() void MAVLinkProtocol::enableVersionCheck(bool enabled) { - m_enable_version_check = enabled; + _enable_version_check = enabled; emit versionCheckChanged(enabled); } diff --git a/src/Comms/MAVLinkProtocol.h b/src/Comms/MAVLinkProtocol.h index 3980aadae3b..bb779a0581e 100644 --- a/src/Comms/MAVLinkProtocol.h +++ b/src/Comms/MAVLinkProtocol.h @@ -47,7 +47,7 @@ class MAVLinkProtocol : public QGCTool /** @brief Get protocol version check state */ bool versionCheckEnabled() const { - return m_enable_version_check; + return _enable_version_check; } /** @brief Get the protocol version */ int getVersion() { @@ -96,7 +96,7 @@ public slots: void checkForLostLogFiles(void); protected: - bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC + bool _enable_version_check; ///< Enable checking of version match of MAV and QGC uint8_t lastIndex[256][256]; ///< Store the last received sequence ID for each system/componenet pair uint8_t firstMessage[256][256]; ///< First message flag uint64_t totalReceiveCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< The total number of successfully received messages diff --git a/src/Comms/MockLink/MockLink.cc b/src/Comms/MockLink/MockLink.cc index 405103feebb..1859c2969d0 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(m_config.get()); + MockConfiguration* mockConfig = qobject_cast(_config.get()); _firmwareType = mockConfig->firmwareType(); _vehicleType = mockConfig->vehicleType(); _sendStatusText = mockConfig->sendStatusText(); diff --git a/src/Comms/SerialLink.cc b/src/Comms/SerialLink.cc index 7485b7a9afd..5a584c71c0e 100644 --- a/src/Comms/SerialLink.cc +++ b/src/Comms/SerialLink.cc @@ -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(m_config->name())); + _emitLinkError(tr("Could not send data - link %1 is disconnected!").arg(_config->name())); } } @@ -103,7 +103,7 @@ bool SerialLink::_connect(void) // Initialize the connection if (!_hardwareConnect(error, errorString)) { - if (m_config->isAutoConnect()) { + if (_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() << m_config->name() << "autconnect:" << m_config->isAutoConnect(); + qDebug() << "open failed" << _port->errorString() << _port->error() << _config->name() << "autconnect:" << _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(m_config->name())); + _emitLinkError(tr("Could not read data - link %1 is disconnected!").arg(_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(m_config->name()).arg(errorMsg)); + emit communicationError(tr("Link Error"), msg.arg(_config->name()).arg(errorMsg)); } bool SerialLink::isSecureConnection() diff --git a/src/Comms/TCPLink.cc b/src/Comms/TCPLink.cc index 1f5a69cccdf..7ed6a8f96d8 100644 --- a/src/Comms/TCPLink.cc +++ b/src/Comms/TCPLink.cc @@ -121,7 +121,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(m_config->name())); + emit communicationError(tr("Link Error"), tr("Error on link %1. Connection failed").arg(_config->name())); } delete _socket; _socket = nullptr; @@ -135,7 +135,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(m_config->name()).arg(_socket->errorString())); + emit communicationError(tr("Link Error"), tr("Error on link %1. Error on socket: %2.").arg(_config->name()).arg(_socket->errorString())); } /**