Skip to content

Commit

Permalink
Added persistence to debug console
Browse files Browse the repository at this point in the history
  • Loading branch information
pixhawk-students committed Jan 26, 2011
1 parent 076e240 commit 6f367e7
Show file tree
Hide file tree
Showing 11 changed files with 131 additions and 30 deletions.
6 changes: 3 additions & 3 deletions images/earth.html
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@

}

function hideTrail(id)
function clearTrail(id)
{
trailsVisible[id] = false;
ge.getFeatures().removeChild(trailPlacemarks[id]);
Expand Down Expand Up @@ -253,9 +253,9 @@
// FIXME Currently invalid conversion from right-handed z-down to z-up frame
planeOrient.setRoll(((roll/M_PI))*180.0+180.0);
planeOrient.setTilt(((pitch/M_PI))*180.0+180.0);
planeOrient.setHeading(((yaw/M_PI))*180.0-90.0);
planeOrient.setHeading(((yaw/M_PI))*180.0-90.0+180.0);

currFollowHeading = ((yaw/M_PI))*180.0;
currFollowHeading = ((yaw/M_PI))*180.0+180.0;

planeLoc.setLatitude(lastLat);
planeLoc.setLongitude(lastLon);
Expand Down
21 changes: 21 additions & 0 deletions src/QGC.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@ This file is part of the QGROUNDCONTROL project

#include "QGC.h"

#include <qmath.h>

namespace QGC {

quint64 groundTimeUsecs()
Expand All @@ -34,6 +36,25 @@ quint64 groundTimeUsecs()
return static_cast<quint64>(microseconds + (time.time().msec()*1000));
}

double limitAngleToPMPI(double angle)
{
if (angle < -M_PI)
{
while (angle < -M_PI)
{
angle += M_PI;
}
}
else if (angle > M_PI)
{
while (angle > M_PI)
{
angle -= M_PI;
}
}
return angle;
}

int applicationVersion()
{
return APPLICATIONVERSION;
Expand Down
2 changes: 2 additions & 0 deletions src/QGC.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@ namespace QGC

/** @brief Get the current ground time in microseconds */
quint64 groundTimeUsecs();
/** @brief Returns the angle limited to -pi - pi */
double limitAngleToPMPI(double angle);
int applicationVersion();

const static int MAX_FLIGHT_TIME = 60 * 60 * 24 * 21;
Expand Down
5 changes: 1 addition & 4 deletions src/comm/MAVLinkProtocol.cc
Original file line number Diff line number Diff line change
Expand Up @@ -77,10 +77,7 @@ MAVLinkProtocol::~MAVLinkProtocol()

void MAVLinkProtocol::run()
{
forever
{
QGC::SLEEP::msleep(5000);
}
exec();
}

QString MAVLinkProtocol::getLogfileName()
Expand Down
1 change: 1 addition & 0 deletions src/comm/MAVLinkSimulationLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -959,6 +959,7 @@ bool MAVLinkSimulationLink::connect()
MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 47.376, 8.548);
MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2);
Q_UNUSED(mav1);
Q_UNUSED(mav2);
// timer->start(rate);
return true;
}
Expand Down
9 changes: 5 additions & 4 deletions src/comm/UDPLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -64,10 +64,11 @@ UDPLink::~UDPLink()
**/
void UDPLink::run()
{
forever
{
QGC::SLEEP::msleep(5000);
}
// forever
// {
// QGC::SLEEP::msleep(5000);
// }
exec();
}

void UDPLink::setAddress(QString address)
Expand Down
5 changes: 5 additions & 0 deletions src/uas/UAS.cc
Original file line number Diff line number Diff line change
Expand Up @@ -385,6 +385,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
roll = attitude.roll;
pitch = attitude.pitch;
yaw = attitude.yaw;

roll = QGC::limitAngleToPMPI(roll);
pitch = QGC::limitAngleToPMPI(pitch);
yaw = QGC::limitAngleToPMPI(yaw);

// emit valueChanged(uasId, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
// emit valueChanged(uasId, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
// emit valueChanged(uasId, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
Expand Down
9 changes: 5 additions & 4 deletions src/uas/UASManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -69,10 +69,11 @@ UASManager::~UASManager()

