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
144ef965
Commit
144ef965
authored
Dec 22, 2013
by
Bryant Mairs
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Removed various bits of dead code.
parent
0fe7fa8d
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
8 additions
and
76 deletions
+8
-76
SerialLink.cc
src/comm/SerialLink.cc
+6
-16
DebugConsole.cc
src/ui/DebugConsole.cc
+2
-60
No files found.
src/comm/SerialLink.cc
View file @
144ef965
...
...
@@ -157,9 +157,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 +174,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,6 +182,7 @@ void SerialLink::run()
disconnect
();
}
// Write all our buffered data out the serial port.
if
(
m_transmitBuffer
.
count
()
>
0
)
{
QMutexLocker
writeLocker
(
&
m_writeMutex
);
int
numWritten
=
m_port
->
write
(
m_transmitBuffer
);
...
...
@@ -190,6 +192,8 @@ 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
);
...
...
@@ -205,7 +209,6 @@ void SerialLink::run()
readData
+=
m_port
->
readAll
();
if
(
readData
.
length
()
>
0
)
{
emit
bytesReceived
(
this
,
readData
);
// qDebug() << "rx of length " << QString::number(readData.length());
m_bytesRead
+=
readData
.
length
();
linkErrorCount
=
0
;
...
...
@@ -213,7 +216,6 @@ void SerialLink::run()
}
else
{
linkErrorCount
++
;
//qDebug() << "Wait read response timeout" << QTime::currentTime().toString();
}
if
(
bytes
!=
m_bytesRead
)
{
// i.e things are good and data is being read.
...
...
@@ -269,7 +271,6 @@ void SerialLink::run()
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
);
{
...
...
@@ -299,7 +300,6 @@ void SerialLink::readBytes()
const
qint64
maxLength
=
2048
;
char
data
[
maxLength
];
qint64
numBytes
=
m_port
->
bytesAvailable
();
//qDebug() << "numBytes: " << numBytes;
if
(
numBytes
>
0
)
{
/* Read as much data in buffer as possible without overflow */
...
...
@@ -308,15 +308,6 @@ 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
();
...
...
@@ -654,7 +645,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/ui/DebugConsole.cc
View file @
144ef965
...
...
@@ -78,13 +78,8 @@ 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 the DebugConsole
loadSettings
();
// Enable traffic measurements
...
...
@@ -155,13 +150,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 +164,6 @@ void DebugConsole::storeSettings()
settings
.
setValue
(
"AUTO_HOLD_ENABLED"
,
autoHold
);
settings
.
endGroup
();
settings
.
sync
();
//qDebug() << "Storing settings!";
}
void
DebugConsole
::
uasCreated
(
UASInterface
*
uas
)
...
...
@@ -205,7 +192,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
);
...
...
@@ -250,7 +236,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
));
...
...
@@ -344,38 +329,9 @@ void DebugConsole::updateTrafficMeasurements()
m_ui
->
downSpeedLabel
->
setText
(
tr
(
"%L1 kB/s"
).
arg
(
lowpassDataRate
,
4
,
'f'
,
1
));
}
//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
)
...
...
@@ -428,7 +384,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
...
...
@@ -436,7 +391,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
...
...
@@ -483,7 +438,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
);
...
...
@@ -514,8 +468,6 @@ void DebugConsole::receiveBytes(LinkInterface* link, QByteArray bytes)
else
{
if
(
filterMAVLINK
)
this
->
bytesToIgnore
--
;
// Constrain bytes to positive range
// bytesToIgnore = qMax(0, bytesToIgnore);
}
}
...
...
@@ -599,7 +551,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
)
...
...
@@ -705,7 +656,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
(
" "
);
...
...
@@ -722,16 +672,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
);
...
...
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