Skip to content

Commit

Permalink
Comms: Fix Private Variable Naming
Browse files Browse the repository at this point in the history
  • Loading branch information
HTRamsey committed Aug 19, 2024
1 parent 4a3b719 commit d29ff61
Show file tree
Hide file tree
Showing 9 changed files with 76 additions and 78 deletions.
44 changes: 21 additions & 23 deletions src/Comms/LinkConfiguration.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand All @@ -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)
Expand Down Expand Up @@ -148,40 +146,40 @@ 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);
}
}

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();
}
}
20 changes: 10 additions & 10 deletions src/Comms/LinkConfiguration.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<LinkInterface> 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);
Expand Down Expand Up @@ -126,13 +126,13 @@ class LinkConfiguration : public QObject
void highLatencyChanged();

protected:
std::weak_ptr<LinkInterface> m_link; ///< Link currently using this configuration (if any)
std::weak_ptr<LinkInterface> _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<LinkConfiguration> SharedLinkConfigurationPtr;
Expand Down
40 changes: 20 additions & 20 deletions src/Comms/LinkInterface.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -46,27 +46,27 @@ 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)
{
if (!isSecureConnection()) {
auto appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
QByteArray signingKeyBytes = appSettings->mavlink2SigningKey()->rawValue().toByteArray();
if (MAVLinkSigning::initSigning(static_cast<mavlink_channel_t>(m_mavlinkChannel), signingKeyBytes, MAVLinkSigning::insecureConnectionAccceptUnsignedCallback)) {
if (MAVLinkSigning::initSigning(static_cast<mavlink_channel_t>(_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;
}
Expand All @@ -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();

Expand All @@ -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)
Expand All @@ -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";
Expand All @@ -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 {
Expand Down
20 changes: 10 additions & 10 deletions src/Comms/LinkInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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
Expand All @@ -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<uint8_t>::max();
bool m_decodedFirstMavlinkPacket = false;
bool m_isPX4Flow = false;
int m_vehicleReferenceCount = 0;
uint8_t _mavlinkChannel = std::numeric_limits<uint8_t>::max();
bool _decodedFirstMavlinkPacket = false;
bool _isPX4Flow = false;
int _vehicleReferenceCount = 0;
bool _signingSignatureFailure = false;
};

Expand Down
10 changes: 5 additions & 5 deletions src/Comms/MAVLinkProtocol.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -105,15 +105,15 @@ 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()
{
// 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();
Expand All @@ -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
}
Expand Down Expand Up @@ -413,7 +413,7 @@ int MAVLinkProtocol::getComponentId()

void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
m_enable_version_check = enabled;
_enable_version_check = enabled;
emit versionCheckChanged(enabled);
}

Expand Down
4 changes: 2 additions & 2 deletions src/Comms/MAVLinkProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -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() {
Expand Down Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion src/Comms/MockLink/MockLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ MockLink::MockLink(SharedLinkConfigurationPtr& config)
{
qCDebug(MockLinkLog) << "MockLink" << this;

MockConfiguration* mockConfig = qobject_cast<MockConfiguration*>(m_config.get());
MockConfiguration* mockConfig = qobject_cast<MockConfiguration*>(_config.get());
_firmwareType = mockConfig->firmwareType();
_vehicleType = mockConfig->vehicleType();
_sendStatusText = mockConfig->sendStatusText();
Expand Down
Loading

0 comments on commit d29ff61

Please sign in to comment.