void UASManager::run()
{
forever
{
QGC::SLEEP::msleep(5000);
}
// forever
// {
// QGC::SLEEP::msleep(5000);
// }
exec();
}

void UASManager::addUAS(UASInterface* uas)
Expand Down
89 changes: 80 additions & 9 deletions src/ui/DebugConsole.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ This file is part of the QGROUNDCONTROL project
*
*/
#include <QPainter>
#include <QSettings>

#include "DebugConsole.h"
#include "ui_DebugConsole.h"
Expand All @@ -45,6 +46,7 @@ DebugConsole::DebugConsole(QWidget *parent) :
holdOn(false),
convertToAscii(true),
filterMAVLINK(false),
autoHold(true),
bytesToIgnore(0),
lastByte(-1),
sentBytes(),
Expand All @@ -57,7 +59,6 @@ DebugConsole::DebugConsole(QWidget *parent) :
dataRate(0.0f),
lowpassDataRate(0.0f),
dataRateThreshold(500),
autoHold(true),
commandIndex(0),
m_ui(new Ui::DebugConsole)
{
Expand Down Expand Up @@ -121,14 +122,57 @@ DebugConsole::DebugConsole(QWidget *parent) :

hold(false);

this->setVisible(false);
loadSettings();

// Warn user about not activated hold
if (!m_ui->holdCheckBox->isChecked())
{
m_ui->receiveText->appendHtml(QString("<font color=\"%1\">%2</font>\n").arg(QColor(Qt::red).name(), tr("WARNING: You have NOT enabled auto-hold (stops updating the console is huge amounts of serial data arrive). Updating the console consumes significant CPU load, so if you receive more than about 5 KB/s of serial data, make sure to enable auto-hold if not using the console.")));
}
}

DebugConsole::~DebugConsole()
{
storeSettings();
delete m_ui;
}

void DebugConsole::loadSettings()
{
// Load defaults from settings
QSettings settings;
settings.sync();
settings.beginGroup("QGC_DEBUG_CONSOLE");
m_ui->specialComboBox->setCurrentIndex(settings.value("SPECIAL_SYMBOL", m_ui->specialComboBox->currentIndex()).toInt());
m_ui->specialCheckBox->setChecked(settings.value("SPECIAL_SYMBOL_CHECKBOX_STATE", m_ui->specialCheckBox->isChecked()).toBool());
hexModeEnabled(settings.value("HEX_MODE_ENABLED", m_ui->hexCheckBox->isChecked()).toBool());
MAVLINKfilterEnabled(settings.value("MAVLINK_FILTER_ENABLED", m_ui->mavlinkCheckBox->isChecked()).toBool());
setAutoHold(settings.value("AUTO_HOLD_ENABLED", m_ui->holdCheckBox->isChecked()).toBool());
settings.endGroup();

// Update visibility settings
if (m_ui->specialCheckBox->isChecked())
{
m_ui->specialCheckBox->setVisible(true);
m_ui->addSymbolButton->setVisible(false);
}
}

void DebugConsole::storeSettings()
{
// Store settings
QSettings settings;
settings.beginGroup("QGC_DEBUG_CONSOLE");
settings.setValue("SPECIAL_SYMBOL", m_ui->specialComboBox->currentIndex());
settings.setValue("SPECIAL_SYMBOL_CHECKBOX_STATE", m_ui->specialCheckBox->isChecked());
settings.setValue("HEX_MODE_ENABLED", m_ui->hexCheckBox->isChecked());
settings.setValue("MAVLINK_FILTER_ENABLED", m_ui->mavlinkCheckBox->isChecked());
settings.setValue("AUTO_HOLD_ENABLED", m_ui->holdCheckBox->isChecked());
settings.endGroup();
settings.sync();
//qDebug() << "Storing settings!";
}

/**
* Add a link to the debug console output
*/
Expand Down Expand Up @@ -480,6 +524,12 @@ void DebugConsole::appendSpecialSymbol()

