Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
6caef012
Commit
6caef012
authored
Dec 22, 2013
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #437 from Susurrus/simpleCheckRates
Add display of the upstream data rate to the Debug Console
parents
17883dbb
03e904d5
Changes
17
Hide whitespace changes
Inline
Side-by-side
Showing
17 changed files
with
412 additions
and
173 deletions
+412
-173
LinkInterface.h
src/comm/LinkInterface.h
+22
-2
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+12
-2
MAVLinkSimulationLink.h
src/comm/MAVLinkSimulationLink.h
+4
-2
OpalLink.cc
src/comm/OpalLink.cc
+12
-10
OpalLink.h
src/comm/OpalLink.h
+3
-4
SerialLink.cc
src/comm/SerialLink.cc
+149
-33
SerialLink.h
src/comm/SerialLink.h
+39
-8
TCPLink.cc
src/comm/TCPLink.cc
+12
-2
TCPLink.h
src/comm/TCPLink.h
+5
-3
UDPLink.cc
src/comm/UDPLink.cc
+12
-2
UDPLink.h
src/comm/UDPLink.h
+4
-2
XbeeLink.cpp
src/comm/XbeeLink.cpp
+13
-2
XbeeLink.h
src/comm/XbeeLink.h
+5
-1
DebugConsole.cc
src/ui/DebugConsole.cc
+44
-89
DebugConsole.h
src/ui/DebugConsole.h
+4
-5
DebugConsole.ui
src/ui/DebugConsole.ui
+71
-5
apmtoolbar.cpp
src/ui/apmtoolbar.cpp
+1
-1
No files found.
src/comm/LinkInterface.h
View file @
6caef012
...
...
@@ -73,7 +73,7 @@ public:
/* 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
* interface. For 100Base-T Ethernet this would be 100 Mbit/s (100'000'000
...
...
@@ -81,7 +81,27 @@ public:
*
* @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
...
...
src/comm/MAVLinkSimulationLink.cc
View file @
6caef012
...
...
@@ -1000,8 +1000,18 @@ QString MAVLinkSimulationLink::getName() const
return
name
;
}
qint64
MAVLinkSimulationLink
::
get
NominalDataRate
()
const
qint64
MAVLinkSimulationLink
::
get
ConnectionSpeed
()
const
{
/* 100 Mbit is reasonable fast and sufficient for all embedded applications */
return
100000000
;
}
\ No newline at end of file
}
qint64
MAVLinkSimulationLink
::
getCurrentInDataRate
()
const
{
return
0
;
}
qint64
MAVLinkSimulationLink
::
getCurrentOutDataRate
()
const
{
return
0
;
}
src/comm/MAVLinkSimulationLink.h
View file @
6caef012
...
...
@@ -58,8 +58,10 @@ public:
bool
connect
();
bool
disconnect
();
/* Extensive statistics for scientific purposes */
qint64
getNominalDataRate
()
const
;
// Extensive statistics for scientific purposes
qint64
getConnectionSpeed
()
const
;
qint64
getCurrentInDataRate
()
const
;
qint64
getCurrentOutDataRate
()
const
;
QString
getName
()
const
;
int
getId
()
const
;
...
...
src/comm/OpalLink.cc
View file @
6caef012
...
...
@@ -496,16 +496,18 @@ bool OpalLink::disconnect()
return
true
;
}
// Data rate functions
qint64
OpalLink
::
getConnectionSpeed
()
const
{
return
0
;
//unknown
}
qint64
OpalLink
::
getCurrentInDataRate
()
const
{
return
0
;
}
/*
*
Statisctics
*
*/
qint64
OpalLink
::
getNominalDataRate
()
const
qint64
OpalLink
::
getCurrentOutDataRate
()
const
{
return
0
;
//unknown
}
\ No newline at end of file
return
0
;
}
src/comm/OpalLink.h
View file @
6caef012
...
...
@@ -75,10 +75,9 @@ public:
QString
getName
()
const
;
bool
isConnected
()
const
;
/* Connection characteristics */
qint64
getNominalDataRate
()
const
;
qint64
getConnectionSpeed
()
const
;
qint64
getCurrentInDataRate
()
const
;
qint64
getCurrentOutDataRate
()
const
;
bool
connect
();
...
...
src/comm/SerialLink.cc
View file @
6caef012
...
...
@@ -19,18 +19,26 @@
#include "QGC.h"
#include <MG.h>
SerialLink
::
SerialLink
(
QString
portname
,
int
baudRate
,
bool
hardwareFlowControl
,
bool
parity
,
int
dataBits
,
int
stopBits
)
:
m_bytesRead
(
0
),
m_port
(
NULL
),
inDataIndex
(
0
),
outDataIndex
(
0
),
m_stopp
(
false
),
m_reqReset
(
false
)
{
// Setup settings
m_portName
=
portname
.
trimmed
();
// Initialize our arrays manually, cause C++<03 is dumb.
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
)
{
m_portName
=
m_ports
.
first
().
trimmed
();
...
...
@@ -69,6 +77,7 @@ SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl,
LinkManager
::
instance
()
->
add
(
this
);
}
void
SerialLink
::
requestReset
()
{
QMutexLocker
locker
(
&
this
->
m_stoppMutex
);
...
...
@@ -157,9 +166,9 @@ void SerialLink::run()
qint64
timeout
=
5000
;
int
linkErrorCount
=
0
;
forever
{
forever
{
{
QMutexLocker
locker
(
&
this
->
m_stoppMutex
);
QMutexLocker
locker
(
&
this
->
m_stoppMutex
);
if
(
m_stopp
)
{
m_stopp
=
false
;
break
;
// exit the thread
...
...
@@ -174,6 +183,7 @@ void SerialLink::run()
}
}
// If there are too many errors on this link, disconnect.
if
(
isConnected
()
&&
(
linkErrorCount
>
1000
))
{
qDebug
()
<<
"linkErrorCount too high: disconnecting!"
;
linkErrorCount
=
0
;
...
...
@@ -181,8 +191,9 @@ void SerialLink::run()
disconnect
();
}
// Write all our buffered data out the serial port.
if
(
m_transmitBuffer
.
count
()
>
0
)
{
QMutexLocker
writeLocker
(
&
m_writeMutex
);
m_writeMutex
.
lock
(
);
int
numWritten
=
m_port
->
write
(
m_transmitBuffer
);
bool
txSuccess
=
m_port
->
waitForBytesWritten
(
5
);
if
(
!
txSuccess
||
(
numWritten
!=
m_transmitBuffer
.
count
()))
{
...
...
@@ -190,30 +201,46 @@ void SerialLink::run()
qDebug
()
<<
"TX Error! wrote"
<<
numWritten
<<
", asked for "
<<
m_transmitBuffer
.
count
()
<<
"bytes"
;
}
else
{
// Since we were successful, reset out error counter.
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
//[TODO][BB] lower to SerialLink::poll_interval?
m_dataMutex
.
lock
();
bool
success
=
m_port
->
waitForReadyRead
(
10
);
if
(
success
)
{
QByteArray
readData
=
m_port
->
readAll
();
while
(
m_port
->
waitForReadyRead
(
10
))
readData
+=
m_port
->
readAll
();
m_dataMutex
.
unlock
();
if
(
readData
.
length
()
>
0
)
{
emit
bytesReceived
(
this
,
readData
);
// qDebug() << "rx of length " << QString::number(readData.length());
// 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
();
linkErrorCount
=
0
;
}
}
else
{
m_dataMutex
.
unlock
();
linkErrorCount
++
;
//qDebug() << "Wait read response timeout" << QTime::currentTime().toString();
}
if
(
bytes
!=
m_bytesRead
)
{
// i.e things are good and data is being read.
...
...
@@ -266,19 +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
)
{
if
(
m_port
&&
m_port
->
isOpen
())
{
// qDebug() << "writeBytes" << m_portName << "attempting to tx " << size << "bytes.";
QByteArray
byteArray
(
data
,
size
);
{
QMutexLocker
writeLocker
(
&
m_writeMutex
);
m_transmitBuffer
.
append
(
byteArray
);
}
// Extra debug logging
// qDebug() << byteArray->toHex();
m_writeMutex
.
lock
();
m_transmitBuffer
.
append
(
byteArray
);
m_writeMutex
.
unlock
();
}
else
{
disconnect
();
// Error occured
...
...
@@ -294,12 +333,11 @@ void SerialLink::writeBytes(const char* data, qint64 size)
**/
void
SerialLink
::
readBytes
()
{
m_dataMutex
.
lock
();
if
(
m_port
&&
m_port
->
isOpen
())
{
const
qint64
maxLength
=
2048
;
char
data
[
maxLength
];
m_dataMutex
.
lock
();
qint64
numBytes
=
m_port
->
bytesAvailable
();
//qDebug() << "numBytes: " << numBytes;
if
(
numBytes
>
0
)
{
/* Read as much data in buffer as possible without overflow */
...
...
@@ -308,18 +346,9 @@ void SerialLink::readBytes()
m_port
->
read
(
data
,
numBytes
);
QByteArray
b
(
data
,
numBytes
);
emit
bytesReceived
(
this
,
b
);
//qDebug() << "SerialLink::readBytes()" << std::hex << data;
// int i;
// for (i=0; i<numBytes; i++){
// unsigned int v=data[i];
//
// fprintf(stderr,"%02x ", v);
// }
// fprintf(stderr,"\n");
}
m_dataMutex
.
unlock
();
}
m_dataMutex
.
unlock
();
}
...
...
@@ -482,7 +511,7 @@ QString SerialLink::getName() const
* This function maps baud rate constants to numerical equivalents.
* It relies on the mapping given in qportsettings.h from the QSerialPort library.
*/
qint64
SerialLink
::
get
NominalDataRate
()
const
qint64
SerialLink
::
get
ConnectionSpeed
()
const
{
int
baudRate
;
if
(
m_port
)
{
...
...
@@ -526,6 +555,94 @@ qint64 SerialLink::getNominalDataRate() const
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.0
f
/
((
float
)
totalTime
/
1000.0
f
))
:
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.0
f
/
((
float
)
totalTime
/
1000.0
f
))
:
0
;
// Finally return our calculated data rate.
return
dataRate
;
}
QString
SerialLink
::
getPortName
()
const
{
return
m_portName
;
...
...
@@ -535,7 +652,7 @@ QString SerialLink::getPortName() const
int
SerialLink
::
getBaudRate
()
const
{
return
get
NominalDataRate
();
return
get
ConnectionSpeed
();
}
int
SerialLink
::
getBaudRateType
()
const
...
...
@@ -654,7 +771,6 @@ bool SerialLink::setPortName(QString portName)
if
((
portName
!=
m_portName
)
&&
(
portName
.
trimmed
().
length
()
>
0
))
{
m_portName
=
portName
.
trimmed
();
// m_name = tr("serial port ") + portName.trimmed(); // [TODO] Do we need this?
if
(
m_port
)
m_port
->
setPortName
(
portName
);
...
...
src/comm/SerialLink.h
View file @
6caef012
...
...
@@ -68,6 +68,10 @@ public:
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 */
QList
<
QString
>
getCurrentPorts
();
...
...
@@ -95,8 +99,9 @@ public:
int
getDataBitsType
()
const
;
int
getStopBitsType
()
const
;
/* Extensive statistics for scientific purposes */
qint64
getNominalDataRate
()
const
;
qint64
getConnectionSpeed
()
const
;
qint64
getCurrentInDataRate
()
const
;
qint64
getCurrentOutDataRate
()
const
;
void
loadSettings
();
void
writeSettings
();
...
...
@@ -147,19 +152,45 @@ protected:
int
m_stopBits
;
int
m_parity
;
QString
m_portName
;
// QString m_name;
int
m_timeout
;
int
m_id
;
QMutex
m_dataMutex
;
QMutex
m_writeMutex
;
// Implement a simple circular buffer for storing when and how much data was received.
// Used for calculating the incoming data rate. Use with *StatsBuffer() functions.
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
;
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_reqReset
;
QMutex
m_stoppMutex
;
QByteArray
m_transmitBuffer
;
QMutex
m_stoppMutex
;
// Mutex for accessing m_stopp
QByteArray
m_transmitBuffer
;
// An internal buffer for receiving data from member functions and actually transmitting them via the serial port.
bool
hardwareConnect
();
...
...
src/comm/TCPLink.cc
View file @
6caef012
...
...
@@ -262,7 +262,17 @@ void TCPLink::setName(QString name)
}
qint64
TCPLink
::
get
NominalDataRate
()
const
qint64
TCPLink
::
get
ConnectionSpeed
()
const
{
return
54000000
;
// 54 Mbit
}
\ No newline at end of file
}
qint64
TCPLink
::
getCurrentInDataRate
()
const
{
return
0
;
}
qint64
TCPLink
::
getCurrentOutDataRate
()
const
{
return
0
;
}
src/comm/TCPLink.h
View file @
6caef012
...
...
@@ -68,9 +68,11 @@ public:
int
getParityType
()
const
;
int
getDataBitsType
()
const
;
int
getStopBitsType
()
const
;
/* Extensive statistics for scientific purposes */
qint64
getNominalDataRate
()
const
;
// Extensive statistics for scientific purposes
qint64
getConnectionSpeed
()
const
;
qint64
getCurrentInDataRate
()
const
;
qint64
getCurrentOutDataRate
()
const
;
void
run
();
...
...
src/comm/UDPLink.cc
View file @
6caef012
...
...
@@ -376,7 +376,17 @@ void UDPLink::setName(QString name)
}
qint64
UDPLink
::
get
NominalDataRate
()
const
qint64
UDPLink
::
get
ConnectionSpeed
()
const
{
return
54000000
;
// 54 Mbit
}
\ No newline at end of file
}
qint64
UDPLink
::
getCurrentInDataRate
()
const
{
return
0
;
}
qint64
UDPLink
::
getCurrentOutDataRate
()
const
{
return
0
;
}
src/comm/UDPLink.h
View file @
6caef012
...
...
@@ -71,8 +71,10 @@ public:
return
hosts
;
}
/* Extensive statistics for scientific purposes */
qint64
getNominalDataRate
()
const
;
// Extensive statistics for scientific purposes
qint64
getConnectionSpeed
()
const
;
qint64
getCurrentInDataRate
()
const
;
qint64
getCurrentOutDataRate
()
const
;
void
run
();
...
...
src/comm/XbeeLink.cpp
View file @
6caef012
...
...
@@ -119,10 +119,21 @@ bool XbeeLink::isConnected() const
return
this
->
m_connected
;
}
qint64
XbeeLink
::
get
NominalDataRate
()
const
qint64
XbeeLink
::
get
ConnectionSpeed
()
const
{
return
this
->
m_baudRate
;
}
qint64
XbeeLink
::
getCurrentInDataRate
()
const
{
return
0
;
}
qint64
XbeeLink
::
getCurrentOutDataRate
()
const
{
return
0
;
}
bool
XbeeLink
::
hardwareConnect
()
{
emit
tryConnectBegin
(
true
);
...
...
@@ -245,4 +256,4 @@ void CALLTYPE XbeeLink::portCallback(xbee_con *xbeeCon, xbee_pkt *XbeePkt)
buf.push_back(XbeePkt->data[i]);
}
emit bytesReceived(this, buf);
}*/
\ No newline at end of file
}*/
src/comm/XbeeLink.h
View file @
6caef012
...
...
@@ -34,11 +34,15 @@ public: // virtual functions from LinkInterface
int
getId
()
const
;
QString
getName
()
const
;
bool
isConnected
()
const
;
qint64
getNominalDataRate
()
const
;
bool
connect
();
bool
disconnect
();
qint64
bytesAvailable
();
// Extensive statistics for scientific purposes
qint64
getConnectionSpeed
()
const
;
qint64
getCurrentOutDataRate
()
const
;
qint64
getCurrentInDataRate
()
const
;
public
slots
:
// virtual functions from LinkInterface
void
writeBytes
(
const
char
*
bytes
,
qint64
length
);
...
...
src/ui/DebugConsole.cc
View file @
6caef012
...
...
@@ -23,7 +23,7 @@ This file is part of the QGROUNDCONTROL project
/**
* @file
* @brief
Implementation of DebugConsole
* @brief
This file implements the Debug Console, a serial console built-in to QGC.
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
...
...
@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project
#include <QPainter>
#include <QSettings>
#include <QScrollBar>
#include <QDebug>
#include "DebugConsole.h"
#include "ui_DebugConsole.h"
...
...
@@ -39,8 +40,6 @@ This file is part of the QGROUNDCONTROL project
#include "protocol.h"
#include "QGC.h"
#include <QDebug>
DebugConsole
::
DebugConsole
(
QWidget
*
parent
)
:
QWidget
(
parent
),
currLink
(
NULL
),
...
...
@@ -58,11 +57,8 @@ DebugConsole::DebugConsole(QWidget *parent) :
lastLineBuffer
(
0
),
lineBufferTimer
(),
snapShotTimer
(),
snapShotInterval
(
500
),
snapShotBytes
(
0
),
dataRate
(
0.0
f
),
lowpassDataRate
(
0.0
f
),
dataRateThreshold
(
400
),
lowpassInDataRate
(
0.0
f
),
lowpassOutDataRate
(
0.0
f
),
commandIndex
(
0
),
m_ui
(
new
Ui
::
DebugConsole
)
{
...
...
@@ -78,21 +74,14 @@ DebugConsole::DebugConsole(QWidget *parent) :
m_ui
->
receiveText
->
setMaximumBlockCount
(
500
);
// Allow to wrap everywhere
m_ui
->
receiveText
->
setWordWrapMode
(
QTextOption
::
WrapAnywhere
);
// // Set monospace font
// m_ui->receiveText->setFontFamily("Monospace");
// Enable 10 Hz output
//connect(&lineBufferTimer, SIGNAL(timeout()), this, SLOT(showData()));
//lineBufferTimer.setInterval(100); // 100 Hz
//lineBufferTimer.start();
// Load settings for this widget
loadSettings
();
// Enable traffic measurements
// Enable traffic measurements. We only start/stop the timer as our links change, as
// these calculations are dependent on the specific link.
connect
(
&
snapShotTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
updateTrafficMeasurements
()));
snapShotTimer
.
setInterval
(
snapShotInterval
);
snapShotTimer
.
start
();
// Update measurements the first time
updateTrafficMeasurements
();
// First connect management slots, then make sure to add all existing objects
// Connect to link manager to get notified about new links
...
...
@@ -155,13 +144,6 @@ void DebugConsole::loadSettings()
MAVLINKfilterEnabled
(
settings
.
value
(
"MAVLINK_FILTER_ENABLED"
,
filterMAVLINK
).
toBool
());
setAutoHold
(
settings
.
value
(
"AUTO_HOLD_ENABLED"
,
autoHold
).
toBool
());
settings
.
endGroup
();
// // Update visibility settings
// if (m_ui->specialCheckBox->isChecked())
// {
// m_ui->specialCheckBox->setVisible(true);
// m_ui->addSymbolButton->setVisible(false);
// }
}
void
DebugConsole
::
storeSettings
()
...
...
@@ -176,7 +158,6 @@ void DebugConsole::storeSettings()
settings
.
setValue
(
"AUTO_HOLD_ENABLED"
,
autoHold
);
settings
.
endGroup
();
settings
.
sync
();
//qDebug() << "Storing settings!";
}
void
DebugConsole
::
uasCreated
(
UASInterface
*
uas
)
...
...
@@ -205,7 +186,6 @@ void DebugConsole::addLink(LinkInterface* link)
void
DebugConsole
::
removeLink
(
LinkInterface
*
const
linkInterface
)
{
//LinkInterface* linkInterface = dynamic_cast<LinkInterface*>(link);
// Add link to link list
if
(
links
.
contains
(
linkInterface
))
{
int
linkIndex
=
links
.
indexOf
(
linkInterface
);
...
...
@@ -214,7 +194,14 @@ void DebugConsole::removeLink(LinkInterface* const linkInterface)
m_ui
->
linkComboBox
->
removeItem
(
linkIndex
);
}
if
(
linkInterface
==
currLink
)
currLink
=
NULL
;
// Now if this was the current link, clean up some stuff.
if
(
linkInterface
==
currLink
)
{
// Like disable the update time for the UI.
snapShotTimer
.
stop
();
currLink
=
NULL
;
}
}
void
DebugConsole
::
linkStatusUpdate
(
const
QString
&
name
,
const
QString
&
text
)
{
...
...
@@ -227,11 +214,14 @@ void DebugConsole::linkStatusUpdate(const QString& name,const QString& text)
void
DebugConsole
::
linkSelected
(
int
linkId
)
{
// Disconnect
if
(
currLink
)
{
if
(
currLink
)
{
disconnect
(
currLink
,
SIGNAL
(
bytesReceived
(
LinkInterface
*
,
QByteArray
)),
this
,
SLOT
(
receiveBytes
(
LinkInterface
*
,
QByteArray
)));
disconnect
(
currLink
,
SIGNAL
(
connected
(
bool
)),
this
,
SLOT
(
setConnectionState
(
bool
)));
disconnect
(
currLink
,
SIGNAL
(
communicationUpdate
(
QString
,
QString
)),
this
,
SLOT
(
linkStatusUpdate
(
QString
,
QString
)));
snapShotTimer
.
stop
();
}
// Clear data
m_ui
->
receiveText
->
clear
();
...
...
@@ -241,6 +231,7 @@ void DebugConsole::linkSelected(int linkId)
connect
(
currLink
,
SIGNAL
(
connected
(
bool
)),
this
,
SLOT
(
setConnectionState
(
bool
)));
connect
(
currLink
,
SIGNAL
(
communicationUpdate
(
QString
,
QString
)),
this
,
SLOT
(
linkStatusUpdate
(
QString
,
QString
)));
setConnectionState
(
currLink
->
isConnected
());
snapShotTimer
.
start
();
}
/**
...
...
@@ -250,7 +241,6 @@ void DebugConsole::updateLinkName(QString name)
{
// Set name if signal came from a link
LinkInterface
*
link
=
qobject_cast
<
LinkInterface
*>
(
sender
());
//if (link != NULL) m_ui->linkComboBox->setItemText(link->getId(), name);
if
((
link
!=
NULL
)
&&
(
links
.
contains
(
link
)))
{
const
qint16
&
linkIndex
(
links
.
indexOf
(
link
));
...
...
@@ -326,65 +316,44 @@ void DebugConsole::receiveTextMessage(int id, int component, int severity, QStri
}
}
/**
* This function updates the speed indicator text in the GUI.
* Additionally, if this speed is too high, the display of incoming characters is disabled.
*/
void
DebugConsole
::
updateTrafficMeasurements
()
{
lowpassDataRate
=
lowpassDataRate
*
0.9
f
+
(
0.1
f
*
((
float
)
snapShotBytes
/
(
float
)
snapShotInterval
)
*
1000.0
f
);
dataRate
=
((
float
)
snapShotBytes
/
(
float
)
snapShotInterval
)
*
1000.0
f
;
snapShotBytes
=
0
;
// Check if limit has been exceeded
if
((
lowpassDataRate
>
dataRateThreshold
)
&&
autoHold
)
{
// Enable auto-old
// Calculate the rate of incoming data, converting to
// kilobytes per second from the received bits per second.
qint64
inDataRate
=
currLink
->
getCurrentInDataRate
()
/
1000.0
f
;
lowpassInDataRate
=
lowpassInDataRate
*
0.9
f
+
(
0.1
f
*
inDataRate
/
8.0
f
);
// If the incoming data rate is faster than our threshold, don't display the data.
// We don't use the low-passed data rate as we want the true data rate. The low-passed data
// is just for displaying to the user to remove jitter.
if
((
inDataRate
>
inDataRateThreshold
)
&&
autoHold
)
{
// Enable auto-hold
m_ui
->
holdButton
->
setChecked
(
true
);
hold
(
true
);
}
QString
speed
;
speed
=
speed
.
sprintf
(
"%04.1f kB/s"
,
dataRate
/
1000.0
f
);
m_ui
->
speedLabel
->
setText
(
speed
);
// Update the incoming data rate label.
m_ui
->
downSpeedLabel
->
setText
(
tr
(
"%L1 kB/s"
).
arg
(
lowpassInDataRate
,
4
,
'f'
,
1
,
'0'
));
if
(
holdOn
)
{
//repaint();
}
// Calculate the rate of outgoing data, converting to
// kilobytes per second from the received bits per second.
lowpassOutDataRate
=
lowpassOutDataRate
*
0.9
f
+
(
0.1
f
*
currLink
->
getCurrentOutDataRate
()
/
8.0
f
/
1000.0
f
);
// Update the outoing data rate label.
m_ui
->
upSpeedLabel
->
setText
(
tr
(
"%L1 kB/s"
).
arg
(
lowpassOutDataRate
,
4
,
'f'
,
1
,
'0'
));
}
//QPainter painter(m_ui->receiveText);
//painter.setRenderHint(QPainter::HighQualityAntialiasing);
//painter.translate((this->vwidth/2.0+xCenterOffset)*scalingFactor, (this->vheight/2.0+yCenterOffset)*scalingFactor);
void
DebugConsole
::
paintEvent
(
QPaintEvent
*
event
)
{
Q_UNUSED
(
event
);
// Update bandwidth
// if (holdOn)
// {
// //qDebug() << "Data rate:" << dataRate/1000.0f << "kB/s";
// QString rate("data rate: %1");
// rate.arg(dataRate);
// QPainter painter(this);
// painter.setRenderHint(QPainter::HighQualityAntialiasing);
// painter.translate(width()/5.0f, height()/5.0f);
// //QFont font("Bitstream Vera Sans");
// QFont font = painter.font();
// font.setPixelSize((int)(60.0f));
// QFontMetrics metrics = QFontMetrics(font);
// int border = qMax(4, metrics.leading());
// QRect rect = metrics.boundingRect(0, 0, width() - 2*border, int(height()*0.125),
// Qt::AlignLeft | Qt::TextWordWrap, rate);
// painter.setPen(QColor(255, 50, 50));
// painter.setRenderHint(QPainter::TextAntialiasing);
// painter.drawText(QRect(QPoint(static_cast<int>(width()/5.0f), static_cast<int>(height()/5.0f)), QPoint(static_cast<int>(width() - width()/5.0f), static_cast<int>(height() - height()/5.0f))), rate);
// //Qt::AlignRight | Qt::TextWordWrap
// }
}
void
DebugConsole
::
receiveBytes
(
LinkInterface
*
link
,
QByteArray
bytes
)
{
snapShotBytes
+=
bytes
.
size
();
int
len
=
bytes
.
size
();
int
lastSpace
=
0
;
if
((
this
->
bytesToIgnore
>
260
)
||
(
this
->
bytesToIgnore
<
-
2
))
this
->
bytesToIgnore
=
0
;
...
...
@@ -432,7 +401,6 @@ void DebugConsole::receiveBytes(LinkInterface* link, QByteArray bytes)
if
(
escIndex
<
static_cast
<
int
>
(
sizeof
(
escBytes
)))
{
escBytes
[
escIndex
]
=
byte
;
//qDebug() << "GOT BYTE ESC:" << byte;
if
(
/*escIndex == 1 && */
escBytes
[
escIndex
]
==
0x48
)
{
// Handle sequence
...
...
@@ -440,7 +408,7 @@ void DebugConsole::receiveBytes(LinkInterface* link, QByteArray bytes)
m_ui
->
receiveText
->
clear
();
escReceived
=
false
;
}
else
if
(
/*escIndex == 1 && */
escBytes
[
escIndex
]
==
0x4b
)
else
if
(
escBytes
[
escIndex
]
==
0x4b
)
{
// Handle sequence
// for this one, do nothing
...
...
@@ -487,7 +455,6 @@ void DebugConsole::receiveBytes(LinkInterface* link, QByteArray bytes)
// Do nothing for now
break
;
default:
// Append replacement character (box) if char is not ASCII
// str.append(QChar(QChar::ReplacementCharacter));
QString
str2
;
if
(
lastSpace
==
1
)
str2
.
sprintf
(
"0x%02x "
,
byte
);
...
...
@@ -518,8 +485,6 @@ void DebugConsole::receiveBytes(LinkInterface* link, QByteArray bytes)
else
{
if
(
filterMAVLINK
)
this
->
bytesToIgnore
--
;
// Constrain bytes to positive range
// bytesToIgnore = qMax(0, bytesToIgnore);
}
}
...
...
@@ -603,7 +568,6 @@ QString DebugConsole::bytesToSymbolNames(const QByteArray& b)
void
DebugConsole
::
specialSymbolSelected
(
const
QString
&
text
)
{
Q_UNUSED
(
text
);
//m_ui->specialCheckBox->setVisible(true);
}
void
DebugConsole
::
appendSpecialSymbol
(
const
QString
&
text
)
...
...
@@ -709,7 +673,6 @@ void DebugConsole::sendBytes()
if
(
okByte
)
{
// Feedback
//feedback.append("0x");
feedback
.
append
(
str
.
at
(
i
).
toUpper
());
feedback
.
append
(
str
.
at
(
i
+
1
).
toUpper
());
feedback
.
append
(
" "
);
...
...
@@ -726,16 +689,8 @@ void DebugConsole::sendBytes()
// Transmit ASCII or HEX formatted text, only if more than one symbol
if
(
ok
&&
m_ui
->
sendText
->
text
().
toLatin1
().
size
()
>
0
)
{
// Transmit only if conversion succeeded
// int transmitted =
currLink
->
writeBytes
(
transmit
,
transmit
.
size
());
// if (transmit.size() == transmitted)
// {
m_ui
->
sentText
->
setText
(
tr
(
"Sent: "
)
+
feedback
);
// }
// else
// {
// m_ui->sentText->setText(tr("Error during sending: Transmitted only %1 bytes instead of %2.").arg(transmitted, transmit.size()));
// }
}
else
if
(
m_ui
->
sendText
->
text
().
toLatin1
().
size
()
>
0
)
{
// Conversion failed, display error message
m_ui
->
sentText
->
setText
(
tr
(
"Not sent: "
)
+
feedback
);
...
...
@@ -787,7 +742,7 @@ void DebugConsole::hold(bool hold)
// TODO No conversion is done to the bytes in the hold buffer
m_ui
->
receiveText
->
appendPlainText
(
QString
(
holdBuffer
));
holdBuffer
.
clear
();
lowpassDataRate
=
0.0
f
;
lowpass
In
DataRate
=
0.0
f
;
}
this
->
holdOn
=
hold
;
...
...
src/ui/DebugConsole.h
View file @
6caef012
...
...
@@ -137,11 +137,10 @@ protected:
quint64
lastLineBuffer
;
///< Last line buffer emission time
QTimer
lineBufferTimer
;
///< Line buffer timer
QTimer
snapShotTimer
;
///< Timer for measuring traffic snapshots
int
snapShotInterval
;
///< Snapshot interval for traffic measurements
int
snapShotBytes
;
///< Number of bytes received in current snapshot
float
dataRate
;
///< Current data rate
float
lowpassDataRate
;
///< Lowpass filtered data rate
float
dataRateThreshold
;
///< Threshold where to enable auto-hold
static
const
int
snapShotInterval
=
500
;
///< Set the time between UI updates for the data rate (ms)
float
lowpassInDataRate
;
///< Lowpass filtered data rate (kilobytes/s)
static
const
float
inDataRateThreshold
=
0
.
4
;
///< Threshold where to enable auto-hold (kilobytes/s)
float
lowpassOutDataRate
;
///< Low-pass filtered outgoing data rate (kilobytes/s)
QStringList
commandHistory
;
QString
currCommand
;
int
commandIndex
;
...
...
src/ui/DebugConsole.ui
View file @
6caef012
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
5
66
</width>
<height>
190
</height>
<width>
5
70
</width>
<height>
211
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
...
...
@@ -24,7 +24,7 @@
<number>
6
</number>
</property>
<item
row=
"0"
column=
"0"
colspan=
"2"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_2"
stretch=
"10,0,0,0,0,0"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_2"
stretch=
"10,0,0,0,0,0
,0,0,0
"
>
<item>
<widget
class=
"QComboBox"
name=
"linkComboBox"
>
<property
name=
"maximumSize"
>
...
...
@@ -39,9 +39,75 @@
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"speedLabel"
>
<widget
class=
"QLabel"
name=
"downArrow"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Minimum"
vsizetype=
"Minimum"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"minimumSize"
>
<size>
<width>
12
</width>
<height>
16
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
12
</width>
<height>
16
</height>
</size>
</property>
<property
name=
"baseSize"
>
<size>
<width>
12
</width>
<height>
16
</height>
</size>
</property>
<property
name=
"autoFillBackground"
>
<bool>
false
</bool>
</property>
<property
name=
"text"
>
<string/>
</property>
<property
name=
"pixmap"
>
<pixmap
resource=
"../../qgroundcontrol.qrc"
>
:/files/images/actions/go-down.svg
</pixmap>
</property>
<property
name=
"scaledContents"
>
<bool>
true
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"downSpeedLabel"
>
<property
name=
"text"
>
<string>
00.0 kB/s
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"upArrow"
>
<property
name=
"maximumSize"
>
<size>
<width>
12
</width>
<height>
16
</height>
</size>
</property>
<property
name=
"text"
>
<string/>
</property>
<property
name=
"pixmap"
>
<pixmap
resource=
"../../qgroundcontrol.qrc"
>
:/files/images/actions/go-up.svg
</pixmap>
</property>
<property
name=
"scaledContents"
>
<bool>
true
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"upSpeedLabel"
>
<property
name=
"text"
>
<string>
0.0 kB/s
</string>
<string>
0
0
.0 kB/s
</string>
</property>
</widget>
</item>
...
...
src/ui/apmtoolbar.cpp
View file @
6caef012
...
...
@@ -204,7 +204,7 @@ void APMToolBar::updateLinkDisplay(LinkInterface* newLink)
QObject
*
object
=
rootObject
();
if
(
newLink
&&
object
){
qint64
baudrate
=
newLink
->
get
NominalDataRate
();
qint64
baudrate
=
newLink
->
get
ConnectionSpeed
();
object
->
setProperty
(
"baudrateLabel"
,
QString
::
number
(
baudrate
));
QString
linkName
=
newLink
->
getName
();
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment