Commit c4db113d authored by Bryant Mairs's avatar Bryant Mairs

Renamed getNominalDataRate to getConnectionSpeed. Also added...

Renamed getNominalDataRate to getConnectionSpeed. Also added upstream/downstream data rate functions to all Link classes.
parent 144ef965
...@@ -73,7 +73,7 @@ public: ...@@ -73,7 +73,7 @@ public:
/* Connection characteristics */ /* Connection characteristics */
/** /**
* @Brief Get the nominal data rate of the interface. * @Brief Get the maximum connection speed for this interface.
* *
* The nominal data rate is the theoretical maximum data rate of the * The nominal data rate is the theoretical maximum data rate of the
* interface. For 100Base-T Ethernet this would be 100 Mbit/s (100'000'000 * interface. For 100Base-T Ethernet this would be 100 Mbit/s (100'000'000
...@@ -81,7 +81,27 @@ public: ...@@ -81,7 +81,27 @@ public:
* *
* @return The nominal data rate of the interface in bit per second, 0 if unknown * @return The nominal data rate of the interface in bit per second, 0 if unknown
**/ **/
virtual qint64 getNominalDataRate() const = 0; virtual qint64 getConnectionSpeed() const = 0;
/**
* @Brief Get the current incoming data rate.
*
* This should be over a short timespan, something like 100ms. A precise value isn't necessary,
* and this can be filtered, but should be a reasonable estimate of current data rate.
*
* @return The data rate of the interface in bits per second, 0 if unknown
**/
virtual qint64 getCurrentInDataRate() const = 0;
/**
* @Brief Get the current outgoing data rate.
*
* This should be over a short timespan, something like 100ms. A precise value isn't necessary,
* and this can be filtered, but should be a reasonable estimate of current data rate.
*
* @return The data rate of the interface in bits per second, 0 if unknown
**/
virtual qint64 getCurrentOutDataRate() const = 0;
/** /**
* @brief Connect this interface logically * @brief Connect this interface logically
......
...@@ -1000,8 +1000,18 @@ QString MAVLinkSimulationLink::getName() const ...@@ -1000,8 +1000,18 @@ QString MAVLinkSimulationLink::getName() const
return name; return name;
} }
qint64 MAVLinkSimulationLink::getNominalDataRate() const qint64 MAVLinkSimulationLink::getConnectionSpeed() const
{ {
/* 100 Mbit is reasonable fast and sufficient for all embedded applications */ /* 100 Mbit is reasonable fast and sufficient for all embedded applications */
return 100000000; return 100000000;
} }
\ No newline at end of file
qint64 MAVLinkSimulationLink::getCurrentInDataRate() const
{
return 0;
}
qint64 MAVLinkSimulationLink::getCurrentOutDataRate() const
{
return 0;
}
...@@ -58,8 +58,10 @@ public: ...@@ -58,8 +58,10 @@ public:
bool connect(); bool connect();
bool disconnect(); bool disconnect();
/* Extensive statistics for scientific purposes */ // Extensive statistics for scientific purposes
qint64 getNominalDataRate() const; qint64 getConnectionSpeed() const;
qint64 getCurrentInDataRate() const;
qint64 getCurrentOutDataRate() const;
QString getName() const; QString getName() const;
int getId() const; int getId() const;
......
...@@ -496,16 +496,18 @@ bool OpalLink::disconnect() ...@@ -496,16 +496,18 @@ bool OpalLink::disconnect()
return true; return true;
} }
// Data rate functions
qint64 OpalLink::getConnectionSpeed() const
{
return 0; //unknown
}
qint64 OpalLink::getCurrentInDataRate() const
{
return 0;
}
qint64 OpalLink::getCurrentOutDataRate() const
/*
*
Statisctics
*
*/
qint64 OpalLink::getNominalDataRate() const
{ {
return 0; //unknown return 0;
} }
\ No newline at end of file
...@@ -75,10 +75,9 @@ public: ...@@ -75,10 +75,9 @@ public:
QString getName() const; QString getName() const;
bool isConnected() const; bool isConnected() const;
/* Connection characteristics */ qint64 getConnectionSpeed() const;
qint64 getCurrentInDataRate() const;
qint64 getCurrentOutDataRate() const;
qint64 getNominalDataRate() const;
bool connect(); bool connect();
......
...@@ -19,18 +19,26 @@ ...@@ -19,18 +19,26 @@
#include "QGC.h" #include "QGC.h"
#include <MG.h> #include <MG.h>
SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl, bool parity, SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl, bool parity,
int dataBits, int stopBits) : int dataBits, int stopBits) :
m_bytesRead(0), m_bytesRead(0),
m_port(NULL), m_port(NULL),
inDataIndex(0),
outDataIndex(0),
m_stopp(false), m_stopp(false),
m_reqReset(false) m_reqReset(false)
{ {
// Setup settings // Initialize our arrays manually, cause C++<03 is dumb.
m_portName = portname.trimmed(); for (int i = 0; i < buffer_size; ++i)
{
inDataWriteAmounts[i] = 0;
inDataWriteTimes[i] = 0;
outDataWriteAmounts[i] = 0;
outDataWriteTimes[i] = 0;
}
// Get the name of the current port in use.
m_portName = portname.trimmed();
if (m_portName == "" && getCurrentPorts().size() > 0) if (m_portName == "" && getCurrentPorts().size() > 0)
{ {
m_portName = m_ports.first().trimmed(); m_portName = m_ports.first().trimmed();
...@@ -69,6 +77,7 @@ SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl, ...@@ -69,6 +77,7 @@ SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl,
LinkManager::instance()->add(this); LinkManager::instance()->add(this);
} }
void SerialLink::requestReset() void SerialLink::requestReset()
{ {
QMutexLocker locker(&this->m_stoppMutex); QMutexLocker locker(&this->m_stoppMutex);
...@@ -184,7 +193,7 @@ void SerialLink::run() ...@@ -184,7 +193,7 @@ void SerialLink::run()
// Write all our buffered data out the serial port. // Write all our buffered data out the serial port.
if (m_transmitBuffer.count() > 0) { if (m_transmitBuffer.count() > 0) {
QMutexLocker writeLocker(&m_writeMutex); m_writeMutex.lock();
int numWritten = m_port->write(m_transmitBuffer); int numWritten = m_port->write(m_transmitBuffer);
bool txSuccess = m_port->waitForBytesWritten(5); bool txSuccess = m_port->waitForBytesWritten(5);
if (!txSuccess || (numWritten != m_transmitBuffer.count())) { if (!txSuccess || (numWritten != m_transmitBuffer.count())) {
...@@ -196,25 +205,41 @@ void SerialLink::run() ...@@ -196,25 +205,41 @@ void SerialLink::run()
// Since we were successful, reset out error counter. // Since we were successful, reset out error counter.
linkErrorCount = 0; linkErrorCount = 0;
} }
m_transmitBuffer = m_transmitBuffer.remove(0, numWritten);
// Now that we transmit all of the data in the transmit buffer, flush it.
m_transmitBuffer = m_transmitBuffer.remove(0, numWritten);
m_writeMutex.unlock();
// Log this written data for this timestep. If this value ends up being 0 due to
// write() failing, that's what we want as well.
QMutexLocker statsLocker(&m_statisticsMutex);
WriteDataStatsBuffer(outDataWriteAmounts, outDataWriteTimes, &outDataIndex, numWritten, QDateTime::currentMSecsSinceEpoch());
} }
//wait n msecs for data to be ready //wait n msecs for data to be ready
//[TODO][BB] lower to SerialLink::poll_interval? //[TODO][BB] lower to SerialLink::poll_interval?
m_dataMutex.lock();
bool success = m_port->waitForReadyRead(10); bool success = m_port->waitForReadyRead(10);
if (success) { if (success) {
QByteArray readData = m_port->readAll(); QByteArray readData = m_port->readAll();
while (m_port->waitForReadyRead(10)) while (m_port->waitForReadyRead(10))
readData += m_port->readAll(); readData += m_port->readAll();
m_dataMutex.unlock();
if (readData.length() > 0) { if (readData.length() > 0) {
emit bytesReceived(this, readData); emit bytesReceived(this, readData);
// Log this data reception for this timestep
QMutexLocker statsLocker(&m_statisticsMutex);
WriteDataStatsBuffer(inDataWriteAmounts, inDataWriteTimes, &inDataIndex, readData.length(), QDateTime::currentMSecsSinceEpoch());
// Track the total amount of data read.
m_bytesRead += readData.length(); m_bytesRead += readData.length();
linkErrorCount = 0; linkErrorCount = 0;
} }
} }
else { else {
m_dataMutex.unlock();
linkErrorCount++; linkErrorCount++;
} }
...@@ -268,18 +293,31 @@ void SerialLink::run() ...@@ -268,18 +293,31 @@ void SerialLink::run()
} }
} }
void SerialLink::WriteDataStatsBuffer(quint64 *bytesBuffer, qint64 *timeBuffer, int *writeIndex, quint64 bytes, qint64 time)
{
int i = *writeIndex;
// Now write into the buffer, if there's no room, we just overwrite the first data point.
bytesBuffer[i] = bytes;
timeBuffer[i] = time;
// Increment and wrap the write index
++i;
if (i == buffer_size)
{
i = 0;
}
*writeIndex = i;
}
void SerialLink::writeBytes(const char* data, qint64 size) void SerialLink::writeBytes(const char* data, qint64 size)
{ {
if(m_port && m_port->isOpen()) { if(m_port && m_port->isOpen()) {
QByteArray byteArray(data, size); QByteArray byteArray(data, size);
{ m_writeMutex.lock();
QMutexLocker writeLocker(&m_writeMutex); m_transmitBuffer.append(byteArray);
m_transmitBuffer.append(byteArray); m_writeMutex.unlock();
}
// Extra debug logging
// qDebug() << byteArray->toHex();
} else { } else {
disconnect(); disconnect();
// Error occured // Error occured
...@@ -295,10 +333,10 @@ void SerialLink::writeBytes(const char* data, qint64 size) ...@@ -295,10 +333,10 @@ void SerialLink::writeBytes(const char* data, qint64 size)
**/ **/
void SerialLink::readBytes() void SerialLink::readBytes()
{ {
m_dataMutex.lock();
if(m_port && m_port->isOpen()) { if(m_port && m_port->isOpen()) {
const qint64 maxLength = 2048; const qint64 maxLength = 2048;
char data[maxLength]; char data[maxLength];
m_dataMutex.lock();
qint64 numBytes = m_port->bytesAvailable(); qint64 numBytes = m_port->bytesAvailable();
if(numBytes > 0) { if(numBytes > 0) {
...@@ -309,8 +347,8 @@ void SerialLink::readBytes() ...@@ -309,8 +347,8 @@ void SerialLink::readBytes()
QByteArray b(data, numBytes); QByteArray b(data, numBytes);
emit bytesReceived(this, b); emit bytesReceived(this, b);
} }
m_dataMutex.unlock();
} }
m_dataMutex.unlock();
} }
...@@ -473,7 +511,7 @@ QString SerialLink::getName() const ...@@ -473,7 +511,7 @@ QString SerialLink::getName() const
* This function maps baud rate constants to numerical equivalents. * This function maps baud rate constants to numerical equivalents.
* It relies on the mapping given in qportsettings.h from the QSerialPort library. * It relies on the mapping given in qportsettings.h from the QSerialPort library.
*/ */
qint64 SerialLink::getNominalDataRate() const qint64 SerialLink::getConnectionSpeed() const
{ {
int baudRate; int baudRate;
if (m_port) { if (m_port) {
...@@ -517,6 +555,94 @@ qint64 SerialLink::getNominalDataRate() const ...@@ -517,6 +555,94 @@ qint64 SerialLink::getNominalDataRate() const
return dataRate; return dataRate;
} }
qint64 SerialLink::getCurrentOutDataRate() const
{
const qint64 now = QDateTime::currentMSecsSinceEpoch();
// Limit the time we calculate to the recent past
const qint64 cutoff = now - stats_timespan;
// Grab the mutex for working with the stats variables
QMutexLocker statsLocker(&m_statisticsMutex);
// Now iterate through the buffer of all received data packets adding up all values
// within now and our cutof.
int index = outDataIndex;
qint64 totalBytes = 0;
qint64 totalTime = 0;
qint64 lastTime = 0;
int size = buffer_size;
while (size-- > 0)
{
// If this data is within our cutoff time, include it in our calculations.
// This also accounts for when the buffer is empty and filled with 0-times.
if (outDataWriteTimes[index] > cutoff && lastTime > 0) {
// Track the total time, using the previous time as our timeperiod.
totalTime += outDataWriteTimes[index] - lastTime;
totalBytes += outDataWriteAmounts[index];
}
// Track the last time sample for doing timespan calculations
lastTime = outDataWriteTimes[index];
// Increment and wrap the index if necessary.
if (++index == buffer_size)
{
index = 0;
}
}
// Return the final calculated value in bits / s, converted from bytes/ms.
qint64 dataRate = (totalTime != 0)?(qint64)((float)totalBytes * 8.0f / ((float)totalTime / 1000.0f)):0;
// Finally return our calculated data rate.
return dataRate;
}
qint64 SerialLink::getCurrentInDataRate() const
{
const qint64 now = QDateTime::currentMSecsSinceEpoch();
// Limit the time we calculate to the recent past
const qint64 cutoff = now - stats_timespan;
// Grab the mutex for working with the stats variables
QMutexLocker statsLocker(&m_statisticsMutex);
// Now iterate through the buffer of all received data packets adding up all values
// within now and our cutof.
int index = inDataIndex;
qint64 totalBytes = 0;
qint64 totalTime = 0;
qint64 lastTime = 0;
int size = buffer_size;
while (size-- > 0)
{
// If this data is within our cutoff time, include it in our calculations.
// This also accounts for when the buffer is empty and filled with 0-times.
if (inDataWriteTimes[index] > cutoff && lastTime > 0) {
// Track the total time, using the previous time as our timeperiod.
totalTime += inDataWriteTimes[index] - lastTime;
totalBytes += inDataWriteAmounts[index];
}
// Track the last time sample for doing timespan calculations
lastTime = inDataWriteTimes[index];
// Increment and wrap the index if necessary.
if (++index == buffer_size)
{
index = 0;
}
}
// Return the final calculated value in bits / s, converted from bytes/ms.
qint64 dataRate = (totalTime != 0)?(qint64)((float)totalBytes * 8.0f / ((float)totalTime / 1000.0f)):0;
// Finally return our calculated data rate.
return dataRate;
}
QString SerialLink::getPortName() const QString SerialLink::getPortName() const
{ {
return m_portName; return m_portName;
...@@ -526,7 +652,7 @@ QString SerialLink::getPortName() const ...@@ -526,7 +652,7 @@ QString SerialLink::getPortName() const
int SerialLink::getBaudRate() const int SerialLink::getBaudRate() const
{ {
return getNominalDataRate(); return getConnectionSpeed();
} }
int SerialLink::getBaudRateType() const int SerialLink::getBaudRateType() const
......
...@@ -68,6 +68,10 @@ public: ...@@ -68,6 +68,10 @@ public:
static const int poll_interval = SERIAL_POLL_INTERVAL; ///< Polling interval, defined in configuration.h static const int poll_interval = SERIAL_POLL_INTERVAL; ///< Polling interval, defined in configuration.h
static const int buffer_size = 20; ///< Specify how many data points to capture for data rate calculations.
static const qint64 stats_timespan = 500; ///< Set the maximum age of samples to use for data calculations (ms).
/** @brief Get a list of the currently available ports */ /** @brief Get a list of the currently available ports */
QList<QString> getCurrentPorts(); QList<QString> getCurrentPorts();
...@@ -95,8 +99,9 @@ public: ...@@ -95,8 +99,9 @@ public:
int getDataBitsType() const; int getDataBitsType() const;
int getStopBitsType() const; int getStopBitsType() const;
/* Extensive statistics for scientific purposes */ qint64 getConnectionSpeed() const;
qint64 getNominalDataRate() const; qint64 getCurrentInDataRate() const;
qint64 getCurrentOutDataRate() const;
void loadSettings(); void loadSettings();
void writeSettings(); void writeSettings();
...@@ -147,19 +152,45 @@ protected: ...@@ -147,19 +152,45 @@ protected:
int m_stopBits; int m_stopBits;
int m_parity; int m_parity;
QString m_portName; QString m_portName;
// QString m_name;
int m_timeout; int m_timeout;
int m_id; int m_id;
// Implement a simple circular buffer for storing when and how much data was received.
QMutex m_dataMutex; // Used for calculating the incoming data rate. Use with *StatsBuffer() functions.
QMutex m_writeMutex; int inDataIndex;
quint64 inDataWriteAmounts[buffer_size]; // In bytes
qint64 inDataWriteTimes[buffer_size]; // in ms
// Implement a simple circular buffer for storing when and how much data was transmit.
// Used for calculating the outgoing data rate. Use with *StatsBuffer() functions.
int outDataIndex;
quint64 outDataWriteAmounts[buffer_size]; // In bytes
qint64 outDataWriteTimes[buffer_size]; // in ms
quint64 m_connectionStartTime; // Connection start time (ms since epoch)
mutable QMutex m_statisticsMutex; // Mutex for accessing the statistics member variables (inData*,outData*,bitsSent,bitsReceived)
QMutex m_dataMutex; // Mutex for reading data from m_port
QMutex m_writeMutex; // Mutex for accessing the m_transmitBuffer.
QList<QString> m_ports; QList<QString> m_ports;
private: private:
/**
* @brief WriteDataStatsBuffer Stores transmission times/amounts for statistics
*
* This function logs the send times and amounts of datas to the given circular buffers.
* This data is used for calculating the transmission rate.
*
* @param bytesBuffer The buffer to write the bytes value into.
* @param timeBuffer The buffer to write the time value into
* @param writeIndex The write index used for this buffer.
* @param bytes The amount of bytes transmit.
* @param time The time (in ms) this transmission occurred.
*/
void WriteDataStatsBuffer(quint64 *bytesBuffer, qint64 *timeBuffer, int *writeIndex, quint64 bytes, qint64 time);
volatile bool m_stopp; volatile bool m_stopp;
volatile bool m_reqReset; volatile bool m_reqReset;
QMutex m_stoppMutex; QMutex m_stoppMutex; // Mutex for accessing m_stopp
QByteArray m_transmitBuffer; QByteArray m_transmitBuffer; // An internal buffer for receiving data from member functions and actually transmitting them via the serial port.
bool hardwareConnect(); bool hardwareConnect();
......
...@@ -262,7 +262,17 @@ void TCPLink::setName(QString name) ...@@ -262,7 +262,17 @@ void TCPLink::setName(QString name)
} }
qint64 TCPLink::getNominalDataRate() const qint64 TCPLink::getConnectionSpeed() const
{ {
return 54000000; // 54 Mbit return 54000000; // 54 Mbit
} }
\ No newline at end of file
qint64 TCPLink::getCurrentInDataRate() const
{
return 0;
}
qint64 TCPLink::getCurrentOutDataRate() const
{
return 0;
}
...@@ -68,9 +68,11 @@ public: ...@@ -68,9 +68,11 @@ public:
int getParityType() const; int getParityType() const;
int getDataBitsType() const; int getDataBitsType() const;
int getStopBitsType() const; int getStopBitsType() const;
/* Extensive statistics for scientific purposes */ // Extensive statistics for scientific purposes
qint64 getNominalDataRate() const; qint64 getConnectionSpeed() const;
qint64 getCurrentInDataRate() const;
qint64 getCurrentOutDataRate() const;
void run(); void run();
......
...@@ -376,7 +376,17 @@ void UDPLink::setName(QString name) ...@@ -376,7 +376,17 @@ void UDPLink::setName(QString name)
} }
qint64 UDPLink::getNominalDataRate() const qint64 UDPLink::getConnectionSpeed() const
{ {
return 54000000; // 54 Mbit return 54000000; // 54 Mbit
} }
\ No newline at end of file
qint64 UDPLink::getCurrentInDataRate() const
{
return 0;
}
qint64 UDPLink::getCurrentOutDataRate() const
{
return 0;
}
...@@ -71,8 +71,10 @@ public: ...@@ -71,8 +71,10 @@ public:
return hosts; return hosts;
} }
/* Extensive statistics for scientific purposes */ // Extensive statistics for scientific purposes
qint64 getNominalDataRate() const; qint64 getConnectionSpeed() const;
qint64 getCurrentInDataRate() const;
qint64 getCurrentOutDataRate() const;
void run(); void run();
......
...@@ -119,10 +119,21 @@ bool XbeeLink::isConnected() const ...@@ -119,10 +119,21 @@ bool XbeeLink::isConnected() const
return this->m_connected; return this->m_connected;
} }
qint64 XbeeLink::getNominalDataRate() const qint64 XbeeLink::getConnectionSpeed() const
{ {
return this->m_baudRate; return this->m_baudRate;
} }
qint64 XbeeLink::getCurrentInDataRate() const
{
return 0;
}
qint64 XbeeLink::getCurrentOutDataRate() const
{
return 0;
}
bool XbeeLink::hardwareConnect() bool XbeeLink::hardwareConnect()
{ {
emit tryConnectBegin(true); emit tryConnectBegin(true);
...@@ -245,4 +256,4 @@ void CALLTYPE XbeeLink::portCallback(xbee_con *xbeeCon, xbee_pkt *XbeePkt) ...@@ -245,4 +256,4 @@ void CALLTYPE XbeeLink::portCallback(xbee_con *xbeeCon, xbee_pkt *XbeePkt)
buf.push_back(XbeePkt->data[i]); buf.push_back(XbeePkt->data[i]);
} }
emit bytesReceived(this, buf); emit bytesReceived(this, buf);
}*/ }*/
\ No newline at end of file
...@@ -34,11 +34,15 @@ public: // virtual functions from LinkInterface ...@@ -34,11 +34,15 @@ public: // virtual functions from LinkInterface
int getId() const; int getId() const;
QString getName() const; QString getName() const;
bool isConnected() const; bool isConnected() const;
qint64 getNominalDataRate() const;
bool connect(); bool connect();
bool disconnect(); bool disconnect();
qint64 bytesAvailable(); qint64 bytesAvailable();
// Extensive statistics for scientific purposes
qint64 getConnectionSpeed() const;
qint64 getCurrentOutDataRate() const;
qint64 getCurrentInDataRate() const;
public slots: // virtual functions from LinkInterface public slots: // virtual functions from LinkInterface
void writeBytes(const char *bytes, qint64 length); void writeBytes(const char *bytes, qint64 length);
......
...@@ -326,7 +326,7 @@ void DebugConsole::updateTrafficMeasurements() ...@@ -326,7 +326,7 @@ void DebugConsole::updateTrafficMeasurements()
} }
// Update the rate label. // Update the rate label.
m_ui->downSpeedLabel->setText(tr("%L1 kB/s").arg(lowpassDataRate, 4, 'f', 1)); m_ui->downSpeedLabel->setText(tr("%L1 kB/s").arg(lowpassDataRate, 4, 'f', 1, '0'));
} }
void DebugConsole::paintEvent(QPaintEvent *event) void DebugConsole::paintEvent(QPaintEvent *event)
......
...@@ -204,7 +204,7 @@ void APMToolBar::updateLinkDisplay(LinkInterface* newLink) ...@@ -204,7 +204,7 @@ void APMToolBar::updateLinkDisplay(LinkInterface* newLink)
QObject *object = rootObject(); QObject *object = rootObject();
if (newLink && object){ if (newLink && object){
qint64 baudrate = newLink->getNominalDataRate(); qint64 baudrate = newLink->getConnectionSpeed();
object->setProperty("baudrateLabel", QString::number(baudrate)); object->setProperty("baudrateLabel", QString::number(baudrate));
QString linkName = newLink->getName(); QString linkName = newLink->getName();
......
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