void DebugConsole::sendBytes()
{
// FIXME This store settings should be removed
// once all threading issues have been resolved
// since its called in the destructor, which
// is absolutely sufficient
storeSettings();

// Store command history
commandHistory.append(m_ui->sendText->text());
// Since text was just sent, we're at position commandHistory.length()
Expand Down Expand Up @@ -614,26 +664,42 @@ void DebugConsole::sendBytes()
*/
void DebugConsole::hexModeEnabled(bool mode)
{
convertToAscii = !mode;
m_ui->receiveText->clear();
m_ui->sendText->clear();
m_ui->sentText->clear();
commandHistory.clear();
if (convertToAscii == mode)
{
convertToAscii = !mode;
if (m_ui->hexCheckBox->isChecked() != mode)
{
m_ui->hexCheckBox->setChecked(mode);
}
m_ui->receiveText->clear();
m_ui->sendText->clear();
m_ui->sentText->clear();
commandHistory.clear();
}
}

/**
* @param filter true to ignore all MAVLINK raw data in output, false, to display all incoming data
*/
void DebugConsole::MAVLINKfilterEnabled(bool filter)
{
filterMAVLINK = filter;
bytesToIgnore = 0;
if (filterMAVLINK != filter)
{
filterMAVLINK = filter;
bytesToIgnore = 0;
if (m_ui->mavlinkCheckBox->isChecked() != filter)
{
m_ui->mavlinkCheckBox->setChecked(filter);
}
}
}
/**
* @param hold Freeze the input and thus any scrolling
*/
void DebugConsole::hold(bool hold)
{
if (holdOn != hold)
{
// Check if we need to append bytes from the hold buffer
if (this->holdOn && !hold)
{
Expand All @@ -654,6 +720,11 @@ void DebugConsole::hold(bool hold)
{
m_ui->receiveText->setTextInteractionFlags(Qt::NoTextInteraction);
}
if (m_ui->holdCheckBox->isChecked() != hold)
{
m_ui->holdCheckBox->setChecked(hold);
}
}
}

/**
Expand Down
10 changes: 6 additions & 4 deletions src/ui/DebugConsole.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,8 @@ public slots:
void paintEvent(QPaintEvent *event);
/** @brief Update traffic measurements */
void updateTrafficMeasurements();
void loadSettings();
void storeSettings();

protected:
void changeEvent(QEvent *e);
Expand All @@ -109,14 +111,12 @@ public slots:
void cycleCommandHistory(bool up);

QList<LinkInterface*> links;
QStringList commandHistory;
QString currCommand;
int commandIndex;
LinkInterface* currLink;

bool holdOn; ///< Hold current view, ignore new data
bool convertToAscii; ///< Convert data to ASCII
bool filterMAVLINK; ///< Set true to filter out MAVLink in output
bool autoHold; ///< Auto-hold mode sets view into hold if the data rate is too high
int bytesToIgnore; ///< Number of bytes to ignore
char lastByte; ///< The last received byte
QList<QString> sentBytes; ///< Transmitted bytes, per transmission
Expand All @@ -129,7 +129,9 @@ public slots:
float dataRate; ///< Current data rate
float lowpassDataRate; ///< Lowpass filtered data rate
float dataRateThreshold; ///< Threshold where to enable auto-hold
bool autoHold; ///< Auto-hold mode sets view into hold if the data rate is too high
QStringList commandHistory;
QString currCommand;
int commandIndex;

private:
Ui::DebugConsole *m_ui;
Expand Down
4 changes: 2 additions & 2 deletions src/ui/map3D/QGCGoogleEarthView.ui
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@
</widget>
</item>
<item row="1" column="7">
<widget class="QPushButton" name="clearWPButton">
<widget class="QPushButton" name="clearTrailsButton">
<property name="toolTip">
<string>Delete all waypoints</string>
</property>
Expand All @@ -169,7 +169,7 @@
<string>Delete all waypoints</string>
</property>
<property name="text">
<string>Clear WPs</string>
<string>Clear Trails</string>
</property>
</widget>
</item>
Expand Down

0 comments on commit 6f367e7

Please sign in to comment.