Commit acd86423 authored by pixhawk's avatar pixhawk

Improved GPS, added UAS trails, improved error reporting

parent 9e5b07ee
......@@ -253,6 +253,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_aux_status_t status;
mavlink_msg_aux_status_decode(&message, &status);
emit loadChanged(this, status.load/10.0f);
emit errCountChanged(uasId, "IMU", "I2C0", status.i2c0_err_count);
emit errCountChanged(uasId, "IMU", "I2C1", status.i2c1_err_count);
emit errCountChanged(uasId, "IMU", "SPI0", status.spi0_err_count);
emit errCountChanged(uasId, "IMU", "SPI1", status.spi1_err_count);
emit errCountChanged(uasId, "IMU", "UART", status.uart_total_err_count);
emit valueChanged(this, "Load", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow());
}
break;
......
......@@ -229,6 +229,21 @@ signals:
* @param severity The severity of the message, 0 for plain debug messages, 10 for very critical messages
*/
void textMessageReceived(int uasid, int severity, QString text);
/**
* @brief Update the error count of a device
*
* The error count indicates how many errors occured during the use of a device.
* Usually a random error from time to time is acceptable, e.g. through electromagnetic
* interferences on device lines like I2C and SPI. A constantly and rapidly increasing
* error count however can help to identify broken cables or misbehaving drivers.
*
* @param uasid System ID
* @param component Name of the component, e.g. "IMU"
* @param device Name of the device, e.g. "SPI0" or "I2C1"
* @param count Errors occured since system startup
*/
void errCountChanged(int uasid, QString component, QString device, int count);
/**
* @brief Drop rate of communication link updated
*
......
......@@ -39,6 +39,8 @@ This file is part of the PIXHAWK project
MapWidget::MapWidget(QWidget *parent) :
QWidget(parent),
zoomLevel(0),
uasIcons(),
uasTrails(),
m_ui(new Ui::MapWidget)
{
m_ui->setupUi(this);
......@@ -50,7 +52,7 @@ MapWidget::MapWidget(QWidget *parent) :
mc->showScale(true);
mc->enablePersistentCache();
uasIcons = QMap<int, CirclePoint*>();
//uasIcons = QMap<int, CirclePoint*>();
//QSize(480,640)
// ImageManager::instance()->setProxy("www-cache", 8080);
......@@ -125,55 +127,66 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
{
Q_UNUSED(usec);
quint64 currTime = MG::TIME::getGroundTimeNow();
if (currTime - lastUpdate > 100)
if (currTime - lastUpdate > 90)
{
lastUpdate = currTime;
// create a LineString
//QList<Point*> points;
// Points with a circle
// A QPen can be used to customize the
QPen* pointpen = new QPen(uas->getColor());
//pointpen->setWidth(3);
//points.append(new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen));
if (!uasIcons.contains(uas->getUASID()))
{
CirclePoint* p = new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen);
uasIcons.insert(uas->getUASID(), p);
osmLayer->addGeometry(p);
}
else
{
CirclePoint* p = uasIcons.value(uas->getUASID());
p->setCoordinate(QPointF(lat, lon));
// create a LineString
//QList<Point*> points;
// Points with a circle
// A QPen can be used to customize the
//pointpen->setWidth(3);
//points.append(new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen));
if (!uasIcons.contains(uas->getUASID()))
{
// Get the UAS color
QColor uasColor = uas->getColor();
// Icon
QPen* pointpen = new QPen(uasColor);
CirclePoint* p = new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen);
uasIcons.insert(uas->getUASID(), p);
osmLayer->addGeometry(p);
// Line
// A QPen also can use transparency
QList<Point*> points;
points.append(new Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
QPen* linepen = new QPen(uasColor.darker());
linepen->setWidth(2);
// Add the Points and the QPen to a LineString
LineString* ls = new LineString(points, uas->getUASName(), linepen);
uasTrails.insert(uas->getUASID(), ls);
// Add the LineString to the layer
osmLayer->addGeometry(ls);
}
else
{
CirclePoint* p = uasIcons.value(uas->getUASID());
p->setCoordinate(QPointF(lat, lon));
// Extend trail
uasTrails.value(uas->getUASID())->addPoint(new Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
}
// points.append(new CirclePoint(8.275145, 50.016992, 15, "Wiesbaden-Mainz-Kastel, Johannes-Goßner-Straße", Point::Middle, pointpen));
// points.append(new CirclePoint(8.270476, 50.021426, 15, "Wiesbaden-Mainz-Kastel, Ruthof", Point::Middle, pointpen));
// // "Blind" Points
// points.append(new Point(8.266445, 50.025913, "Wiesbaden-Mainz-Kastel, Mudra Kaserne"));
// points.append(new Point(8.260378, 50.030345, "Wiesbaden-Mainz-Amoneburg, Dyckerhoffstraße"));
// Connect click events of the layer to this object
//connect(osmLayer, SIGNAL(geometryClicked(Geometry*, QPoint)),
// this, SLOT(geometryClicked(Geometry*, QPoint)));
// Sets the view to the interesting area
//QList<QPointF> view;
//view.append(QPointF(8.24764, 50.0319));
//view.append(QPointF(8.28412, 49.9998));
// mc->setView(view);
updatePosition(0, lat, lon);
}
// points.append(new CirclePoint(8.275145, 50.016992, 15, "Wiesbaden-Mainz-Kastel, Johannes-Goßner-Straße", Point::Middle, pointpen));
// points.append(new CirclePoint(8.270476, 50.021426, 15, "Wiesbaden-Mainz-Kastel, Ruthof", Point::Middle, pointpen));
// // "Blind" Points
// points.append(new Point(8.266445, 50.025913, "Wiesbaden-Mainz-Kastel, Mudra Kaserne"));
// points.append(new Point(8.260378, 50.030345, "Wiesbaden-Mainz-Amoneburg, Dyckerhoffstraße"));
// // A QPen also can use transparency
// QPen* linepen = new QPen(QColor(0, 0, 255, 100));
// linepen->setWidth(5);
// // Add the Points and the QPen to a LineString
// LineString* ls = new LineString(points, "Path", linepen);
//
// // Add the LineString to the layer
// osmLayer->addGeometry(ls);
// Connect click events of the layer to this object
//connect(osmLayer, SIGNAL(geometryClicked(Geometry*, QPoint)),
// this, SLOT(geometryClicked(Geometry*, QPoint)));
// Sets the view to the interesting area
//QList<QPointF> view;
//view.append(QPointF(8.24764, 50.0319));
//view.append(QPointF(8.28412, 49.9998));
// mc->setView(view);
updatePosition(0, lat, lon);
}
}
......
......@@ -73,6 +73,7 @@ protected:
Layer* gSatLayer;
QMap<int, CirclePoint*> uasIcons;
QMap<int, LineString*> uasTrails;
UASInterface* mav;
quint64 lastUpdate;
......
......@@ -61,7 +61,7 @@ UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent)
// Set default values
/** Set two voltage decimals and zero charge level decimals **/
this->voltageDecimals = 2;
this->voltageDecimals = 2;
this->loadDecimals = 2;
this->voltage = 0;
......@@ -69,6 +69,7 @@ UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent)
this->load = 0;
receiveLoss = 0;
sendLoss = 0;
errors = QMap<QString, int>();
updateTimer = new QTimer(this);
connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh()));
......@@ -88,6 +89,7 @@ void UASInfoWidget::addUAS(UASInterface* uas)
connect(uas, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBattery(UASInterface*,double,double,int)));
connect(uas, SIGNAL(dropRateChanged(int,float)), this, SLOT(updateReceiveLoss(int,float)));
connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateCPULoad(UASInterface*,double)));
connect(uas, SIGNAL(errCountChanged(int,QString,QString,int)), this, SLOT(updateErrorCount(int,QString,QString,int)));
// Set this UAS as active if it is the first one
if (activeUAS == 0) activeUAS = uas;
......@@ -106,6 +108,16 @@ void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double perc
setTimeRemaining(uas, seconds);
}
void UASInfoWidget::updateErrorCount(int uasid, QString component, QString device, int count)
{
qDebug() << __FILE__ << __LINE__ << activeUAS->getUASID() << "=" << uasid;
if (activeUAS->getUASID() == uasid)
{
errors.remove(component + ":" + device);
errors.insert(component + ":" + device, count);
}
}
/**
*
*/
......@@ -168,4 +180,7 @@ void UASInfoWidget::refresh()
ui.sendLossBar->setValue(sendLoss);
ui.sendLossLabel->setText(QString::number(sendLoss, 'f', 2));
QString errorString;
// ui.
}
......@@ -60,6 +60,8 @@ public slots:
void updateReceiveLoss(int uasId, float receiveLoss);
/** @brief Set the loss rate of packets sent from the MAV */
void updateSendLoss(int uasId, float sendLoss);
/** @brief Update the error count */
void updateErrorCount(int uasid, QString component, QString device, int count);
void setVoltage(UASInterface* uas, double voltage);
void setChargeLevel(UASInterface* uas, double chargeLevel);
......@@ -90,6 +92,7 @@ protected:
QTimer* updateTimer;
QString name;
quint64 startTime;
QMap<QString, int> errors;
// double lastRemainingTime;
// double lastChargeLevel;
// double startVoltage;
......
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