Commit fe8ff69e authored by Nate Weibley's avatar Nate Weibley

Refactor writeBytes to _writeBytes

parent a2a20353
......@@ -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)
{
......
......@@ -193,7 +193,7 @@ private:
void _restartConnection ();
private slots:
void writeBytes (const QByteArray bytes);
void _writeBytes (const QByteArray bytes);
private:
void _createSocket ();
......
......@@ -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*>("LinkInterface*");
}
......
......@@ -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);
}
......
......@@ -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);
......
......@@ -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());
......
......@@ -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);
......
......@@ -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
......
......@@ -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();
......
......@@ -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:
......
......@@ -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
......
......@@ -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();
......
......@@ -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;
......
......@@ -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();
......
......@@ -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());
......
......@@ -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);
......
......@@ -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);
......
......@@ -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);
......
......@@ -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;
......
......@@ -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:
......
......@@ -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<char*>(bytes.data()),bytes.size())) // return value of 0 is successful written
{
......
......@@ -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();
......
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