Commit e69732cc authored by pixhawk's avatar pixhawk

Minor cleanups, major: MAVLink logging 100% implemented

parent c70292f0
......@@ -49,15 +49,15 @@ border: 1px solid #777777;
}
QCheckBox::indicator:checked {
background-color: #555555;
background-color: #379AC3;
}
QCheckBox::indicator:checked:hover {
background-color: #555555;
background-color: #379AC3;
}
QCheckBox::indicator:checked:pressed {
background-color: #555555;
background-color: #379AC3;
}
QCheckBox::indicator:indeterminate:hover {
......@@ -189,10 +189,12 @@ QPushButton {
QPushButton:checked {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #404040, stop: 1 #808080);
border: 2px solid #379AC3;
}
QPushButton:pressed {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0);
border: 2px solid #379AC3;
}
QToolButton {
......@@ -207,10 +209,12 @@ QToolButton {
QToolButton:checked {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #090909, stop: 1 #353535);
border: 2px solid #379AC3;
}
QToolButton:pressed {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0);
border: 2px solid #379AC3;
}
QToolTip {
......
......@@ -43,6 +43,8 @@ This file is part of the QGROUNDCONTROL project
#include <inttypes.h>
#include <iostream>
#include "QGC.h"
AS4Protocol::AS4Protocol()
{
......@@ -84,6 +86,10 @@ AS4Protocol::~AS4Protocol()
void AS4Protocol::run()
{
forever
{
QGC::SLEEP::msleep(5000);
}
}
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
/*===================================================================
======================================================================*/
/**
......@@ -59,7 +39,7 @@ MAVLinkProtocol::MAVLinkProtocol() :
heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
m_heartbeatsEnabled(false),
m_loggingEnabled(false),
m_logfile(new QFile(QCoreApplication::applicationDirPath()+"/mavlink.log")),
m_logfile(new QFile(QCoreApplication::applicationDirPath()+"/mavlink_packetlog.mavlink")),
m_enable_version_check(true),
versionMismatchIgnore(false)
{
......@@ -86,6 +66,7 @@ MAVLinkProtocol::~MAVLinkProtocol()
{
if (m_logfile)
{
m_logfile->flush();
m_logfile->close();
delete m_logfile;
}
......@@ -95,6 +76,10 @@ MAVLinkProtocol::~MAVLinkProtocol()
void MAVLinkProtocol::run()
{
forever
{
QGC::SLEEP::msleep(5000);
}
}
QString MAVLinkProtocol::getLogfileName()
......@@ -124,12 +109,18 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// Log data
if (m_loggingEnabled)
{
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
quint64 time = MG::TIME::getGroundTimeNowUsecs();
int len = MAVLINK_MAX_PACKET_LEN+sizeof(quint64);
uint8_t buf[len];
quint64 time = QGC::groundTimeUsecs();
memcpy(buf, (void*)&time, sizeof(quint64));
// int packetlen =
// quint64 checktime = *((quint64*)buf);
// qDebug() << "TIME" << time << "CHECKTIME:" << checktime;
mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message);
m_logfile->write((const char*) buf);
qDebug() << "WROTE LOGFILE";
QByteArray b((const char*)buf, len);
//int packetlen =
if(m_logfile->write(b) < MAVLINK_MAX_PACKET_LEN+sizeof(quint64)) qDebug() << "WRITING TO LOG FAILED!";
//qDebug() << "WROTE LOGFILE";
}
// ORDER MATTERS HERE!
......@@ -170,7 +161,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
if (!versionMismatchIgnore)
{
emit protocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
tr("It is unsafe to use different MAVLink versions. QGroundControl therefore refuses to connect to system %1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(message.sysid).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION));
tr("It is unsafe to use different MAVLink versions. QGroundControl therefore refuses to connect to system %1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(message.sysid).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION));
versionMismatchIgnore = true;
}
......@@ -189,37 +180,37 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
break;
case MAV_AUTOPILOT_PIXHAWK:
{
// Fixme differentiate between quadrotor and coaxial here
PxQuadMAV* mav = new PxQuadMAV(this, message.sysid);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
// packets never reach their goal)
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav;
}
// Fixme differentiate between quadrotor and coaxial here
PxQuadMAV* mav = new PxQuadMAV(this, message.sysid);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
// packets never reach their goal)
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav;
}
break;
case MAV_AUTOPILOT_SLUGS:
{
SlugsMAV* mav = new SlugsMAV(this, message.sysid);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
// packets never reach their goal)
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav;
}
SlugsMAV* mav = new SlugsMAV(this, message.sysid);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
// packets never reach their goal)
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav;
}
break;
case MAV_AUTOPILOT_ARDUPILOTMEGA:
{
ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(this, message.sysid);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
// packets never reach their goal)
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav;
}
ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(this, message.sysid);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
// packets never reach their goal)
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav;
}
break;
default:
uas = new UAS(this, message.sysid);
......@@ -389,23 +380,37 @@ void MAVLinkProtocol::enableHeartbeats(bool enabled)
void MAVLinkProtocol::enableLogging(bool enabled)
{
if (enabled && !m_loggingEnabled)
bool changed = false;
if (enabled != m_loggingEnabled) changed = true;
if (enabled)
{
if (m_logfile->isOpen()) m_logfile->close();
m_logfile->open(QIODevice::WriteOnly | QIODevice::Append);
if (m_logfile->isOpen())
{
m_logfile->flush();
m_logfile->close();
}
if (!m_logfile->open(QIODevice::WriteOnly | QIODevice::Append))
{
emit protocolStatusMessage(tr("Opening MAVLink logfile for writing failed"), tr("MAVLink cannot log to the file %1, please choose a different file.").arg(m_logfile->fileName()));
qDebug() << "OPENING LOGFILE FAILED!";
}
}
else if (!enabled)
{
m_logfile->close();
m_logfile->flush();
m_logfile->close();
}
m_loggingEnabled = enabled;
emit loggingChanged(enabled);
if (changed) emit loggingChanged(enabled);
}
void MAVLinkProtocol::setLogfileName(const QString& filename)
{
m_logfile->flush();
m_logfile->close();
m_logfile->setFileName(filename);
enableLogging(m_loggingEnabled);
}
void MAVLinkProtocol::enableVersionCheck(bool enabled)
......
......@@ -141,7 +141,7 @@ void MAVLinkSimulationLink::run()
}
last = MG::TIME::getGroundTimeNow();
}
MG::SLEEP::msleep(3);
QGC::SLEEP::msleep(3);
}
}
......@@ -381,14 +381,16 @@ void MAVLinkSimulationLink::mainloop()
float hackDt = 0.1f; // 100 ms
// Move X Position
x = 12.0*sin(((double)circleCounter)/100.0);
y = 5.0*cos(((double)circleCounter)/100.0);
z = 1.8 + 1.2*sin(((double)circleCounter)/60.0);
x = 12.0*sin(((double)circleCounter)/200.0);
y = 5.0*cos(((double)circleCounter)/200.0);
z = 1.8 + 1.2*sin(((double)circleCounter)/200.0);
float xSpeed = (x - lastX)/hackDt;
float ySpeed = (y - lastY)/hackDt;
float zSpeed = (z - lastZ)/hackDt;
circleCounter++;
......@@ -423,14 +425,14 @@ void MAVLinkSimulationLink::mainloop()
// streampointer += bufferlength;
// GLOBAL POSITION
mavlink_msg_global_position_int_pack(systemId, componentId, &ret, (473780.28137103+(x))*1E3, (85489.9892510421+(y))*1E3, (z+550.0)*1000.0, xSpeed*15.0*100.0, ySpeed*15.0*100.0, zSpeed*15*100.0);
mavlink_msg_global_position_int_pack(systemId, componentId, &ret, (473780.28137103+(x))*1E3, (85489.9892510421+(y))*1E3, (z+550.0)*1000.0, xSpeed, ySpeed, zSpeed);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// GLOBAL POSITION VEHICLE 2
mavlink_msg_global_position_int_pack(54, componentId, &ret, (473780.28137103+(x+0.002))*1E3, (85489.9892510421+((y/2)+0.3))*1E3, (z+570.0)*1000.0, xSpeed*15.0*100.0, ySpeed*15.0*100.0, zSpeed*15.0*100.0);
mavlink_msg_global_position_int_pack(54, componentId, &ret, (473780.28137103+(x+0.002))*1E3, (85489.9892510421+((y/2)+0.3))*1E3, (z+570.0)*1000.0, xSpeed, ySpeed, zSpeed);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......
......@@ -36,6 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include <QFile>
#include <QDebug>
#include <MG.h>
#include "QGC.h"
/**
* Create a simulated link. This link is connected to an input and output file.
......@@ -92,6 +93,10 @@ void SerialSimulationLink::run()
msleep(rate);
}*/
forever
{
QGC::SLEEP::msleep(5000);
}
}
void SerialSimulationLink::enableLoopBackMode(SerialLink* loop)
......
......@@ -35,7 +35,7 @@ This file is part of the QGROUNDCONTROL project
#include <iostream>
#include "UDPLink.h"
#include "LinkManager.h"
#include "MG.h"
#include "QGC.h"
//#include <netinet/in.h>
UDPLink::UDPLink(QHostAddress host, quint16 port)
......@@ -64,6 +64,10 @@ UDPLink::~UDPLink()
**/
void UDPLink::run()
{
forever
{
QGC::SLEEP::msleep(5000);
}
}
void UDPLink::setAddress(QString address)
......@@ -242,7 +246,7 @@ bool UDPLink::connect()
if (connectState)
{
emit connected();
connectionStartTime = MG::TIME::getGroundTimeNow();
connectionStartTime = QGC::groundTimeUsecs()/1000;
}
start(HighPriority);
......@@ -281,7 +285,7 @@ qint64 UDPLink::getNominalDataRate() {
qint64 UDPLink::getTotalUpstream() {
statisticsMutex.lock();
qint64 totalUpstream = bitsSentTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000);
qint64 totalUpstream = bitsSentTotal / ((QGC::groundTimeUsecs()/1000 - connectionStartTime) / 1000);
statisticsMutex.unlock();
return totalUpstream;
}
......@@ -304,7 +308,7 @@ qint64 UDPLink::getBitsReceived() {
qint64 UDPLink::getTotalDownstream() {
statisticsMutex.lock();
qint64 totalDownstream = bitsReceivedTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000);
qint64 totalDownstream = bitsReceivedTotal / ((QGC::groundTimeUsecs()/1000 - connectionStartTime) / 1000);
statisticsMutex.unlock();
return totalDownstream;
}
......
......@@ -36,6 +36,7 @@ This file is part of the PIXHAWK project
#include <limits.h>
#include "UAS.h"
#include "UASManager.h"
#include "QGC.h"
/**
* The coordinate frame of the joystick axis is the aeronautical frame like shown on this image:
......@@ -276,7 +277,7 @@ void JoystickInput::run()
}
// Sleep, update rate of joystick is approx. 50 Hz (1000 ms / 50 = 20 ms)
MG::SLEEP::msleep(20);
QGC::SLEEP::msleep(20);
}
......
......@@ -434,7 +434,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
emit valueChanged(uasId, "speed", "m/s", pos.v, time);
//qDebug() << "GOT GPS RAW";
emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
// emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
}
else
{
......
......@@ -33,10 +33,12 @@ This file is part of the QGROUNDCONTROL project
#include <QMessageBox>
#include <QTimer>
#include "UAS.h"
#include <UASInterface.h>
#include <UASManager.h>
#include "UASInterface.h"
#include "UASManager.h"
#include "QGC.h"
UASManager* UASManager::instance() {
UASManager* UASManager::instance()
{
static UASManager* _instance = 0;
if(_instance == 0) {
_instance = new UASManager();
......@@ -67,6 +69,10 @@ UASManager::~UASManager()
void UASManager::run()
{
forever
{
QGC::SLEEP::msleep(5000);
}
}
void UASManager::addUAS(UASInterface* uas)
......@@ -104,12 +110,6 @@ QList<UASInterface*> UASManager::getUASList()
UASInterface* UASManager::getActiveUAS()
{
// if(!activeUAS)
// {
// QMessageBox msgBox;
// msgBox.setText(tr("No Micro Air Vehicle connected. Please connect one first."));
// msgBox.exec();
// }
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
......@@ -193,8 +193,6 @@ void UASManager::setActiveUAS(UASInterface* uas)
activeUAS = uas;
activeUASMutex.unlock();
qDebug() << __FILE__ << ":" << __LINE__ << " ACTIVE UAS SET TO: " << uas->getUASName();
emit activeUASSet(uas);
emit activeUASSet(uas->getUASID());
emit activeUASStatusChanged(uas, true);
......
......@@ -66,6 +66,8 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) :
setWindowTitle(title);
//m_ui->setupUi(this);
setAutoFillBackground(true);
// Add all items in accept list to gauge
if (plotList)
{
......@@ -150,7 +152,7 @@ HDDisplay::~HDDisplay()
QSize HDDisplay::sizeHint() const
{
return QSize(400, 400*(vwidth/vheight));
return QSize(400, 400.0f*(vwidth/vheight)*1.1f);
}
void HDDisplay::enableGLRendering(bool enable)
......@@ -164,6 +166,35 @@ void HDDisplay::triggerUpdate()
update(this->geometry());
}
//void HDDisplay::updateValue(UASInterface* uas, const QString& name, const QString& unit, double value, quint64 msec)
//{
// // UAS is not needed
// Q_UNUSED(uas);
// if (!isnan(value) && !isinf(value))
// {
// // Update mean
// const float oldMean = valuesMean.value(name, 0.0f);
// const int meanCount = valuesCount.value(name, 0);
// double mean = (oldMean * meanCount + value) / (meanCount + 1);
// if (isnan(mean) || isinf(mean)) mean = 0.0;
// valuesMean.insert(name, mean);
// valuesCount.insert(name, meanCount + 1);
// // Two-value sliding average
// double dot = (valuesDot.value(name) + (value - values.value(name, 0.0f)) / ((msec - lastUpdate.value(name, 0))/1000.0f))/2.0f;
// if (isnan(dot) || isinf(dot))
// {
// dot = 0.0;
// }
// valuesDot.insert(name, dot);
// values.insert(name, value);
// lastUpdate.insert(name, msec);
// //}
// //qDebug() << __FILE__ << __LINE__ << "VALUE:" << value << "MEAN:" << mean << "DOT:" << dot << "COUNT:" << meanCount;
// }
//}
void HDDisplay::paintEvent(QPaintEvent * event)
{
Q_UNUSED(event);
......@@ -180,7 +211,12 @@ void HDDisplay::contextMenuEvent (QContextMenuEvent* event)
menu.addActions(getItemRemoveActions());
menu.addSeparator();
menu.addAction(setColumnsAction);
menu.addAction(setTitleAction);
// Title change would ruin settings
// this can only be allowed once
// HDDisplays are instantiated
// by a factory method based on
// QSettings
//menu.addAction(setTitleAction);
menu.exec(event->globalPos());
}
......@@ -249,11 +285,20 @@ void HDDisplay::addGauge()
QStringList items;
for (int i = 0; i < values.count(); ++i)
{
items.append(QString("%1,%2,%3,%4").arg("-180").arg(values.keys().at(i)).arg(units.keys().at(i)).arg("+180"));
QString key = values.keys().at(i);
QString unit = units.value(key);
if (unit.contains("deg") || unit.contains("rad"))
{
items.append(QString("%1,%2,%3,%4,s").arg("-180").arg(key).arg(unit).arg("+180"));
}
else
{
items.append(QString("%1,%2,%3,%4").arg("-180").arg(key).arg(unit).arg("+180"));
}
}
bool ok;
QString item = QInputDialog::getItem(this, tr("Add Gauge Instrument"),
tr("Format: min, curve name, max"), items, 0, true, &ok);
tr("Format: min, curve name, max[,s]"), items, 0, true, &ok);
if (ok && !item.isEmpty())
{
addGauge(item);
......@@ -573,6 +618,11 @@ void HDDisplay::drawGauge(float xRef, float yRef, float radius, float min, float
}
circlePen.setWidth(refLineWidthToPen(radius/12.0f));
circlePen.setColor(color);
if (symmetric)
{
circlePen.setStyle(Qt::DashLine);
}
painter->setBrush(Qt::NoBrush);
painter->setPen(circlePen);
drawCircle(xRef, yRef+nameHeight, radius, 0.0f, color, painter);
......@@ -634,8 +684,8 @@ void HDDisplay::drawGauge(float xRef, float yRef, float radius, float min, float
QPolygonF p(6);
p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef+nameHeight+radius * 0.05f));
p.replace(1, QPointF(xRef-minWidth/2.0f, yRef+nameHeight+radius * 0.9f));
p.replace(2, QPointF(xRef+minWidth/2.0f, yRef+nameHeight+radius * 0.9f));
p.replace(1, QPointF(xRef-minWidth/2.0f, yRef+nameHeight+radius * 0.89f));
p.replace(2, QPointF(xRef+minWidth/2.0f, yRef+nameHeight+radius * 0.89f));
p.replace(3, QPointF(xRef+maxWidth/2.0f, yRef+nameHeight+radius * 0.05f));
p.replace(4, QPointF(xRef, yRef+nameHeight+radius * 0.0f));
p.replace(5, QPointF(xRef-maxWidth/2.0f, yRef+nameHeight+radius * 0.05f));
......@@ -818,6 +868,7 @@ void HDDisplay::updateValue(const int uasId, const QString& name, const QString&
valuesCount.insert(name, meanCount + 1);
valuesDot.insert(name, (value - values.value(name, 0.0f)) / ((msec - lastUpdate.value(name, 0))/1000.0f));
values.insert(name, value);
units.insert(name, unit);
lastUpdate.insert(name, msec);
}
......
......@@ -137,7 +137,7 @@ protected:
UASInterface* uas; ///< The uas currently monitored
QMap<QString, float> values; ///< The variables this HUD displays
QMap<QString, float> units; ///< The units
QMap<QString, QString> units; ///< The units
QMap<QString, float> valuesDot; ///< First derivative of the variable
QMap<QString, float> valuesMean; ///< Mean since system startup for this variable
QMap<QString, int> valuesCount; ///< Number of values received so far
......
This diff is collapsed.
......@@ -63,11 +63,8 @@ public slots:
/** @brief Set the currently monitored UAS */
void setActiveUAS(UASInterface* uas);
/** @brief Update a HUD value */
void updateValue(UASInterface* uas, QString name, double value, quint64 msec);
void updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp);
void updateAttitudeThrustSetPoint(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec);
// void updateAttitudeThrustSetPoint(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec);
void updateBattery(UASInterface*, double, double, int);
void receiveHeartbeat(UASInterface*);
void updateThrust(UASInterface*, double);
......@@ -103,8 +100,6 @@ protected slots:
void drawChangeRateStrip(float xRef, float yRef, float height, float minRate, float maxRate, float value, QPainter* painter);
void drawChangeIndicatorGauge(float xRef, float yRef, float radius, float expectedMaxChange, float value, const QColor& color, QPainter* painter, bool solid=true);
void drawSystemIndicator(float xRef, float yRef, int maxNum, float maxWidth, float maxHeight, QPainter* painter);
void drawPolygon(QPolygonF refPolygon, QPainter* painter);
......@@ -130,11 +125,6 @@ protected:
QImage* image; ///< Double buffer image
QImage glImage; ///< The background / camera image
UASInterface* uas; ///< The uas currently monitored
QMap<QString, float> values; ///< The variables this HUD displays
QMap<QString, float> valuesDot; ///< First derivative of the variable
QMap<QString, float> valuesMean; ///< Mean since system startup for this variable
QMap<QString, int> valuesCount; ///< Number of values received so far
QMap<QString, quint64> lastUpdate; ///< The last update time for this variable
float yawInt; ///< The yaw integral. Used to damp the yaw indication.
QString mode; ///< The current vehicle mode
QString state; ///< The current vehicle state
......@@ -188,7 +178,20 @@ protected:
float roll;
float pitch;
float yaw;
float yawDiff;
float rollLP;
float pitchLP;
float yawLP;
double yawDiff;
double xPos;
double yPos;
double zPos;
double xSpeed;
double ySpeed;
double zSpeed;
double lat;
double lon;
double alt;
float load;
void paintEvent(QPaintEvent *event);
};
......
......@@ -86,7 +86,10 @@ MainWindow::MainWindow(QWidget *parent):
}
else
{
currentView = (VIEW_SECTIONS) settings.value("CURRENT_VIEW", currentView).toInt();
if (settings.value("CURRENT_VIEW", VIEW_PILOT) != VIEW_PILOT)
{
currentView = (VIEW_SECTIONS) settings.value("CURRENT_VIEW", currentView).toInt();
}
}
// Check if the settings exist, instantiate defaults if necessary
......@@ -316,8 +319,8 @@ void MainWindow::buildPxWidgets()
//FIXME: memory of acceptList2 will never be freed again
QStringList* acceptList2 = new QStringList();
acceptList2->append("0,abs pressure,hPa,65500");
acceptList2->append("-2000,accel. X,raw,2000,s");
acceptList2->append("-2000,accel. Y,raw,2000,s");
acceptList2->append("-999,accel. X,raw,999,s");
acceptList2->append("-999,accel. Y,raw,999,s");
if (!linechartWidget)
{
......
......@@ -2,7 +2,9 @@
#include <QMessageBox>
#include <QDesktopServices>
#include "MainWindow.h"
#include "QGCMAVLinkLogPlayer.h"
#include "QGC.h"
#include "ui_QGCMAVLinkLogPlayer.h"
QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *parent) :
......@@ -11,18 +13,27 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
totalLines(0),
startTime(0),
endTime(0),
currentTime(0),
currentStartTime(0),
accelerationFactor(1.0f),
mavlink(mavlink),
logLink(NULL),
loopCounter(0),
ui(new Ui::QGCMAVLinkLogPlayer)
{
ui->setupUi(this);
ui->gridLayout->setAlignment(Qt::AlignTop);
// Setup timer
connect(&loopTimer, SIGNAL(timeout()), this, SLOT(logLoop()));
// Setup buttons
connect(ui->selectFileButton, SIGNAL(clicked()), this, SLOT(selectLogFile()));
connect(ui->pauseButton, SIGNAL(clicked()), this, SLOT(pause()));
connect(ui->playButton, SIGNAL(clicked()), this, SLOT(play()));
connect(ui->speedSlider, SIGNAL(valueChanged(int)), this, SLOT(setAccelerationFactorInt(int)));
setAccelerationFactorInt(49);
ui->speedSlider->setValue(49);
}
QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer()
......@@ -35,6 +46,15 @@ void QGCMAVLinkLogPlayer::play()
if (logFile.isOpen())
{
ui->pauseButton->setChecked(false);
ui->selectFileButton->setEnabled(false);
if (logLink != NULL)
{
delete logLink;
}
logLink = new MAVLinkSimulationLink("");
// Start timer
loopTimer.start(1);
}
else
{
......@@ -51,7 +71,21 @@ void QGCMAVLinkLogPlayer::play()
void QGCMAVLinkLogPlayer::pause()
{
loopTimer.stop();
ui->playButton->setChecked(false);
ui->selectFileButton->setEnabled(true);
delete logLink;
logLink = NULL;
}
void QGCMAVLinkLogPlayer::reset()
{
pause();
loopCounter = 0;
logFile.reset();
ui->pauseButton->setChecked(true);
ui->progressBar->setValue(0);
startTime = 0;
}
void QGCMAVLinkLogPlayer::selectLogFile()
......@@ -61,27 +95,60 @@ void QGCMAVLinkLogPlayer::selectLogFile()
loadLogFile(fileName);
}
/**
* @param factor 0: 0.01X, 50: 1.0X, 100: 100.0X
*/
void QGCMAVLinkLogPlayer::setAccelerationFactorInt(int factor)
{
float f = factor+1.0f;
f -= 50.0f;
if (f < 0.0f)
{
accelerationFactor = 1.0f / (-f/2.0f);
}
else
{
accelerationFactor = 1+(f/2.0f);
}
//qDebug() << "FACTOR:" << accelerationFactor;
ui->speedLabel->setText(tr("Speed: %1X").arg(accelerationFactor, 0, 'f', 2));
}
void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
{
// Ensure that the playback process is stopped
if (logFile.isOpen())
{
loopTimer.stop();
logFile.reset();
logFile.close();
}
logFile.setFileName(file);
if (!logFile.open(QFile::ReadOnly))
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText(tr("The selected logfile is unreadable"));
msgBox.setInformativeText(tr("Please make sure that the file %1 is readable or select a different file").arg(file));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec();
MainWindow::instance()->showCriticalMessage(tr("The selected logfile is unreadable"), tr("Please make sure that the file %1 is readable or select a different file").arg(file));
logFile.setFileName("");
}
else
{
ui->logFileNameLabel->setText(tr("%1").arg(file));
QFileInfo logFileInfo(file);
logFile.reset();
startTime = 0;
ui->logFileNameLabel->setText(tr("%1").arg(logFileInfo.baseName()));
ui->logStatsLabel->setText(tr("Log: %2 MB, %3 packets").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(logFileInfo.size()/(MAVLINK_MAX_PACKET_LEN+sizeof(quint64))));
}
}
union log64
{
quint64 q;
const char* b;
};
/**
* This function is the "mainloop" of the log player, reading one line
* and adjusting the mainloop timer to read the next line in time.
......@@ -90,14 +157,118 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
* For scientific logging, the use of onboard timestamps and the log
* functionality of the line chart plot is recommended.
*/
void QGCMAVLinkLogPlayer::readLine()
void QGCMAVLinkLogPlayer::logLoop()
{
const int packetLen = MAVLINK_MAX_PACKET_LEN;
const int timeLen = sizeof(quint64);
bool ok;
// Ui update: Only every 20 messages
// to prevent flickering and high CPU load
// First check initialization
if (startTime == 0)
{
QByteArray startBytes = logFile.read(timeLen);
// Check if the correct number of bytes could be read
if (startBytes.length() != timeLen)
{
ui->logStatsLabel->setText(tr("Error reading first %1 bytes").arg(timeLen));
MainWindow::instance()->showCriticalMessage(tr("Failed loading MAVLink Logfile"), tr("Error reading first %1 bytes from logfile. Got %2 instead of %1 bytes. Is the logfile readable?").arg(timeLen).arg(startBytes.length()));
reset();
return;
}
// Convert data to timestamp
startTime = *((quint64*)(startBytes.constData()));
currentStartTime = QGC::groundTimeUsecs();
ok = true;
//qDebug() << "START TIME: " << startTime;
// Check if these bytes could be correctly decoded
if (!ok)
{
ui->logStatsLabel->setText(tr("Error decoding first timestamp, aborting."));
MainWindow::instance()->showCriticalMessage(tr("Failed loading MAVLink Logfile"), tr("Could not load initial timestamp from file %1. Is the file corrupted?").arg(logFile.fileName()));
reset();
return;
}
}
// Initialization seems fine, load next chunk
QByteArray chunk = logFile.read(timeLen+packetLen);
QByteArray packet = chunk.mid(0, packetLen);
// Emit this packet
mavlink->receiveBytes(logLink, packet);
// Check if reached end of file before reading next timestamp
if (chunk.length() < timeLen+packetLen || logFile.atEnd())
{
// Reached end of file
reset();
QString status = tr("Reached end of MAVLink log file.");
ui->logStatsLabel->setText(status);
ui->progressBar->setValue(100);
MainWindow::instance()->showStatusMessage(status);
return;
}
// End of file not reached, read next timestamp
QByteArray rawTime = chunk.mid(packetLen);
// Update status label
// Update progress bar
// This is the timestamp of the next packet
quint64 time = *((quint64*)(rawTime.constData()));
ok = true;
if (!ok)
{
// Convert it to 64bit number
QString status = tr("Time conversion error during log replay. Continuing..");
ui->logStatsLabel->setText(status);
MainWindow::instance()->showStatusMessage(status);
}
else
{
// Normal processing, passed all checks
// start timer to match time offset between
// this and next packet
// Offset in ms
qint64 timediff = (time - startTime)/accelerationFactor;
// Immediately load any data within
// a 3 ms interval
int nextExecutionTime = (((qint64)currentStartTime + (qint64)timediff) - (qint64)QGC::groundTimeUsecs())/1000;
//qDebug() << "nextExecutionTime:" << nextExecutionTime << "QGC START TIME:" << currentStartTime << "LOG START TIME:" << startTime;
if (nextExecutionTime < 5)
{
logLoop();
}
else
{
loopTimer.start(nextExecutionTime);
}
// loopTimer.start(20);
if (loopCounter % 40 == 0)
{
QFileInfo logFileInfo(logFile);
int progress = 100.0f*(loopCounter/(float)(logFileInfo.size()/(MAVLINK_MAX_PACKET_LEN+sizeof(quint64))));
//qDebug() << "Progress:" << progress;
ui->progressBar->setValue(progress);
}
loopCounter++;
// Ui update: Only every 20 messages
// to prevent flickering and high CPU load
// Update status label
// Update progress bar
}
}
void QGCMAVLinkLogPlayer::changeEvent(QEvent *e)
......
......@@ -5,6 +5,7 @@
#include <QFile>
#include "MAVLinkProtocol.h"
#include "MAVLinkSimulationLink.h"
namespace Ui {
class QGCMAVLinkLogPlayer;
......@@ -30,22 +31,30 @@ public slots:
void play();
/** @brief Pause the logfile */
void pause();
/** @brief Reset the logfile */
void reset();
/** @brief Select logfile */
void selectLogFile();
/** @brief Load log file */
void loadLogFile(const QString& file);
/** @brief The logging mainloop */
void logLoop();
/** @brief Set acceleration factor in percent */
void setAccelerationFactorInt(int factor);
protected:
int lineCounter;
int totalLines;
quint64 startTime;
quint64 endTime;
quint64 currentTime;
quint64 currentStartTime;
float accelerationFactor;
MAVLinkProtocol* mavlink;
MAVLinkSimulationLink* logLink;
QFile logFile;
QTimer loopTimer;
int loopCounter;
void changeEvent(QEvent *e);
void readLine();
private:
Ui::QGCMAVLinkLogPlayer *ui;
......
......@@ -142,15 +142,41 @@ updateTimer(new QTimer())
updateTimer->setInterval(300);
connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh()));
updateTimer->start();
readSettings();
}
LinechartWidget::~LinechartWidget() {
LinechartWidget::~LinechartWidget()
{
writeSettings();
stopLogging();
delete listedCurves;
listedCurves = NULL;
}
void LinechartWidget::writeSettings()
{
QSettings settings;
settings.beginGroup("LINECHART");
if (timeButton) settings.setValue("ENFORCE_GROUNDTIME", timeButton->isChecked());
if (unitsCheckBox) settings.setValue("SHOW_UNITS", unitsCheckBox->isChecked());
settings.endGroup();
settings.sync();
}
void LinechartWidget::readSettings()
{
QSettings settings;
settings.sync();
settings.beginGroup("LINECHART");
if (activePlot)
{
timeButton->setChecked(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool());
activePlot->enforceGroundTime(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool());
}
if (unitsCheckBox) unitsCheckBox->setChecked(settings.value("SHOW_UNITS").toBool());
settings.endGroup();
}
void LinechartWidget::createLayout()
{
// Create actions
......@@ -215,7 +241,7 @@ void LinechartWidget::createLayout()
connect(logButton, SIGNAL(clicked()), this, SLOT(startLogging()));
// Ground time button
QCheckBox* timeButton = new QCheckBox(this);
timeButton = new QCheckBox(this);
timeButton->setText(tr("Ground Time"));
timeButton->setToolTip(tr("Overwrite timestamp of data from vehicle with ground receive time. Helps if the plots are not visible because of missing or invalid onboard time."));
timeButton->setWhatsThis(tr("Overwrite timestamp of data from vehicle with ground receive time. Helps if the plots are not visible because of missing or invalid onboard time."));
......@@ -225,6 +251,7 @@ void LinechartWidget::createLayout()
layout->addWidget(timeButton, 1, 4);
layout->setColumnStretch(4, 0);
connect(timeButton, SIGNAL(clicked(bool)), activePlot, SLOT(enforceGroundTime(bool)));
connect(timeButton, SIGNAL(clicked()), this, SLOT(writeSettings()));
unitsCheckBox = new QCheckBox(this);
unitsCheckBox->setText(tr("Show units"));
......@@ -232,21 +259,7 @@ void LinechartWidget::createLayout()
unitsCheckBox->setToolTip(tr("Enable unit display in curve list"));
unitsCheckBox->setWhatsThis(tr("Enable unit display in curve list"));
layout->addWidget(unitsCheckBox, 1, 5);
// Create the scroll bar
//scrollbar = new QScrollBar(Qt::Horizontal, ui.diagramGroupBox);
//scrollbar->setMinimum(MIN_TIME_SCROLLBAR_VALUE);
//scrollbar->setMaximum(MAX_TIME_SCROLLBAR_VALUE);
//scrollbar->setPageStep(PAGESTEP_TIME_SCROLLBAR_VALUE);
// Set scrollbar to maximum and disable it
//scrollbar->setValue(MIN_TIME_SCROLLBAR_VALUE);
//scrollbar->setDisabled(true);
// scrollbar->setFixedHeight(20);
// Add scroll bar to layout and make sure it gets all available space
//layout->addWidget(scrollbar, 1, 5);
//layout->setColumnStretch(5, 10);
connect(unitsCheckBox, SIGNAL(clicked()), this, SLOT(writeSettings()));
ui.diagramGroupBox->setLayout(layout);
......@@ -255,14 +268,6 @@ void LinechartWidget::createLayout()
// Connect notifications from the user interface to the plot
connect(this, SIGNAL(curveRemoved(QString)), activePlot, SLOT(hideCurve(QString)));
//connect(this, SIGNAL(curveSet(QString, int)), activePlot, SLOT(showshowCurveCurve(QString, int)));
// FIXME
// Connect notifications from the plot to the user interface
//connect(activePlot, SIGNAL(curveAdded(QString)), this, SLOT(addCurve(QString)));
//connect(activePlot, SIGNAL(curveRemoved(QString)), this, SLOT(removeCurve(QString)));
// Scrollbar
// Update scrollbar when plot window changes (via translator method setPlotWindowPosition()
connect(activePlot, SIGNAL(windowPositionChanged(quint64)), this, SLOT(setPlotWindowPosition(quint64)));
......@@ -612,6 +617,7 @@ void LinechartWidget::addCurve(const QString& curve, const QString& unit)
unitLabel->setToolTip(tr("Unit of ") + curve);
unitLabel->setWhatsThis(tr("Unit of ") + curve);
curvesWidgetLayout->addWidget(unitLabel, labelRow, 4);
unitLabel->setVisible(unitsCheckBox->isChecked());
connect(unitsCheckBox, SIGNAL(clicked(bool)), unitLabel, SLOT(setVisible(bool)));
// Mean
......@@ -649,6 +655,10 @@ void LinechartWidget::addCurve(const QString& curve, const QString& unit)
// Set stretch factors so that the label gets the whole space
// Load visibility settings
// TODO
// Connect actions
QObject::connect(checkBox, SIGNAL(clicked(bool)), this, SLOT(takeButtonClick(bool)));
QObject::connect(this, SIGNAL(curveVisible(QString, bool)), plot, SLOT(setVisible(QString, bool)));
......@@ -691,7 +701,7 @@ void LinechartWidget::setActive(bool active)
}
if (active)
{
updateTimer->start();
updateTimer->start(updateInterval);
}
else
{
......
......@@ -95,6 +95,10 @@ public slots:
void stopLogging();
/** @brief Refresh the view */
void refresh();
/** @brief Write the current configuration to disk */
void writeSettings();
/** @brief Read the current configuration from disk */
void readSettings();
protected:
void addCurveToList(QString curve);
......@@ -133,6 +137,7 @@ protected:
QToolButton* scalingLogButton;
QToolButton* logButton;
QPointer<QCheckBox> unitsCheckBox;
QPointer<QCheckBox> timeButton;
QFile* logFile;
unsigned int logindex;
......@@ -140,6 +145,7 @@ protected:
quint64 logStartTime;
QTimer* updateTimer;
LogCompressor* compressor;
static const int updateInterval = 400; ///< Time between number updates, in milliseconds
static const int MAX_CURVE_MENUITEM_NUMBER = 8;
static const int PAGESTEP_TIME_SCROLLBAR_VALUE = (MAX_TIME_SCROLLBAR_VALUE - MIN_TIME_SCROLLBAR_VALUE) / 10;
......
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