Commit daf07a1f authored by pixhawk's avatar pixhawk

Merge branch 'master' of git@pixhawk.ethz.ch:qgroundcontrol

parents 3e803237 09ebae05
#include "PxQuadMAV.h" #include "PxQuadMAV.h"
#include "GAudioOutput.h"
PxQuadMAV::PxQuadMAV(MAVLinkProtocol* mavlink, int id) : PxQuadMAV::PxQuadMAV(MAVLinkProtocol* mavlink, int id) :
UAS(mavlink, id) UAS(mavlink, id)
...@@ -60,6 +61,31 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -60,6 +61,31 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, str+".z", vect.z, MG::TIME::getGroundTimeNow()); emit valueChanged(uasId, str+".z", vect.z, MG::TIME::getGroundTimeNow());
} }
break; break;
case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
{
mavlink_vision_position_estimate_t pos;
mavlink_msg_vision_position_estimate_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec);
emit valueChanged(uasId, "vis. time", pos.usec, time);
emit valueChanged(uasId, "vis. roll", pos.roll, time);
emit valueChanged(uasId, "vis. pitch", pos.pitch, time);
emit valueChanged(uasId, "vis. yaw", pos.yaw, time);
emit valueChanged(uasId, "vis. x", pos.x, time);
emit valueChanged(uasId, "vis. y", pos.y, time);
emit valueChanged(uasId, "vis. z", pos.z, time);
emit valueChanged(uasId, "vis. vx", pos.vx, time);
emit valueChanged(uasId, "vis. vy", pos.vy, time);
emit valueChanged(uasId, "vis. vz", pos.vz, time);
emit valueChanged(uasId, "vis. vyaw", pos.vyaw, time);
// Set internal state
if (!positionLock)
{
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
}
break;
default: default:
// Do nothing // Do nothing
break; break;
......
...@@ -254,6 +254,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -254,6 +254,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_aux_status_t status; mavlink_aux_status_t status;
mavlink_msg_aux_status_decode(&message, &status); mavlink_msg_aux_status_decode(&message, &status);
emit loadChanged(this, status.load/10.0f); 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()); emit valueChanged(this, "Load", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow());
} }
break; break;
...@@ -302,37 +307,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -302,37 +307,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit attitudeChanged(this, mavlink_msg_attitude_get_roll(&message), mavlink_msg_attitude_get_pitch(&message), mavlink_msg_attitude_get_yaw(&message), time); emit attitudeChanged(this, mavlink_msg_attitude_get_roll(&message), mavlink_msg_attitude_get_pitch(&message), mavlink_msg_attitude_get_yaw(&message), time);
} }
break; break;
case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
{
mavlink_vision_position_estimate_t pos;
mavlink_msg_vision_position_estimate_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec);
emit valueChanged(uasId, "vis. time", pos.usec, time);
emit valueChanged(uasId, "vis. roll", pos.roll, time);
emit valueChanged(uasId, "vis. pitch", pos.pitch, time);
emit valueChanged(uasId, "vis. yaw", pos.yaw, time);
emit valueChanged(uasId, "vis. x", pos.x, time);
emit valueChanged(uasId, "vis. y", pos.y, time);
emit valueChanged(uasId, "vis. z", pos.z, time);
// FIXME Only for testing for now
emit valueChanged(uasId, "vis. rot r1", pos.r1, time);
emit valueChanged(uasId, "vis. rot r2", pos.r2, time);
emit valueChanged(uasId, "vis. rot r3", pos.r3, time);
emit valueChanged(uasId, "vis. rot r4", pos.r4, time);
emit valueChanged(uasId, "vis. rot r5", pos.r5, time);
emit valueChanged(uasId, "vis. rot r6", pos.r6, time);
emit valueChanged(uasId, "vis. rot r7", pos.r7, time);
emit valueChanged(uasId, "vis. rot r8", pos.r8, time);
emit valueChanged(uasId, "vis. rot r9", pos.r9, time);
// Set internal state
if (!positionLock)
{
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
}
break;
case MAVLINK_MSG_ID_LOCAL_POSITION: case MAVLINK_MSG_ID_LOCAL_POSITION:
//std::cerr << std::endl; //std::cerr << std::endl;
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl; //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
......
...@@ -232,6 +232,21 @@ signals: ...@@ -232,6 +232,21 @@ signals:
* @param severity The severity of the message, 0 for plain debug messages, 10 for very critical messages * @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); 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 * @brief Drop rate of communication link updated
* *
......
...@@ -34,9 +34,13 @@ This file is part of the PIXHAWK project ...@@ -34,9 +34,13 @@ This file is part of the PIXHAWK project
#include "UASInterface.h" #include "UASInterface.h"
#include "UASManager.h" #include "UASManager.h"
#include "MG.h"
MapWidget::MapWidget(QWidget *parent) : MapWidget::MapWidget(QWidget *parent) :
QWidget(parent), QWidget(parent),
zoomLevel(0), zoomLevel(0),
uasIcons(),
uasTrails(),
m_ui(new Ui::MapWidget) m_ui(new Ui::MapWidget)
{ {
m_ui->setupUi(this); m_ui->setupUi(this);
...@@ -48,6 +52,8 @@ MapWidget::MapWidget(QWidget *parent) : ...@@ -48,6 +52,8 @@ MapWidget::MapWidget(QWidget *parent) :
mc->showScale(true); mc->showScale(true);
mc->enablePersistentCache(); mc->enablePersistentCache();
//uasIcons = QMap<int, CirclePoint*>();
//QSize(480,640) //QSize(480,640)
// ImageManager::instance()->setProxy("www-cache", 8080); // ImageManager::instance()->setProxy("www-cache", 8080);
...@@ -74,7 +80,7 @@ MapWidget::MapWidget(QWidget *parent) : ...@@ -74,7 +80,7 @@ MapWidget::MapWidget(QWidget *parent) :
QPushButton* zoomout = new QPushButton(QIcon(":/images/actions/list-remove.svg"), "", this); QPushButton* zoomout = new QPushButton(QIcon(":/images/actions/list-remove.svg"), "", this);
followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this); followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this);
followgps->setCheckable(true); followgps->setCheckable(true);
// gpsposition = new QLabel(); // gpsposition = new QLabel();
zoomin->setMaximumWidth(50); zoomin->setMaximumWidth(50);
zoomout->setMaximumWidth(50); zoomout->setMaximumWidth(50);
followgps->setMaximumWidth(50); followgps->setMaximumWidth(50);
...@@ -120,38 +126,67 @@ void MapWidget::addUAS(UASInterface* uas) ...@@ -120,38 +126,67 @@ void MapWidget::addUAS(UASInterface* uas)
void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec) void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
{ {
Q_UNUSED(usec); Q_UNUSED(usec);
// create a LineString quint64 currTime = MG::TIME::getGroundTimeNow();
QList<Point*> points; if (currTime - lastUpdate > 90)
// Points with a circle {
// A QPen can be used to customize the lastUpdate = currTime;
QPen* pointpen = new QPen(uas->getColor()); // create a LineString
pointpen->setWidth(3); //QList<Point*> points;
points.append(new CirclePoint(lat, lon, alt, uas->getUASName(), Point::Middle, pointpen)); // Points with a circle
// points.append(new CirclePoint(8.275145, 50.016992, 15, "Wiesbaden-Mainz-Kastel, Johannes-Goßner-Straße", Point::Middle, pointpen)); // A QPen can be used to customize the
// points.append(new CirclePoint(8.270476, 50.021426, 15, "Wiesbaden-Mainz-Kastel, Ruthof", Point::Middle, pointpen)); //pointpen->setWidth(3);
// // "Blind" Points //points.append(new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen));
// 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")); if (!uasIcons.contains(uas->getUASID()))
{
// A QPen also can use transparency // Get the UAS color
QPen* linepen = new QPen(QColor(0, 0, 255, 100)); QColor uasColor = uas->getColor();
linepen->setWidth(5);
// Add the Points and the QPen to a LineString // Icon
LineString* ls = new LineString(points, "Path", linepen); QPen* pointpen = new QPen(uasColor);
CirclePoint* p = new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen);
// Add the LineString to the layer uasIcons.insert(uas->getUASID(), p);
osmLayer->addGeometry(ls); osmLayer->addGeometry(p);
// Connect click events of the layer to this object // Line
//connect(osmLayer, SIGNAL(geometryClicked(Geometry*, QPoint)), // A QPen also can use transparency
// this, SLOT(geometryClicked(Geometry*, QPoint)));
QList<Point*> points;
// Sets the view to the interesting area points.append(new Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
//QList<QPointF> view; QPen* linepen = new QPen(uasColor.darker());
//view.append(QPointF(8.24764, 50.0319)); linepen->setWidth(2);
//view.append(QPointF(8.28412, 49.9998)); // Add the Points and the QPen to a LineString
// mc->setView(view); LineString* ls = new LineString(points, uas->getUASName(), linepen);
updatePosition(0, lat, lon); 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);
}
} }
......
...@@ -33,6 +33,7 @@ This file is part of the PIXHAWK project ...@@ -33,6 +33,7 @@ This file is part of the PIXHAWK project
#define MAPWIDGET_H #define MAPWIDGET_H
#include <QtGui/QWidget> #include <QtGui/QWidget>
#include <QMap>
#include "qmapcontrol.h" #include "qmapcontrol.h"
#include "UASInterface.h" #include "UASInterface.h"
...@@ -71,7 +72,10 @@ protected: ...@@ -71,7 +72,10 @@ protected:
Layer* osmLayer; Layer* osmLayer;
Layer* gSatLayer; Layer* gSatLayer;
QMap<int, CirclePoint*> uasIcons;
QMap<int, LineString*> uasTrails;
UASInterface* mav; UASInterface* mav;
quint64 lastUpdate;
private: private:
Ui::MapWidget *m_ui; Ui::MapWidget *m_ui;
......
...@@ -61,7 +61,7 @@ UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent) ...@@ -61,7 +61,7 @@ UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent)
// Set default values // Set default values
/** Set two voltage decimals and zero charge level decimals **/ /** Set two voltage decimals and zero charge level decimals **/
this->voltageDecimals = 2; this->voltageDecimals = 2;
this->loadDecimals = 2; this->loadDecimals = 2;
this->voltage = 0; this->voltage = 0;
...@@ -69,6 +69,7 @@ UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent) ...@@ -69,6 +69,7 @@ UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent)
this->load = 0; this->load = 0;
receiveLoss = 0; receiveLoss = 0;
sendLoss = 0; sendLoss = 0;
errors = QMap<QString, int>();
updateTimer = new QTimer(this); updateTimer = new QTimer(this);
connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh())); connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh()));
...@@ -88,6 +89,7 @@ void UASInfoWidget::addUAS(UASInterface* uas) ...@@ -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(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(dropRateChanged(int,float)), this, SLOT(updateReceiveLoss(int,float)));
connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateCPULoad(UASInterface*,double))); 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 // Set this UAS as active if it is the first one
if (activeUAS == 0) activeUAS = uas; if (activeUAS == 0) activeUAS = uas;
...@@ -106,6 +108,16 @@ void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double perc ...@@ -106,6 +108,16 @@ void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double perc
setTimeRemaining(uas, seconds); 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() ...@@ -168,4 +180,7 @@ void UASInfoWidget::refresh()
ui.sendLossBar->setValue(sendLoss); ui.sendLossBar->setValue(sendLoss);
ui.sendLossLabel->setText(QString::number(sendLoss, 'f', 2)); ui.sendLossLabel->setText(QString::number(sendLoss, 'f', 2));
QString errorString;
// ui.
} }
...@@ -60,6 +60,8 @@ public slots: ...@@ -60,6 +60,8 @@ public slots:
void updateReceiveLoss(int uasId, float receiveLoss); void updateReceiveLoss(int uasId, float receiveLoss);
/** @brief Set the loss rate of packets sent from the MAV */ /** @brief Set the loss rate of packets sent from the MAV */
void updateSendLoss(int uasId, float sendLoss); 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 setVoltage(UASInterface* uas, double voltage);
void setChargeLevel(UASInterface* uas, double chargeLevel); void setChargeLevel(UASInterface* uas, double chargeLevel);
...@@ -90,6 +92,7 @@ protected: ...@@ -90,6 +92,7 @@ protected:
QTimer* updateTimer; QTimer* updateTimer;
QString name; QString name;
quint64 startTime; quint64 startTime;
QMap<QString, int> errors;
// double lastRemainingTime; // double lastRemainingTime;
// double lastChargeLevel; // double lastChargeLevel;
// double startVoltage; // 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