Commit f7cef6a2 authored by LM's avatar LM

Merged

parents f4c240a1 604d976a
......@@ -207,6 +207,15 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// ORDER MATTERS HERE!
// If the matching UAS object does not yet exist, it has to be created
// before emitting the packetReceived signal
// BIG NASTY HACK
//TODO
//BUG
//BAD
//FIXME
if (message.sysid == 35)
message.sysid = 42;
UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);
// Check and (if necessary) create UAS object
......
......@@ -379,7 +379,8 @@ void MAVLinkSimulationLink::mainloop()
// Send back new setpoint
mavlink_message_t ret;
mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, MAV_FRAME_LOCAL_NED, spX, spY, spZ, spYaw);
mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, MAV_FRAME_LOCAL_NED, spX, spY, spZ, spYaw); // spYaw/180.0*M_PI);
mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, spX, spY, spZ,
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......
......@@ -72,7 +72,7 @@ pitch(0.0),
yaw(0.0),
statusTimeout(new QTimer(this)),
paramsOnceRequested(false),
airframe(0),
airframe(QGC_AIRFRAME_EASYSTAR),
attitudeKnown(false),
paramManager(NULL),
attitudeStamped(false),
......@@ -957,7 +957,7 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t msg;
mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
mavlink_msg_local_position_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw/M_PI*180.0);
sendMessage(msg);
#else
Q_UNUSED(x);
......
......@@ -96,6 +96,26 @@ bool UASManager::setHomePosition(double lat, double lon, double alt)
return changed;
}
/**
* @param x1 Point 1 coordinate in x dimension
* @param y1 Point 1 coordinate in y dimension
* @param z1 Point 1 coordinate in z dimension
*
* @param x2 Point 2 coordinate in x dimension
* @param y2 Point 2 coordinate in y dimension
* @param z2 Point 2 coordinate in z dimension
*/
void UASManager::setLocalNEDSafetyBorders(double x1, double y1, double z1, double x2, double y2, double z2)
{
nedSafetyLimitPosition1.x() = x1;
nedSafetyLimitPosition1.y() = y1;
nedSafetyLimitPosition1.z() = z1;
nedSafetyLimitPosition2.x() = x2;
nedSafetyLimitPosition2.y() = y2;
nedSafetyLimitPosition2.z() = z2;
}
void UASManager::initReference(const double & latitude, const double & longitude, const double & altitude)
{
......@@ -198,6 +218,7 @@ UASManager::UASManager() :
{
start(QThread::LowPriority);
loadSettings();
setLocalNEDSafetyBorders(1, -1, 0, -1, 1, -1);
}
UASManager::~UASManager()
......
......@@ -92,6 +92,37 @@ public:
/** @brief Convert WGS84 lat/lon coordinates to carthesian coordinates with home position as origin */
void wgs84ToEnu(const double& lat, const double& lon, const double& alt, double* east, double* north, double* up);
void getLocalNEDSafetyLimits(double* x1, double* y1, double* z1, double* x2, double* y2, double* z2)
{
*x1 = nedSafetyLimitPosition1.x();
*y1 = nedSafetyLimitPosition1.y();
*z1 = nedSafetyLimitPosition1.z();
*x2 = nedSafetyLimitPosition2.x();
*y2 = nedSafetyLimitPosition2.y();
*z2 = nedSafetyLimitPosition2.z();
}
/** @brief Check if a position is in the local NED safety limits */
bool isInLocalNEDSafetyLimits(double x, double y, double z)
{
if (x < nedSafetyLimitPosition1.x() &&
y > nedSafetyLimitPosition1.y() &&
z < nedSafetyLimitPosition1.z() &&
x > nedSafetyLimitPosition2.x() &&
y < nedSafetyLimitPosition2.y() &&
z > nedSafetyLimitPosition2.z())
{
// Within limits
return true;
}
else
{
// Not within limits
return false;
}
}
// void wgs84ToNed(const double& lat, const double& lon, const double& alt, double* north, double* east, double* down);
......@@ -188,6 +219,9 @@ public slots:
/** @brief Set the current home position on all UAVs*/
bool setHomePosition(double lat, double lon, double alt);
/** @brief Set the safety limits in local position frame */
void setLocalNEDSafetyBorders(double x1, double y1, double z1, double x2, double y2, double z2);
/** @brief Update home position based on the position from one of the UAVs */
void uavChangedHomePosition(int uav, double lat, double lon, double alt);
......@@ -207,6 +241,8 @@ protected:
double homeAlt;
Eigen::Quaterniond ecef_ref_orientation_;
Eigen::Vector3d ecef_ref_point_;
Eigen::Vector3d nedSafetyLimitPosition1;
Eigen::Vector3d nedSafetyLimitPosition2;
void initReference(const double & latitude, const double & longitude, const double & altitude);
......
This diff is collapsed.
......@@ -85,6 +85,14 @@ public slots:
void pressKey(int key);
/** @brief Reset the state of the view */
void resetMAVState();
/** @brief Clear the status message */
void clearStatusMessage()
{
statusMessage = "";
if (actionPending) statusMessage = "TIMED OUT, NO ACTION";
statusClearTimer.start();
actionPending = false;
}
signals:
void metricWidthChanged(double width);
......@@ -101,19 +109,33 @@ protected slots:
/** @brief Draw a position lock indicator */
void drawPositionLock(float x, float y, QString label, int status, bool known, QPainter& painter);
void setBodySetpointCoordinateXY(double x, double y);
void setBodySetpointCoordinateYaw(double yaw);
void setBodySetpointCoordinateZ(double z);
/** @brief Send the current ui setpoint coordinates as new setpoint to the MAV */
void sendBodySetPointCoordinates();
/** @brief Draw one setpoint */
void drawSetpointXY(float x, float y, float yaw, const QColor &color, QPainter &painter);
void drawSetpointXYZYaw(float x, float y, float z, float yaw, const QColor &color, QPainter &painter);
/** @brief Draw waypoints of this system */
void drawWaypoints(QPainter& painter);
/** @brief Draw the limiting safety area */
void drawSafetyArea(const QPointF &topLeft, const QPointF &bottomRight, const QColor &color, QPainter &painter);
/** @brief Receive mouse clicks */
void mouseDoubleClickEvent(QMouseEvent* event);
void mousePressEvent(QMouseEvent * event);
void mouseReleaseEvent(QMouseEvent * event);
void mouseMoveEvent(QMouseEvent * event);
/** @brief Receive mouse wheel events */
void wheelEvent(QWheelEvent* event);
/** @brief Read out send keys */
void keyPressEvent(QKeyEvent* event);
/** @brief Ignore context menu event */
void contextMenuEvent (QContextMenuEvent* event);
/** @brief Set status message on screen */
void setStatusMessage(const QString& message)
{
statusMessage = message;
statusClearTimer.start();
}
protected:
......@@ -131,6 +153,10 @@ protected:
QPointF refToMetricBody(QPointF &ref);
/** @brief Metric coordinates to reference coordinates */
QPointF metricBodyToRef(QPointF &metric);
/** @brief Metric length to reference coordinates */
double metricToRef(double metric);
/** @bried Reference coordinates to metric length */
double refToMetric(double ref);
/** @brief Metric body coordinates to screen coordinates */
QPointF metricBodyToScreen(QPointF metric);
QMap<int, QString> objectNames;
......@@ -138,6 +164,14 @@ protected:
QMap<int, float> objectQualities;
QMap<int, float> objectBearings;
QMap<int, float> objectDistances;
bool dragStarted;
bool leftDragStarted;
bool mouseHasMoved;
float startX;
float startY;
QTimer statusClearTimer;
QString statusMessage;
bool actionPending;
/**
* @brief Private data container class to be used within the HSI widget
......@@ -254,7 +288,8 @@ protected:
// Data indicators
bool setPointKnown; ///< Controller setpoint known status flag
bool positionSetPointKnown; ///< Position setpoint known status flag
bool userSetPointSet;
bool userSetPointSet; ///< User set X, Y and Z
bool userXYSetPointSet; ///< User set the X/Y position already
private:
};
......
......@@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>662</width>
<height>381</height>
<width>833</width>
<height>585</height>
</rect>
</property>
<property name="sizePolicy">
......@@ -25,23 +25,8 @@
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2" stretch="10,20">
<property name="spacing">
<number>3</number>
</property>
<property name="leftMargin">
<number>2</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>2</number>
</property>
<property name="bottomMargin">
<number>2</number>
</property>
<item>
<layout class="QGridLayout" name="gridLayout" columnstretch="5,5,5,5,100">
<item row="0" column="0" colspan="4">
<widget class="QGroupBox" name="curveGroupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="MinimumExpanding">
......@@ -114,8 +99,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>210</width>
<height>361</height>
<width>232</width>
<height>516</height>
</rect>
</property>
</widget>
......@@ -124,7 +109,7 @@
</layout>
</widget>
</item>
<item>
<item row="0" column="4" rowspan="2">
<widget class="QGroupBox" name="diagramGroupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
......@@ -149,6 +134,33 @@
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QCheckBox" name="shortNameCheckBox">
<property name="text">
<string>Short Names</string>
</property>
</widget>
</item>
<item row="1" column="2" colspan="2">
<widget class="QPushButton" name="recolorButton">
<property name="text">
<string>Recolor</string>
</property>
</widget>
</item>
<item row="1" column="1">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<resources/>
......
......@@ -64,7 +64,7 @@ QGCToolBar::QGCToolBar(QWidget *parent) :
toolBarBatteryBar->setMinimum(0);
toolBarBatteryBar->setMaximum(100);
toolBarBatteryBar->setMinimumWidth(20);
toolBarBatteryBar->setMaximumWidth(200);
toolBarBatteryBar->setMaximumWidth(100);
toolBarBatteryVoltageLabel = new QLabel("xx.x V");
toolBarBatteryVoltageLabel->setStyleSheet(QString("QLabel { margin: 0px 0px 0px 4px; font: 14px; color: %1; }").arg(QColor(Qt::green).name()));
symbolButton->setStyleSheet("QWidget { background-color: #050508; color: #DDDDDF; background-clip: border; } QToolButton { font-weight: bold; font-size: 12px; border: 0px solid #999999; border-radius: 5px; min-width:22px; max-width: 22px; min-height: 22px; max-height: 22px; padding: 0px; margin: 0px 0px 0px 20px; background-color: none; }");
......
......@@ -210,7 +210,7 @@ void WaypointList::addCurrentPositonWaypoint()
yawGlobal = last->getYaw();
}
// Create global frame waypoint per default
wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitude(), yawGlobal, acceptanceRadiusGlobal, holdTime, 0.0, true, true, MAV_FRAME_GLOBAL_RELATIVE_ALT, MAV_CMD_NAV_WAYPOINT);
wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitude(), 0, acceptanceRadiusGlobal, holdTime, yawGlobal, true, true, MAV_FRAME_GLOBAL_RELATIVE_ALT, MAV_CMD_NAV_WAYPOINT);
uas->getWaypointManager()->addWaypoint(wp);
updateStatusLabel(tr("Added GLOBAL, ALTITUDE OVER GROUND waypoint"));
}
......
......@@ -53,6 +53,7 @@ QGCCommandButton::QGCCommandButton(QWidget *parent) :
ui->editCommandComboBox->addItem("CUSTOM 13", 13);
ui->editCommandComboBox->addItem("CUSTOM 14", 14);
ui->editCommandComboBox->addItem("CUSTOM 15", 15);
ui->editCommandComboBox->addItem("NAV_WAYPOINT", 16);
ui->editCommandComboBox->setEditable(true);
}
......@@ -75,6 +76,7 @@ void QGCCommandButton::sendCommand()
int component = ui->editComponentSpinBox->value();
QGCToolWidgetItem::uas->executeCommand(command, confirm, param1, param2, param3, param4, component);
qDebug() << __FILE__ << __LINE__ << "SENDING COMMAND" << index;
} else {
qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
}
......
......@@ -127,6 +127,7 @@ LinechartPlot::LinechartPlot(QWidget *parent, int plotid, quint64 interval): Qwt
//updateTimer->start(DEFAULT_REFRESH_RATE);
connect(&timeoutTimer, SIGNAL(timeout()), this, SLOT(removeTimedOutCurves()));
//timeoutTimer.start(5000);
}
LinechartPlot::~LinechartPlot()
......@@ -208,7 +209,7 @@ void LinechartPlot::removeTimedOutCurves()
foreach(QString key, lastUpdate.keys())
{
quint64 time = lastUpdate.value(key);
if (QGC::groundTimeMilliseconds() - time > 20000)
if (QGC::groundTimeMilliseconds() - time > 10000)
{
// Remove this curve
// Delete curves
......@@ -227,6 +228,7 @@ void LinechartPlot::removeTimedOutCurves()
delete d;
// Set the pointer null
d = NULL;
emit curveRemoved(key);
}
}
}
......
......@@ -269,6 +269,17 @@ public slots:
void setAverageWindow(int windowSize);
void removeTimedOutCurves();
/** @brief Reset color map */
void shuffleColors()
{
foreach (QwtPlotCurve* curve, curves)
{
QPen pen(curve->pen());
pen.setColor(getNextColor());
curve->setPen(pen);
}
}
public:
QColor getColorForCurve(QString id);
......
......@@ -76,7 +76,7 @@ LinechartWidget::LinechartWidget(int systemid, QWidget *parent) : QWidget(parent
{
// Add elements defined in Qt Designer
ui.setupUi(this);
this->setMinimumSize(300, 200);
this->setMinimumSize(200, 150);
// Add and customize curve list elements (left side)
curvesWidget = new QWidget(ui.curveListWidget);
......@@ -104,7 +104,8 @@ LinechartWidget::LinechartWidget(int systemid, QWidget *parent) : QWidget(parent
QLabel* mean;
QLabel* variance;
//horizontalLayout->addWidget(checkBox);
connect(ui.recolorButton, SIGNAL(clicked()), this, SLOT(recolor()));
connect(ui.shortNameCheckBox, SIGNAL(clicked(bool)), this, SLOT(setShortNames(bool)));
int labelRow = curvesWidgetLayout->rowCount();
......@@ -170,6 +171,7 @@ void LinechartWidget::writeSettings()
settings.beginGroup("LINECHART");
if (timeButton) settings.setValue("ENFORCE_GROUNDTIME", timeButton->isChecked());
if (unitsCheckBox) settings.setValue("SHOW_UNITS", unitsCheckBox->isChecked());
if (ui.shortNameCheckBox) settings.setValue("SHORT_NAMES", ui.shortNameCheckBox->isChecked());
settings.endGroup();
settings.sync();
}
......@@ -183,7 +185,8 @@ void LinechartWidget::readSettings()
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());
if (unitsCheckBox) unitsCheckBox->setChecked(settings.value("SHOW_UNITS", unitsCheckBox->isChecked()).toBool());
if (ui.shortNameCheckBox) ui.shortNameCheckBox->setChecked(settings.value("SHORT_NAMES", ui.shortNameCheckBox->isChecked()).toBool());
settings.endGroup();
}
......@@ -280,7 +283,8 @@ void LinechartWidget::createLayout()
connect(this, SIGNAL(curveRemoved(QString)), activePlot, SLOT(hideCurve(QString)));
// Update scrollbar when plot window changes (via translator method setPlotWindowPosition()
connect(activePlot, SIGNAL(windowPositionChanged(quint64)), this, SLOT(setPlotWindowPosition(quint64)));
// connect(activePlot, SIGNAL(windowPositionChanged(quint64)), this, SLOT(setPlotWindowPosition(quint64)));
connect(activePlot, SIGNAL(curveRemoved(QString)), this, SLOT(removeCurve(QString)));
// Update plot when scrollbar is moved (via translator method setPlotWindowPosition()
connect(this, SIGNAL(plotWindowPositionUpdated(quint64)), activePlot, SLOT(setWindowPosition(quint64)));
......@@ -614,6 +618,8 @@ void LinechartWidget::addCurve(const QString& curve, const QString& unit)
QLabel* mean;
QLabel* variance;
curveNames.insert(curve+unit, curve);
int labelRow = curvesWidgetLayout->rowCount();
checkBox = new QCheckBox(this);
......@@ -642,6 +648,9 @@ void LinechartWidget::addCurve(const QString& curve, const QString& unit)
colorIcon->setStyleSheet(colorstyle);
colorIcon->setAutoFillBackground(true);
// Label
curveNameLabels.insert(curve+unit, label);
// Value
value = new QLabel(this);
value->setNum(0.00);
......@@ -720,8 +729,96 @@ void LinechartWidget::addCurve(const QString& curve, const QString& unit)
void LinechartWidget::removeCurve(QString curve)
{
Q_UNUSED(curve)
//TODO @todo Ensure that the button for a curve gets deleted when the original curve is deleted
// Remove name
QWidget* widget = NULL;
widget = curveLabels->take(curve);
curvesWidgetLayout->removeWidget(widget);
widget->deleteLater();
widget = curveMeans->take(curve);
curvesWidgetLayout->removeWidget(widget);
widget->deleteLater();
widget = curveMedians->take(curve);
curvesWidgetLayout->removeWidget(widget);
widget->deleteLater();
widget = curveVariances->take(curve);
curvesWidgetLayout->removeWidget(widget);
widget->deleteLater();
// widget = colorIcons->take(curve);
// curvesWidgetLayout->removeWidget(colorIcons->take(curve));
widget->deleteLater();
// intData->remove(curve);
}
void LinechartWidget::recolor()
{
activePlot->shuffleColors();
foreach (QString key, colorIcons.keys())
{
// FIXME
// if (activePlot)
QString colorstyle;
QColor color = activePlot->getColorForCurve(key);
colorstyle = colorstyle.sprintf("QWidget { background-color: #%X%X%X; }", color.red(), color.green(), color.blue());
QWidget* colorIcon = colorIcons.value(key, 0);
if (colorIcon)
{
colorIcon->setStyleSheet(colorstyle);
colorIcon->setAutoFillBackground(true);
}
}
}
void LinechartWidget::setShortNames(bool enable)
{
foreach (QString key, curveNames.keys())
{
QString name;
if (enable)
{
QStringList parts = curveNames.value(key).split(".");
if (parts.length() > 1)
{
name = parts.at(1);
}
else
{
name = parts.at(0);
}
const unsigned int sizeLimit = 10;
// Replace known words with abbreviations
if (name.length() > sizeLimit)
{
name.replace("gyroscope", "gyro");
name.replace("accelerometer", "acc");
name.replace("magnetometer", "mag");
name.replace("distance", "dist");
name.replace("altitude", "alt");
name.replace("waypoint", "wp");
name.replace("error", "err");
name.replace("message", "msg");
name.replace("source", "src");
}
// Check if sub-part is still exceeding N chars
if (name.length() > sizeLimit)
{
name.replace("a", "");
name.replace("e", "");
name.replace("i", "");
name.replace("o", "");
name.replace("u", "");
}
}
else
{
name = curveNames.value(key);
}
curveNameLabels.value(key)->setText(name);
}
}
void LinechartWidget::showEvent(QShowEvent* event)
......
......@@ -73,6 +73,10 @@ public:
public slots:
void addCurve(const QString& curve, const QString& unit);
void removeCurve(QString curve);
/** @brief Recolor all curves */
void recolor();
/** @brief Set short names for curves */
void setShortNames(bool enable);
/** @brief Append data without unit */
void appendData(int uasId, QString curve, double data, quint64 usec);
/** @brief Append data with unit */
......@@ -130,6 +134,8 @@ protected:
int curveListCounter; ///< Counter of curves in curve list
QList<QString>* listedCurves; ///< Curves listed
QMap<QString, QLabel*>* curveLabels; ///< References to the curve labels
QMap<QString, QLabel*> curveNameLabels; ///< References to the curve labels
QMap<QString, QString> curveNames; ///< Full curve names
QMap<QString, QLabel*>* curveMeans; ///< References to the curve means
QMap<QString, QLabel*>* curveMedians; ///< References to the curve medians
QMap<QString, QLabel*>* curveVariances; ///< References to the curve variances
......
......@@ -114,8 +114,8 @@ void UASListWidget::activeUAS(UASInterface* uas)
void UASListWidget::removeUAS(UASInterface* uas)
{
uasViews.remove(uas);
listLayout->removeWidget(uasViews.value(uas));
uasViews.value(uas)->deleteLater();
// uasViews.remove(uas);
// listLayout->removeWidget(uasViews.value(uas));
// uasViews.value(uas)->deleteLater();
}
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