diff --git a/src/comm/BluetoothLink.cc b/src/comm/BluetoothLink.cc index 5062d12..f10161e 100644 --- a/src/comm/BluetoothLink.cc +++ b/src/comm/BluetoothLink.cc @@ -89,7 +89,7 @@ QString BluetoothLink::getName() const return _config->name(); } -void BluetoothLink::writeBytes(const QByteArray bytes) +void BluetoothLink::_writeBytes(const QByteArray bytes) { if(_targetSocket) { diff --git a/src/comm/BluetoothLink.h b/src/comm/BluetoothLink.h index 3fe6540..c2a83f4 100644 --- a/src/comm/BluetoothLink.h +++ b/src/comm/BluetoothLink.h @@ -193,7 +193,7 @@ private: void _restartConnection (); private slots: - void writeBytes (const QByteArray bytes); + void _writeBytes (const QByteArray bytes); private: void _createSocket (); diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index dbd2d3b..bd0b48e 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -163,7 +163,7 @@ public slots: } private slots: - virtual void writeBytes(const QByteArray) = 0; + virtual void _writeBytes(const QByteArray) = 0; signals: void autoconnectChanged(bool autoconnect); @@ -220,7 +220,7 @@ protected: memset(_outDataWriteAmounts,0, sizeof(_outDataWriteAmounts)); memset(_outDataWriteTimes, 0, sizeof(_outDataWriteTimes)); - QObject::connect(this, &LinkInterface::_invokeWriteBytes, this, &LinkInterface::writeBytes); + QObject::connect(this, &LinkInterface::_invokeWriteBytes, this, &LinkInterface::_writeBytes); qRegisterMetaType("LinkInterface*"); } diff --git a/src/comm/LogReplayLink.cc b/src/comm/LogReplayLink.cc index 439e594..81ac1cc 100644 --- a/src/comm/LogReplayLink.cc +++ b/src/comm/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/comm/LogReplayLink.h b/src/comm/LogReplayLink.h index 1c28bd8..e54d27e 100644 --- a/src/comm/LogReplayLink.h +++ b/src/comm/LogReplayLink.h @@ -99,7 +99,7 @@ public: bool disconnect(void); private slots: - virtual void writeBytes(const QByteArray bytes); + virtual void _writeBytes(const QByteArray bytes); signals: void logFileStats(bool logTimestamped, int logDurationSecs, int binaryBaudRate); diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index d06d56d..9d161c6 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -313,7 +313,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) { if (_inNSH) { _handleIncomingNSHBytes(bytes.constData(), bytes.count()); diff --git a/src/comm/MockLink.h b/src/comm/MockLink.h index 49ef8f0..395907e 100644 --- a/src/comm/MockLink.h +++ b/src/comm/MockLink.h @@ -151,7 +151,7 @@ public: static MockLink* startAPMArduPlaneMockLink (bool sendStatusText); private slots: - virtual void writeBytes(const QByteArray bytes); + virtual void _writeBytes(const QByteArray bytes); private slots: void _run1HzTasks(void); diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 9b8773f..5f0ec84 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -244,7 +244,7 @@ void QGCFlightGearLink::updateControls(quint64 time, float rollAilerons, float p } } -void QGCFlightGearLink::writeBytes(const QByteArray data) +void QGCFlightGearLink::_writeBytes(const QByteArray data) { //#define QGCFlightGearLink_DEBUG #ifdef QGCFlightGearLink_DEBUG diff --git a/src/comm/QGCFlightGearLink.h b/src/comm/QGCFlightGearLink.h index 5db87ba..b9887ef 100644 --- a/src/comm/QGCFlightGearLink.h +++ b/src/comm/QGCFlightGearLink.h @@ -129,7 +129,7 @@ private slots: * @param data Pointer to the data byte array * @param size The size of the bytes array **/ - void writeBytes(const QByteArray data); + void _writeBytes(const QByteArray data); public slots: bool connectSimulation(); diff --git a/src/comm/QGCHilLink.h b/src/comm/QGCHilLink.h index 19163e7..9ac6981 100644 --- a/src/comm/QGCHilLink.h +++ b/src/comm/QGCHilLink.h @@ -73,7 +73,7 @@ public slots: virtual bool disconnectSimulation() = 0; private slots: - virtual void writeBytes(const QByteArray) = 0; + virtual void _writeBytes(const QByteArray) = 0; protected: virtual void setName(QString name) = 0; @@ -81,7 +81,7 @@ protected: QGCHilLink() : QThread() { - connect(this, &QGCHilLink::_invokeWriteBytes, this, &QGCHilLink::writeBytes); + connect(this, &QGCHilLink::_invokeWriteBytes, this, &QGCHilLink::_writeBytes); } signals: diff --git a/src/comm/QGCJSBSimLink.cc b/src/comm/QGCJSBSimLink.cc index 0f31dbb..fe82547 100644 --- a/src/comm/QGCJSBSimLink.cc +++ b/src/comm/QGCJSBSimLink.cc @@ -255,7 +255,7 @@ void QGCJSBSimLink::updateControls(quint64 time, float rollAilerons, float pitch //qDebug() << "Updated controls" << state; } -void QGCJSBSimLink::writeBytes(const QByteArray data) +void QGCJSBSimLink::_writeBytes(const QByteArray data) { //#define QGCJSBSimLink_DEBUG #ifdef QGCJSBSimLink_DEBUG diff --git a/src/comm/QGCJSBSimLink.h b/src/comm/QGCJSBSimLink.h index cd4e4b4..e09d43b 100644 --- a/src/comm/QGCJSBSimLink.h +++ b/src/comm/QGCJSBSimLink.h @@ -122,7 +122,7 @@ private slots: * @param data Pointer to the data byte array * @param size The size of the bytes array **/ - void writeBytes(const QByteArray data); + void _writeBytes(const QByteArray data); public slots: bool connectSimulation(); diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index 16b0c1c..244b143 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -448,7 +448,7 @@ Eigen::Matrix3f euler_to_wRo(double yaw, double pitch, double roll) { return wRo; } -void QGCXPlaneLink::writeBytes(const QByteArray data) +void QGCXPlaneLink::_writeBytes(const QByteArray data) { if (data.isEmpty()) return; diff --git a/src/comm/QGCXPlaneLink.h b/src/comm/QGCXPlaneLink.h index 4b234d0..03ebf12 100644 --- a/src/comm/QGCXPlaneLink.h +++ b/src/comm/QGCXPlaneLink.h @@ -134,7 +134,7 @@ private slots: * @param data Pointer to the data byte array * @param size The size of the bytes array **/ - void writeBytes(const QByteArray data); + void _writeBytes(const QByteArray data); public slots: bool connectSimulation(); diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 4633d16..ae702b5 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -82,7 +82,7 @@ bool SerialLink::_isBootloader() return false; } -void SerialLink::writeBytes(const QByteArray data) +void SerialLink::_writeBytes(const QByteArray data) { if(_port && _port->isOpen()) { _logOutputDataRate(data.size(), QDateTime::currentMSecsSinceEpoch()); diff --git a/src/comm/SerialLink.h b/src/comm/SerialLink.h index bdd5e07..f787b81 100644 --- a/src/comm/SerialLink.h +++ b/src/comm/SerialLink.h @@ -164,7 +164,7 @@ private slots: * @param data Pointer to the data byte array * @param size The size of the bytes array **/ - void writeBytes(const QByteArray data); + void _writeBytes(const QByteArray data); public slots: void linkError(QSerialPort::SerialPortError error); diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index 7554a49..75114d3 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -88,7 +88,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); diff --git a/src/comm/TCPLink.h b/src/comm/TCPLink.h index 3644531..593e8e9 100644 --- a/src/comm/TCPLink.h +++ b/src/comm/TCPLink.h @@ -154,7 +154,7 @@ public: private slots: // From LinkInterface - void writeBytes(const QByteArray data); + void _writeBytes(const QByteArray data); public slots: void waitForBytesWritten(int msecs); diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 380e1f4..7f24c38 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -147,7 +147,7 @@ void UDPLink::removeHost(const QString& host) _config->removeHost(host); } -void UDPLink::writeBytes(const QByteArray data) +void UDPLink::_writeBytes(const QByteArray data) { if (!_socket) return; diff --git a/src/comm/UDPLink.h b/src/comm/UDPLink.h index cb22923..23c1151 100644 --- a/src/comm/UDPLink.h +++ b/src/comm/UDPLink.h @@ -208,7 +208,7 @@ private slots: * @param data Pointer to the data byte array * @param size The size of the bytes array **/ - void writeBytes(const QByteArray data); + void _writeBytes(const QByteArray data); protected: diff --git a/src/comm/XbeeLink.cpp b/src/comm/XbeeLink.cpp index 8331a1b..c3a7b15 100644 --- a/src/comm/XbeeLink.cpp +++ b/src/comm/XbeeLink.cpp @@ -172,7 +172,7 @@ void XbeeLink::_disconnect(void) emit disconnected(); } -void XbeeLink::writeBytes(const QByteArray bytes) +void XbeeLink::_writeBytes(const QByteArray bytes) { if(!xbee_nsenddata(this->m_xbeeCon,const_cast(bytes.data()),bytes.size())) // return value of 0 is successful written { diff --git a/src/comm/XbeeLink.h b/src/comm/XbeeLink.h index a8d2d34..02180dd 100644 --- a/src/comm/XbeeLink.h +++ b/src/comm/XbeeLink.h @@ -46,7 +46,7 @@ public: qint64 getCurrentInDataRate() const; private slots: // virtual functions from LinkInterface - void writeBytes(const QByteArray bytes); + void _writeBytes(const QByteArray bytes); protected slots: // virtual functions from LinkInterface void readBytes();