Commit 7e910bba authored by Bryan Godbolt's avatar Bryan Godbolt

Merge branch 'master' of git://github.com/pixhawk/qgroundcontrol into dev

parents fa567258 c3496c0e
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<?fileVersion 4.0.0?>
<cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
<storageModule moduleId="org.eclipse.cdt.core.settings">
<cconfiguration id="org.eclipse.cdt.core.default.config.989472769">
<storageModule buildSystemId="org.eclipse.cdt.core.defaultConfigDataProvider" id="org.eclipse.cdt.core.default.config.989472769" moduleId="org.eclipse.cdt.core.settings" name="Configuration">
<externalSettings/>
<extensions>
<extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
<extension id="org.eclipse.cdt.core.PE" point="org.eclipse.cdt.core.BinaryParser"/>
</extensions>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
<storageModule moduleId="scannerConfiguration">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="org.eclipse.cdt.make.core.GCCStandardMakePerProjectProfile"/>
<profile id="org.eclipse.cdt.make.core.GCCStandardMakePerProjectProfile">
<buildOutputProvider>
<openAction enabled="true" filePath=""/>
<parser enabled="true"/>
</buildOutputProvider>
<scannerInfoProvider id="specsFile">
<runAction arguments="-E -P -v -dD ${plugin_state_location}/${specs_file}" command="gcc" useDefault="true"/>
<parser enabled="true"/>
</scannerInfoProvider>
</profile>
<profile id="org.eclipse.cdt.make.core.GCCStandardMakePerFileProfile">
<buildOutputProvider>
<openAction enabled="true" filePath=""/>
<parser enabled="true"/>
</buildOutputProvider>
<scannerInfoProvider id="makefileGenerator">
<runAction arguments="-E -P -v -dD" command="" useDefault="true"/>
<parser enabled="true"/>
</scannerInfoProvider>
</profile>
<profile id="org.eclipse.cdt.managedbuilder.core.GCCManagedMakePerProjectProfile">
<buildOutputProvider>
<openAction enabled="true" filePath=""/>
<parser enabled="true"/>
</buildOutputProvider>
<scannerInfoProvider id="specsFile">
<runAction arguments="-E -P -v -dD ${plugin_state_location}/${specs_file}" command="gcc" useDefault="true"/>
<parser enabled="true"/>
</scannerInfoProvider>
</profile>
<profile id="org.eclipse.cdt.managedbuilder.core.GCCManagedMakePerProjectProfileCPP">
<buildOutputProvider>
<openAction enabled="true" filePath=""/>
<parser enabled="true"/>
</buildOutputProvider>
<scannerInfoProvider id="specsFile">
<runAction arguments="-E -P -v -dD ${plugin_state_location}/specs.cpp" command="g++" useDefault="true"/>
<parser enabled="true"/>
</scannerInfoProvider>
</profile>
<profile id="org.eclipse.cdt.managedbuilder.core.GCCManagedMakePerProjectProfileC">
<buildOutputProvider>
<openAction enabled="true" filePath=""/>
<parser enabled="true"/>
</buildOutputProvider>
<scannerInfoProvider id="specsFile">
<runAction arguments="-E -P -v -dD ${plugin_state_location}/specs.c" command="gcc" useDefault="true"/>
<parser enabled="true"/>
</scannerInfoProvider>
</profile>
<profile id="org.eclipse.cdt.managedbuilder.core.GCCWinManagedMakePerProjectProfile">
<buildOutputProvider>
<openAction enabled="true" filePath=""/>
<parser enabled="true"/>
</buildOutputProvider>
<scannerInfoProvider id="specsFile">
<runAction arguments="-c 'gcc -E -P -v -dD &quot;${plugin_state_location}/${specs_file}&quot;'" command="sh" useDefault="true"/>
<parser enabled="true"/>
</scannerInfoProvider>
</profile>
<profile id="org.eclipse.cdt.managedbuilder.core.GCCWinManagedMakePerProjectProfileCPP">
<buildOutputProvider>
<openAction enabled="true" filePath=""/>
<parser enabled="true"/>
</buildOutputProvider>
<scannerInfoProvider id="specsFile">
<runAction arguments="-c 'g++ -E -P -v -dD &quot;${plugin_state_location}/specs.cpp&quot;'" command="sh" useDefault="true"/>
<parser enabled="true"/>
</scannerInfoProvider>
</profile>
<profile id="org.eclipse.cdt.managedbuilder.core.GCCWinManagedMakePerProjectProfileC">
<buildOutputProvider>
<openAction enabled="true" filePath=""/>
<parser enabled="true"/>
</buildOutputProvider>
<scannerInfoProvider id="specsFile">
<runAction arguments="-c 'gcc -E -P -v -dD &quot;${plugin_state_location}/specs.c&quot;'" command="sh" useDefault="true"/>
<parser enabled="true"/>
</scannerInfoProvider>
</profile>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.make.core.buildtargets">
<buildTargets>
<target name="Qt Release Build" path="" targetID="org.eclipse.cdt.make.MakeTargetBuilder">
<buildCommand>mingw32-make</buildCommand>
<buildArguments/>
<buildTarget>release</buildTarget>
<stopOnError>false</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="Qt Debug Build" path="" targetID="org.eclipse.cdt.make.MakeTargetBuilder">
<buildCommand>mingw32-make</buildCommand>
<buildArguments/>
<buildTarget>debug</buildTarget>
<stopOnError>false</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
</buildTargets>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.core.pathentry">
<pathentry base-path="C:/Qt/2010.04/qt/include" include="" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="ActiveQt" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="phonon" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="phonon_compat" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="Qt" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="Qt3Support" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtAssistant" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtCore" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtDBus" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtDeclarative" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtDesigner" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtGui" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtHelp" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtMultimedia" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtNetwork" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtOpenGL" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtOpenVG" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtScript" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtScriptTools" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtSql" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtSvg" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtTest" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtUiTools" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtWebKit" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtXml" kind="inc" path="" system="true"/>
<pathentry base-path="C:/Qt/2010.04/qt/include" include="QtXmlPatterns" kind="inc" path="" system="true"/>
</storageModule>
</cconfiguration>
</storageModule>
</cproject>
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>qgroundcontrol</name>
<comment></comment>
<projects>
</projects>
<buildSpec>
<buildCommand>
<name>com.trolltech.qtcppproject.QtMakefileGenerator</name>
<arguments>
</arguments>
</buildCommand>
<buildCommand>
<name>org.eclipse.cdt.make.core.makeBuilder</name>
<triggers>clean,full,incremental,</triggers>
<arguments>
<dictionary>
<key>org.eclipse.cdt.core.errorOutputParser</key>
<value>org.eclipse.cdt.core.GASErrorParser;org.eclipse.cdt.core.GCCErrorParser;org.eclipse.cdt.core.GLDErrorParser;org.eclipse.cdt.core.GmakeErrorParser;org.eclipse.cdt.core.VCErrorParser;org.eclipse.cdt.core.CWDLocator;org.eclipse.cdt.core.MakeErrorParser;</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.append_environment</key>
<value>true</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.build.arguments</key>
<value></value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.build.command</key>
<value>mingw32-make</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.build.target.auto</key>
<value>debug</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.build.target.clean</key>
<value>clean</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.build.target.inc</key>
<value>debug</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.enableAutoBuild</key>
<value>false</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.enableCleanBuild</key>
<value>true</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.enableFullBuild</key>
<value>true</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.enabledIncrementalBuild</key>
<value>true</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.environment</key>
<value>QMAKESPEC=win32-g++|PATH=C:\\Qt\\2010.04\\qt\\bin;${env_var:PATH}|</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.stopOnError</key>
<value>false</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key>
<value>false</value>
</dictionary>
</arguments>
</buildCommand>
<buildCommand>
<name>org.eclipse.cdt.make.core.ScannerConfigBuilder</name>
<arguments>
</arguments>
</buildCommand>
</buildSpec>
<natures>
<nature>org.eclipse.cdt.core.cnature</nature>
<nature>org.eclipse.cdt.core.ccnature</nature>
<nature>org.eclipse.cdt.make.core.makeNature</nature>
<nature>org.eclipse.cdt.make.core.ScannerConfigNature</nature>
<nature>com.trolltech.qtcppproject.QtNature</nature>
</natures>
</projectDescription>
......@@ -18,54 +18,54 @@ margin-top: 1ex; /* leave space at the top for the title */
QCheckBox {
/*background-color: #252528;*/
color: #DDDDDF;
}
QCheckBox::indicator {
border: 1px solid #777777;
border-radius: 2px;
color: #DDDDDF;
width: 10px;
height: 10px;
}
QLineEdit {
border: 1px solid #777777;
border-radius: 2px;
}
QTextEdit {
border: 1px solid #777777;
border-radius: 2px;
}
QPlainTextEdit {
border: 1px solid #777777;
border-radius: 2px;
}
QComboBox {
border: 1px solid #777777;
border-radius: 2px;
}
QCheckBox::indicator:checked {
background-color: #555555;
}
QCheckBox::indicator:checked:hover {
background-color: #555555;
}
QCheckBox::indicator:checked:pressed {
background-color: #555555;
}
QCheckBox::indicator:indeterminate:hover {
image: url(:/images/checkbox_indeterminate_hover.png);
}
QCheckBox::indicator:indeterminate:pressed {
image: url(:/images/checkbox_indeterminate_pressed.png);
}
QCheckBox::indicator {
border: 1px solid #777777;
border-radius: 2px;
color: #DDDDDF;
width: 10px;
height: 10px;
}
QLineEdit {
border: 1px solid #777777;
border-radius: 2px;
}
QTextEdit {
border: 1px solid #777777;
border-radius: 2px;
}
QPlainTextEdit {
border: 1px solid #777777;
border-radius: 2px;
}
QComboBox {
border: 1px solid #777777;
border-radius: 2px;
}
QCheckBox::indicator:checked {
background-color: #555555;
}
QCheckBox::indicator:checked:hover {
background-color: #555555;
}
QCheckBox::indicator:checked:pressed {
background-color: #555555;
}
QCheckBox::indicator:indeterminate:hover {
image: url(:/images/checkbox_indeterminate_hover.png);
}
QCheckBox::indicator:indeterminate:pressed {
image: url(:/images/checkbox_indeterminate_pressed.png);
}
QGroupBox::title {
......@@ -73,7 +73,7 @@ border: 1px solid #777777;
subcontrol-position: top center; /* position at the top center */
margin: 0 3px 0px 3px;
padding: 0 3px 0px 0px;
font: bold 8px;
font: bold 8px;
color: #DDDDDF;
}
......@@ -89,7 +89,7 @@ QDockWidget::close-button, QDockWidget::float-button {
QDockWidget::title {
text-align: left;
background: #121214;
background: #121214;
color: #4A4A4F;
padding-left: 5px;
height: 10px;
......@@ -102,46 +102,46 @@ QSeparator {
QSpinBox {
min-height: 14px;
max-height: 18px;
border: 1px solid #4A4A4F;
min-height: 14px;
max-height: 18px;
border: 1px solid #4A4A4F;
border-radius: 5px;
}
QSpinBox::up-button {
subcontrol-origin: border;
subcontrol-position: top right; /* position at the top right corner */
border-image: url(:/images/actions/go-up.svg) 1;
border-width: 1px;
}
QSpinBox::down-button {
subcontrol-origin: border;
subcontrol-position: bottom right; /* position at the top right corner */
border-image: url(:/images/actions/go-down.svg) 1;
border-width: 1px;
}
QDoubleSpinBox {
min-height: 14px;
max-height: 18px;
border: 1px solid #4A4A4F;
border-radius: 5px;
}
QDoubleSpinBox::up-button {
subcontrol-origin: border;
subcontrol-position: top right; /* position at the top right corner */
border-image: url(:/images/actions/go-up.svg) 1;
border-width: 1px;
max-width: 5px;
}
QDoubleSpinBox::down-button {
subcontrol-origin: border;
subcontrol-position: bottom right; /* position at the top right corner */
border-image: url(:/images/actions/go-down.svg) 1;
border-width: 1px;
max-width: 5px;
}
}
QSpinBox::up-button {
subcontrol-origin: border;
subcontrol-position: top right; /* position at the top right corner */
border-image: url(:/images/actions/go-up.svg) 1;
border-width: 1px;
}
QSpinBox::down-button {
subcontrol-origin: border;
subcontrol-position: bottom right; /* position at the top right corner */
border-image: url(:/images/actions/go-down.svg) 1;
border-width: 1px;
}
QDoubleSpinBox {
min-height: 14px;
max-height: 18px;
border: 1px solid #4A4A4F;
border-radius: 5px;
}
QDoubleSpinBox::up-button {
subcontrol-origin: border;
subcontrol-position: top right; /* position at the top right corner */
border-image: url(:/images/actions/go-up.svg) 1;
border-width: 1px;
max-width: 5px;
}
QDoubleSpinBox::down-button {
subcontrol-origin: border;
subcontrol-position: bottom right; /* position at the top right corner */
border-image: url(:/images/actions/go-down.svg) 1;
border-width: 1px;
max-width: 5px;
}
QPushButton {
font-weight: bold;
......@@ -155,7 +155,7 @@ QPushButton {
}
QPushButton:checked {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #101010, stop: 1 #404040);
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #404040, stop: 1 #808080);
}
QPushButton:pressed {
......@@ -170,8 +170,8 @@ QToolButton {
border: 2px solid #4A4A4F;
border-radius: 5px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208);
}
}
QToolButton:checked {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #090909, stop: 1 #353535);
}
......@@ -228,7 +228,7 @@ QPushButton:pressed#killButton {
border-radius: 5px;
}
QPushButton#controlButton {
QPushButton#controlButton {
min-height: 25px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #A0AE00, stop: 1 #909E00);
}
......@@ -268,4 +268,4 @@ QProgressBar::chunk#speedBar {
QProgressBar::chunk#thrustBar {
background-color: orange;
}
}
......@@ -29,9 +29,9 @@ namespace qmapcontrol
Geometry::Geometry(QString name)
: GeometryType("Geometry"), myparentGeometry(0), mypen(0), visible(true), myname(name)
{
myIndex = name.toInt(0,10);
}
Geometry::~Geometry()
{
}
......@@ -40,6 +40,11 @@ namespace qmapcontrol
{
return myname;
}
int Geometry::get_myIndex() const
{
return myIndex;
}
Geometry* Geometry::parentGeometry() const
{
return myparentGeometry;
......@@ -85,4 +90,5 @@ namespace qmapcontrol
{
return mypen;
}
}
......@@ -49,6 +49,7 @@ namespace qmapcontrol
Q_OBJECT
public:
explicit Geometry(QString name = QString());
virtual ~Geometry();
QString GeometryType;
......@@ -74,6 +75,12 @@ namespace qmapcontrol
*/
QString name() const;
//! returns the index of this Geometry
/*!
* @return the index of this Geometry
*/
int get_myIndex() const;
//! returns the parent Geometry of this Geometry
/*!
* A LineString is a composition of many Points. This methods returns the parent (the LineString) of a Point
......@@ -123,6 +130,7 @@ namespace qmapcontrol
QPen* mypen;
bool visible;
QString myname;
int myIndex;
void setParentGeometry(Geometry* geom);
signals:
......@@ -149,6 +157,8 @@ namespace qmapcontrol
* @param visible if the layer should be visible
*/
virtual void setVisible(bool visible);
};
}
#endif
......@@ -29,6 +29,7 @@ namespace qmapcontrol
Layer::Layer(QString layername, MapAdapter* mapadapter, enum LayerType layertype, bool takeevents)
:visible(true), mylayername(layername), mylayertype(layertype), mapAdapter(mapadapter), takeevents(takeevents), myoffscreenViewport(QRect(0,0,0,0))
{
draggingGeometry = false;
//qDebug() << "creating new Layer: " << layername << ", type: " << contents;
//qDebug() << this->layertype;
}
......
......@@ -366,15 +366,26 @@ namespace qmapcontrol
void LayerManager::mouseEvent(const QMouseEvent* evnt)
{
QListIterator<Layer*> it(mylayers);
while (it.hasNext())
// TODO: to review errors generated in the Windows operating system when the QListIterator is used
for(int i=0; i<mylayers.size(); i++)
{
Layer* l = it.next();
Layer* l = mylayers[i];
if (l->isVisible())
{
l->mouseEvent(evnt, mapmiddle_px);
}
}
// QListIterator<Layer*> it(mylayers);
// while (it.hasNext())
// {
// qDebug() << it.next();
// Layer* l = it.next();
// if (l->isVisible())
// {
// l->mouseEvent(evnt, mapmiddle_px);
// }
// }
}
void LayerManager::updateRequest(QRectF rect)
......
......@@ -126,7 +126,8 @@ win32 {
# Special settings for debug
#CONFIG += CONSOLE
INCLUDEPATH += $$BASEDIR\lib\sdl\include #\
INCLUDEPATH += $$BASEDIR\lib\sdl\include \
$$BASEDIR\lib\opal\include #\ #\
#"C:\Program Files\Microsoft SDKs\Windows\v7.0\Include"
LIBS += -L$$BASEDIR\lib\sdl\win32 \
......
......@@ -18,8 +18,8 @@ TARGET = qgroundcontrol
BASEDIR = .
BUILDDIR = build
LANGUAGE = C++
CONFIG += debug_and_release \
console
CONFIG += release #debug_and_release \
#console
OBJECTS_DIR = $$BUILDDIR/obj
MOC_DIR = $$BUILDDIR/moc
UI_HEADERS_DIR = src/ui/generated
......@@ -75,7 +75,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCFirmwareUpdate.ui \
src/ui/QGCPxImuFirmwareUpdate.ui \
src/ui/QGCDataPlot2D.ui \
src/ui/QGCRemoteControlView.ui
src/ui/QGCRemoteControlView.ui \
src/ui/WaypointGlobalView.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -157,7 +158,9 @@ HEADERS += src/MG.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/MAV2DIcon.h \
src/ui/map/QGC2DIcon.h \
src/ui/QGCRemoteControlView.h
src/ui/QGCRemoteControlView.h \
src/WaypointGlobal.h \
src/ui/WaypointGlobalView.h
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
......@@ -221,7 +224,9 @@ SOURCES += src/main.cc \
src/ui/map/Waypoint2DIcon.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/map/QGC2DIcon.cc \
src/ui/QGCRemoteControlView.cc
src/ui/QGCRemoteControlView.cc \
src/WaypointGlobal.cpp \
src/ui/WaypointGlobalView.cpp
RESOURCES = mavground.qrc
# Include RT-LAB Library
......
......@@ -59,7 +59,7 @@ public:
bool load(QTextStream &loadStream);
private:
protected:
quint16 id;
float x;
float y;
......
#include "WaypointGlobal.h"
#include <QPointF>
WaypointGlobal::WaypointGlobal(const QPointF coordinate):
Waypoint(id, x, y, z, yaw, autocontinue, current, orbit, holdTime)
{
coordinateWP = coordinate;
}
#ifndef WAYPOINTGLOBAL_H
#define WAYPOINTGLOBAL_H
#include "Waypoint.h"
#include <QPointF>
class WaypointGlobal: public Waypoint {
Q_OBJECT
public:
WaypointGlobal(const QPointF coordinate);
public slots:
// void set_latitud(double latitud);
// void set_longitud(double longitud);
// double get_latitud();
// double get_longitud();
private:
QPointF coordinateWP;
};
#endif // WAYPOINTGLOBAL_H
......@@ -222,7 +222,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// LOW BATTERY ALARM
float chargeLevel = getChargeLevel();
if (chargeLevel <= 10.0f)
if (chargeLevel <= 20.0f)
{
startLowBattAlarm();
}
......
......@@ -451,6 +451,7 @@ void UASWaypointManager::writeWaypoints()
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
//clear local buffer
//TODO: Why not replace with waypoint_buffer.clear() ?
while(!waypoint_buffer.empty())
{
delete waypoint_buffer.back();
......@@ -473,6 +474,7 @@ void UASWaypointManager::writeWaypoints()
cur_d->orbit_direction = 0;
cur_d->param1 = cur_s->getOrbit();
cur_d->param2 = cur_s->getHoldTime();
// TODO: Replace this value depending on the type of waypoint
cur_d->type = 1; //FIXME: we only use local waypoints at the moment
cur_d->seq = i; // don't read out the sequence number of the waypoint class
cur_d->x = cur_s->getX();
......
......@@ -61,8 +61,8 @@ This file is part of the QGROUNDCONTROL project
* @see QMainWindow::show()
**/
MainWindow::MainWindow(QWidget *parent) :
QMainWindow(parent),
settings()
QMainWindow(parent),
settings()
{
this->hide();
this->setVisible(false);
......@@ -92,7 +92,7 @@ MainWindow::MainWindow(QWidget *parent) :
// Create actions
connectActions();
// Load widgets and show application window
// Load widgets and show application windowa
loadWidgets();
// Adjust the size
......@@ -108,131 +108,144 @@ MainWindow::~MainWindow()
void MainWindow::buildWidgets()
{
//FIXME: memory of acceptList will never be freed again
QStringList* acceptList = new QStringList();
acceptList->append("roll IMU");
acceptList->append("pitch IMU");
acceptList->append("yaw IMU");
acceptList->append("rollspeed IMU");
acceptList->append("pitchspeed IMU");
acceptList->append("yawspeed IMU");
//FIXME: memory of acceptList will never be freed again
QStringList* acceptList = new QStringList();
acceptList->append("roll IMU");
acceptList->append("pitch IMU");
acceptList->append("yaw IMU");
acceptList->append("rollspeed IMU");
acceptList->append("pitchspeed IMU");
acceptList->append("yawspeed IMU");
//FIXME: memory of acceptList2 will never be freed again
QStringList* acceptList2 = new QStringList();
acceptList2->append("Battery");
acceptList2->append("Pressure");
//FIXME: memory of acceptList2 will never be freed again
QStringList* acceptList2 = new QStringList();
acceptList2->append("Battery");
acceptList2->append("Pressure");
//TODO: move protocol outside UI
mavlink = new MAVLinkProtocol();
//TODO: move protocol outside UI
mavlink = new MAVLinkProtocol();
// Center widgets
linechartWidget = new Linecharts(this);
hudWidget = new HUD(640, 480, this);
mapWidget = new MapWidget(this);
protocolWidget = new XMLCommProtocolWidget(this);
dataplotWidget = new QGCDataPlot2D(this);
// Center widgets
linechartWidget = new Linecharts(this);
hudWidget = new HUD(640, 480, this);
mapWidget = new MapWidget(this);
protocolWidget = new XMLCommProtocolWidget(this);
dataplotWidget = new QGCDataPlot2D(this);
// Dock widgets
controlDockWidget = new QDockWidget(tr("Control"), this);
controlDockWidget->setWidget( new UASControlWidget(this) );
// Dock widgets
controlDockWidget = new QDockWidget(tr("Control"), this);
controlDockWidget->setWidget( new UASControlWidget(this) );
listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
listDockWidget->setWidget( new UASListWidget(this) );
listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
listDockWidget->setWidget( new UASListWidget(this) );
waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
infoDockWidget = new QDockWidget(tr("Status Details"), this);
infoDockWidget->setWidget( new UASInfoWidget(this) );
infoDockWidget = new QDockWidget(tr("Status Details"), this);
infoDockWidget->setWidget( new UASInfoWidget(this) );
detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
debugConsoleDockWidget->setWidget( new DebugConsole(this) );
debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
debugConsoleDockWidget->setWidget( new DebugConsole(this) );
parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
parametersDockWidget->setWidget( new ParameterInterface(this) );
parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
parametersDockWidget->setWidget( new ParameterInterface(this) );
watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
hsiDockWidget->setWidget( new HSIDisplay(this) );
hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
hsiDockWidget->setWidget( new HSIDisplay(this) );
headDown1DockWidget = new QDockWidget(tr("Primary Flight Display"), this);
headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
headDown1DockWidget = new QDockWidget(tr("Primary Flight Display"), this);
headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
// Dialogue widgets
//FIXME: free memory in destructor
joystick = new JoystickInput();
// Dialogue widgets
//FIXME: free memory in destructor
joystick = new JoystickInput();
}
/**
* Connect all signals and slots of the main window widgets
*/
void MainWindow::connectWidgets()
{
if (linechartWidget)
{
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
linechartWidget, SLOT(addSystem(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)),
linechartWidget, SLOT(selectSystem(int)));
connect(linechartWidget, SIGNAL(logfileWritten(QString)),
this, SLOT(loadDataView(QString)));
}
if (infoDockWidget && infoDockWidget->widget())
{
connect(mavlink, SIGNAL(receiveLossChanged(int, float)),
infoDockWidget->widget(), SLOT(updateSendLoss(int, float)));
}
if (linechartWidget)
{
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
linechartWidget, SLOT(addSystem(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)),
linechartWidget, SLOT(selectSystem(int)));
connect(linechartWidget, SIGNAL(logfileWritten(QString)),
this, SLOT(loadDataView(QString)));
}
if (infoDockWidget && infoDockWidget->widget())
{
connect(mavlink, SIGNAL(receiveLossChanged(int, float)),
infoDockWidget->widget(), SLOT(updateSendLoss(int, float)));
}
if (mapWidget && waypointsDockWidget->widget())
{
// clear path create on the map
connect(waypointsDockWidget->widget(), SIGNAL(clearPathclicked()), mapWidget, SLOT(clearPath()));
// add Waypoint widget in the WaypointList widget when mouse clicked
connect(mapWidget, SIGNAL(captureMapCoordinateClick(QPointF)), waypointsDockWidget->widget(), SLOT(addWaypointMouse(QPointF)));
// it notifies that a waypoint global goes to do create
connect(mapWidget, SIGNAL(createGlobalWP(bool)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool)));
connect(mapWidget, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypointsDockWidget->widget(), SLOT(waypointGlobalChanged(QPointF,int)) );
}
}
void MainWindow::arrangeCenterStack()
{
QStackedWidget *centerStack = new QStackedWidget(this);
if (!centerStack) return;
QStackedWidget *centerStack = new QStackedWidget(this);
if (!centerStack) return;
if (linechartWidget) centerStack->addWidget(linechartWidget);
if (protocolWidget) centerStack->addWidget(protocolWidget);
if (mapWidget) centerStack->addWidget(mapWidget);
if (hudWidget) centerStack->addWidget(hudWidget);
if (dataplotWidget) centerStack->addWidget(dataplotWidget);
if (linechartWidget) centerStack->addWidget(linechartWidget);
if (protocolWidget) centerStack->addWidget(protocolWidget);
if (mapWidget) centerStack->addWidget(mapWidget);
if (hudWidget) centerStack->addWidget(hudWidget);
if (dataplotWidget) centerStack->addWidget(dataplotWidget);
setCentralWidget(centerStack);
setCentralWidget(centerStack);
}
void MainWindow::configureWindowName()
{
QList<QHostAddress> hostAddresses = QNetworkInterface::allAddresses();
QString windowname = qApp->applicationName() + " " + qApp->applicationVersion();
bool prevAddr = false;
QList<QHostAddress> hostAddresses = QNetworkInterface::allAddresses();
QString windowname = qApp->applicationName() + " " + qApp->applicationVersion();
bool prevAddr = false;
windowname.append(" (" + QHostInfo::localHostName() + ": ");
windowname.append(" (" + QHostInfo::localHostName() + ": ");
for (int i = 0; i < hostAddresses.size(); i++)
{
// Exclude loopback IPv4 and all IPv6 addresses
if (hostAddresses.at(i) != QHostAddress("127.0.0.1") && !hostAddresses.at(i).toString().contains(":"))
{
if(prevAddr) windowname.append("/");
windowname.append(hostAddresses.at(i).toString());
prevAddr = true;
}
}
for (int i = 0; i < hostAddresses.size(); i++)
{
// Exclude loopback IPv4 and all IPv6 addresses
if (hostAddresses.at(i) != QHostAddress("127.0.0.1") && !hostAddresses.at(i).toString().contains(":"))
{
if(prevAddr) windowname.append("/");
windowname.append(hostAddresses.at(i).toString());
prevAddr = true;
}
}
windowname.append(")");
windowname.append(")");
setWindowTitle(windowname);
setWindowTitle(windowname);
#ifndef Q_WS_MAC
//qApp->setWindowIcon(QIcon(":/core/images/qtcreator_logo_128.png"));
//qApp->setWindowIcon(QIcon(":/core/images/qtcreator_logo_128.png"));
#endif
}
......@@ -353,6 +366,8 @@ void MainWindow::connectActions()
// Joystick configuration
connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
}
void MainWindow::showHelp()
......@@ -471,32 +486,32 @@ void MainWindow::UASCreated(UASInterface* uas)
// FIXME Should be not inside the mainwindow
if (debugConsoleDockWidget)
{
DebugConsole *debugConsole = dynamic_cast<DebugConsole*>(debugConsoleDockWidget->widget());
if (debugConsole)
{
connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)),
debugConsole, SLOT(receiveTextMessage(int,int,int,QString)));
}
DebugConsole *debugConsole = dynamic_cast<DebugConsole*>(debugConsoleDockWidget->widget());
if (debugConsole)
{
connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)),
debugConsole, SLOT(receiveTextMessage(int,int,int,QString)));
}
}
// Health / System status indicator
if (infoDockWidget)
{
UASInfoWidget *infoWidget = dynamic_cast<UASInfoWidget*>(infoDockWidget->widget());
if (infoWidget)
{
infoWidget->addUAS(uas);
}
UASInfoWidget *infoWidget = dynamic_cast<UASInfoWidget*>(infoDockWidget->widget());
if (infoWidget)
{
infoWidget->addUAS(uas);
}
}
// UAS List
if (listDockWidget)
{
UASListWidget *listWidget = dynamic_cast<UASListWidget*>(listDockWidget->widget());
if (listWidget)
{
listWidget->addUAS(uas);
}
UASListWidget *listWidget = dynamic_cast<UASListWidget*>(listDockWidget->widget());
if (listWidget)
{
listWidget->addUAS(uas);
}
}
// Camera view
......@@ -530,7 +545,7 @@ void MainWindow::clearView()
HDDisplay* hddWidget = dynamic_cast<HDDisplay*>( headDown1DockWidget->widget() );
if (hddWidget) hddWidget->stop();
}
if (headDown2DockWidget)
if (headDown2DockWidget)
{
HDDisplay* hddWidget = dynamic_cast<HDDisplay*>( headDown2DockWidget->widget() );
if (hddWidget) hddWidget->stop();
......@@ -678,6 +693,18 @@ void MainWindow::loadPixhawkView()
waypointsDockWidget->show();
}
// HORIZONTAL SITUATION INDICATOR
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi)
{
hsi->start();
addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
}
}
// DEBUG CONSOLE
if (debugConsoleDockWidget)
{
......@@ -718,7 +745,7 @@ void MainWindow::loadDataView()
void MainWindow::loadDataView(QString fileName)
{
clearView();
// DATAPLOT
if (dataplotWidget)
{
......@@ -1014,8 +1041,8 @@ void MainWindow::loadAllView()
// OBJECT DETECTION
if (detectionDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
detectionDockWidget->show();
addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
detectionDockWidget->show();
}
// LINE CHART
......
......@@ -22,6 +22,9 @@
<height>800</height>
</size>
</property>
<property name="mouseTracking">
<bool>false</bool>
</property>
<property name="windowTitle">
<string>MGMainWindow</string>
</property>
......@@ -35,7 +38,7 @@
<x>0</x>
<y>0</y>
<width>1000</width>
<height>22</height>
<height>21</height>
</rect>
</property>
<widget class="QMenu" name="menuMGround">
......
......@@ -87,7 +87,10 @@ MapWidget::MapWidget(QWidget *parent) :
// Set default zoom level
mc->setZoom(16);
// Zurich, ETH
mc->setView(QPointF(8.548056,47.376389));
//mc->setView(QPointF(8.548056,47.376389));
// Veracruz Mexico, ETH
mc->setView(QPointF(-96.105208,19.138955));
// Add controls to select map provider
/////////////////////////////////////////////////
......@@ -299,24 +302,32 @@ void MapWidget::createPathButtonClicked(bool checked)
{
Q_UNUSED(checked);
if (createPath->isChecked())
{
// change the cursor shape
this->setCursor(Qt::PointingHandCursor);
mc->setMouseMode(qmapcontrol::MapControl::None);
// Clear the previous WP track
// TODO: Move this to an actual clear track button and add a warning dialog
mc->layer("Waypoints")->clearGeometries();
wps.clear();
path->setPoints(wps);
mc->layer("Waypoints")->addGeometry(path);
wpIndex.clear();
// emit signal start to create a Waypoint global
emit createGlobalWP(true);
// // Clear the previous WP track
// // TODO: Move this to an actual clear track button and add a warning dialog
// mc->layer("Waypoints")->clearGeometries();
// wps.clear();
// path->setPoints(wps);
// mc->layer("Waypoints")->addGeometry(path);
// wpIndex.clear();
} else {
this->setCursor(Qt::ArrowCursor);
mc->setMouseMode(qmapcontrol::MapControl::Panning);
}
}
......@@ -328,7 +339,7 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
// Create waypoint name
QString str;
str = QString("WP%1").arg(path->numberOfPoints());
str = QString("%1").arg(path->numberOfPoints());
// create the WP and set everything in the LineString to display the path
CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str);
......@@ -342,6 +353,10 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
// Refresh the screen
mc->updateRequestNew();
// emit signal mouse was clicked
emit captureMapCoordinateClick(coordinate);
}
}
......@@ -357,6 +372,10 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
Q_UNUSED(coordinate);
// Refresh the screen
mc->updateRequestNew();
int temp = 0;
Point* point2Find;
point2Find = wpIndex[geom->name()];
point2Find->setCoordinate(coordinate);
......@@ -364,12 +383,18 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
point2Find = dynamic_cast <Point*> (geom);
point2Find->setCoordinate(coordinate);
// Refresh the screen
mc->updateRequestNew();
// qDebug() << geom->name();
temp = geom->get_myIndex();
//qDebug() << temp;
emit sendGeometryEndDrag(coordinate,temp);
}
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate){
mc->setMouseMode(qmapcontrol::MapControl::Panning);
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
{
mc->setMouseMode(qmapcontrol::MapControl::Panning);
// qDebug() << geom->name();
// qDebug() << geom->GeometryType;
......@@ -536,3 +561,21 @@ void MapWidget::changeEvent(QEvent *e)
break;
}
}
void MapWidget::clearPath()
{
// Clear the previous WP track
mc->layer("Waypoints")->clearGeometries();
wps.clear();
path->setPoints(wps);
mc->layer("Waypoints")->addGeometry(path);
wpIndex.clear();
mc->updateRequestNew();
// si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicket
if(createPath->isChecked())
{
createPath->click();
}
}
......@@ -63,6 +63,9 @@ public slots:
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
void updatePosition(float time, double lat, double lon);
//ROCA
void clearPath();
protected:
void changeEvent(QEvent* e);
void wheelEvent(QWheelEvent *event);
......@@ -108,8 +111,14 @@ protected:
void captureGeometryDrag(Geometry* geom, QPointF coordinate);
void captureGeometryEndDrag(Geometry* geom, QPointF coordinate);
signals:
void movePoint(QPointF newCoord);
//void movePoint(QPointF newCoord);
void captureMapCoordinateClick(const QPointF coordinate); //ROCA
void createGlobalWP(bool value);
void sendGeometryEndDrag(const QPointF coordinate, const int index);
private:
Ui::MapWidget *m_ui;
......
#include "WaypointGlobalView.h"
#include "ui_WaypointGlobalView.h"
#include <math.h>
WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) :
QWidget(parent),
ui(new Ui::WaypointGlobalView)
{
ui->setupUi(this);
this->wp = wp;
ui->m_orbitalSpinBox->hide();
connect(ui->m_orbitalSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setOrbit(double)));
connect(ui->m_heigthSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
connect(ui->m_orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int)));
// Read values and set user interface
updateValues();
// connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
// connect(m_ui->ySpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
// connect(m_ui->zSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
// //hidden degree to radian conversion of the yaw angle
// connect(m_ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYaw(int)));
// connect(this, SIGNAL(setYaw(double)), wp, SLOT(setYaw(double)));
// connect(m_ui->upButton, SIGNAL(clicked()), this, SLOT(moveUp()));
// connect(m_ui->downButton, SIGNAL(clicked()), this, SLOT(moveDown()));
// connect(m_ui->removeButton, SIGNAL(clicked()), this, SLOT(remove()));
// connect(m_ui->autoContinue, SIGNAL(stateChanged(int)), this, SLOT(changedAutoContinue(int)));
// connect(m_ui->selectedBox, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int)));
//
// connect(m_ui->holdTimeSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setHoldTime(int)));
}
WaypointGlobalView::~WaypointGlobalView()
{
delete ui;
}
void WaypointGlobalView::updateValues()
{
ui->m_latitudtextEdit->setText(getLatitudString(wp->getY()));
ui->m_longitudtextEdit->setText(getLongitudString(wp->getX()));
ui->idWP_label->setText(QString("%1").arg(wp->getId()));\
}
void WaypointGlobalView::changeEvent(QEvent *e)
{
switch (e->type()) {
case QEvent::LanguageChange:
ui->retranslateUi(this);
break;
default:
break;
}
}
void WaypointGlobalView::remove()
{
emit removeWaypoint(wp);
delete this;
}
QString WaypointGlobalView::getLatitudString(float latitud)
{
QString tempNS ="";
QString stringLatitudTemp = "";
float minutos = 0;
float grados = 0;
float entero = 0;
float dec = 0;
if (latitud<0){tempNS="S"; latitud = latitud * -1;}
else {tempNS="N";}
if(latitud< 90 || latitud > -90)
{
dec = latitud - (entero = ::floor(latitud));;
minutos = dec * 60;
grados = entero;
if(grados < 0) grados = grados * (-1);
if(minutos < 0) minutos = minutos * (-1);
stringLatitudTemp = QString::number(grados)+ " "+ QString::number(minutos)+"' "+ tempNS;
return stringLatitudTemp;
}
else
{
stringLatitudTemp = "erroneous latitude";
return stringLatitudTemp;
}
}
QString WaypointGlobalView::getLongitudString(float longitud)
{
QString tempEW ="";
QString stringLongitudTemp = "";
float minutos = 0;
float grados = 0;
float entero = 0;
float dec = 0;
if (longitud<0){tempEW="W"; longitud = longitud * -1;}
else {tempEW="E";}
if(longitud<180 || longitud > -180)
{
dec = longitud - (entero = ::floor(longitud));;
minutos = dec * 60;
grados = entero;
if(grados < 0) grados = grados * (-1);
if(minutos < 0) minutos = minutos * (-1);
stringLongitudTemp = QString::number(grados)+ " "+ QString::number(minutos)+"' "+ tempEW;
return stringLongitudTemp;
}
else
{
stringLongitudTemp = "erroneous longitude";
return stringLongitudTemp;
}
}
void WaypointGlobalView::changeOrbitalState(int state)
{
Q_UNUSED(state);
if(ui->m_orbitCheckBox->isChecked())
{
ui->m_orbitalSpinBox->setEnabled(true);
ui->m_orbitalSpinBox->show();
}
else
{
ui->m_orbitalSpinBox->setEnabled(false);
ui->m_orbitalSpinBox->hide();
}
}
#ifndef WAYPOINTGLOBALVIEW_H
#define WAYPOINTGLOBALVIEW_H
#include <QWidget>
#include "Waypoint.h"
namespace Ui {
class WaypointGlobalView;
}
class WaypointGlobalView : public QWidget
{
Q_OBJECT
public:
explicit WaypointGlobalView(Waypoint* wp, QWidget *parent = 0);
~WaypointGlobalView();
public slots:
void updateValues(void);
void remove();
QString getLatitudString(float lat);
QString getLongitudString(float lon);
void changeOrbitalState(int state);
signals:
void removeWaypoint(Waypoint*);
protected:
virtual void changeEvent(QEvent *e);
Waypoint* wp;
private:
Ui::WaypointGlobalView *ui;
private slots:
};
#endif // WAYPOINTGLOBALVIEW_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>WaypointGlobalView</class>
<widget class="QWidget" name="WaypointGlobalView">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>869</width>
<height>60</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Maximum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<property name="styleSheet">
<string notr="true">QWidget#colorIcon {}
QWidget {
background-color: #252528;
color: #DDDDDF;
border-color: #EEEEEE;
background-clip: border;
}
QCheckBox {
background-color: #252528;
color: #454545;
}
QGroupBox {
border: 1px solid #EEEEEE;
border-radius: 5px;
padding: 0px 0px 0px 0px;
margin-top: 1ex; /* leave space at the top for the title */
margin: 0px;
}
QGroupBox::title {
subcontrol-origin: margin;
subcontrol-position: top center; /* position at the top center */
margin: 0 3px 0px 3px;
padding: 0 3px 0px 0px;
font: bold 8px;
}
QGroupBox#heartbeatIcon {
background-color: red;
}
QDockWidget {
font: bold;
border: 1px solid #32345E;
}
QPushButton {
font-weight: bold;
font-size: 12px;
border: 1px solid #999999;
border-radius: 10px;
min-width:22px;
max-width: 36px;
min-height: 16px;
max-height: 16px;
padding: 2px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #777777, stop: 1 #555555);
}
QPushButton:pressed {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #444444, stop: 1 #555555);
}
QPushButton#landButton {
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #ffee01, stop:1 #ae8f00) url(&quot;ICONDIR/control/emergency-button.png&quot;);
}
QPushButton:pressed#landButton {
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #bbaa00, stop:1 #a05b00) url(&quot;ICONDIR/control/emergency-button.png&quot;);
}
QPushButton#killButton {
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #ffb917, stop:1 #b37300) url(&quot;ICONDIR/control/emergency-button.png&quot;);
}
QPushButton:pressed#killButton {
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #bb8500, stop:1 #903000) url(&quot;ICONDIR/control/emergency-button.png&quot;);
}
QProgressBar {
border: 1px solid white;
border-radius: 4px;
text-align: center;
padding: 2px;
color: white;
background-color: #111111;
}
QProgressBar:horizontal {
height: 12px;
}
QProgressBar QLabel {
font-size: 8px;
}
QProgressBar:vertical {
width: 12px;
}
QProgressBar::chunk {
background-color: #656565;
}
QProgressBar::chunk#batteryBar {
background-color: green;
}
QProgressBar::chunk#speedBar {
background-color: yellow;
}
QProgressBar::chunk#thrustBar {
background-color: orange;
}</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string/>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="idWP_label">
<property name="text">
<string>WP_id</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>135</width>
<height>13</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="Latitud_label">
<property name="text">
<string>Lat:</string>
</property>
</widget>
</item>
<item>
<widget class="QTextEdit" name="m_latitudtextEdit">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>120</width>
<height>25</height>
</size>
</property>
<property name="verticalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>50</width>
<height>30</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="Longitud_label">
<property name="text">
<string>Lon:</string>
</property>
</widget>
</item>
<item>
<widget class="QTextEdit" name="m_longitudtextEdit">
<property name="maximumSize">
<size>
<width>120</width>
<height>25</height>
</size>
</property>
<property name="verticalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>50</width>
<height>30</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="height_label">
<property name="text">
<string>Heigth</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="m_heigthSpinBox"/>
</item>
<item>
<widget class="QCheckBox" name="m_orbitCheckBox">
<property name="palette">
<palette>
<active>
<colorrole role="WindowText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>69</red>
<green>69</green>
<blue>69</blue>
</color>
</brush>
</colorrole>
<colorrole role="Button">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>37</red>
<green>37</green>
<blue>40</blue>
</color>
</brush>
</colorrole>
<colorrole role="Text">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>69</red>
<green>69</green>
<blue>69</blue>
</color>
</brush>
</colorrole>
<colorrole role="ButtonText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>69</red>
<green>69</green>
<blue>69</blue>
</color>
</brush>
</colorrole>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>37</red>
<green>37</green>
<blue>40</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>37</red>
<green>37</green>
<blue>40</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="WindowText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>69</red>
<green>69</green>
<blue>69</blue>
</color>
</brush>
</colorrole>
<colorrole role="Button">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>37</red>
<green>37</green>
<blue>40</blue>
</color>
</brush>
</colorrole>
<colorrole role="Text">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>69</red>
<green>69</green>
<blue>69</blue>
</color>
</brush>
</colorrole>
<colorrole role="ButtonText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>69</red>
<green>69</green>
<blue>69</blue>
</color>
</brush>
</colorrole>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>37</red>
<green>37</green>
<blue>40</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>37</red>
<green>37</green>
<blue>40</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="WindowText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>69</red>
<green>69</green>
<blue>69</blue>
</color>
</brush>
</colorrole>
<colorrole role="Button">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>37</red>
<green>37</green>
<blue>40</blue>
</color>
</brush>
</colorrole>
<colorrole role="Text">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>69</red>
<green>69</green>
<blue>69</blue>
</color>
</brush>
</colorrole>
<colorrole role="ButtonText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>69</red>
<green>69</green>
<blue>69</blue>
</color>
</brush>
</colorrole>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>37</red>
<green>37</green>
<blue>40</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>37</red>
<green>37</green>
<blue>40</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="text">
<string>Orbital</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="m_orbitalSpinBox">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
......@@ -37,6 +37,8 @@ This file is part of the PIXHAWK project
#include <UASManager.h>
#include <QDebug>
#include <QFileDialog>
#include "WaypointGlobalView.h"
#include <QMessageBox>
WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
QWidget(parent),
......@@ -77,6 +79,8 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
// SET UAS AFTER ALL SIGNALS/SLOTS ARE CONNECTED
setUAS(uas);
......@@ -84,6 +88,8 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
updateStatusLabel("");
this->setVisible(false);
isGlobalWP = false;
isLocalWP = false;
}
WaypointList::~WaypointList()
......@@ -162,18 +168,24 @@ void WaypointList::add()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *last = waypoints.at(waypoints.size()-1);
Waypoint *wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager().localAddWaypoint(wp);
}
else
{
Waypoint *wp = new Waypoint(0, 1.1, 1.1, -0.8, 0.0, true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp);
}
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *last = waypoints.at(waypoints.size()-1);
Waypoint *wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager().localAddWaypoint(wp);
}
else
{
Waypoint *wp = new Waypoint(0, 1.1, 1.1, -0.8, 0.0, true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp);
}
isLocalWP = true;
}
}
......@@ -181,17 +193,27 @@ void WaypointList::addCurrentPositonWaypoint()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0)
// For Global Waypoints
if(isGlobalWP)
{
Waypoint *last = waypoints.at(waypoints.size()-1);
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager().localAddWaypoint(wp);
isLocalWP = false;
}
else
{
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp);
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *last = waypoints.at(waypoints.size()-1);
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager().localAddWaypoint(wp);
}
else
{
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp);
}
isLocalWP = true;
}
}
}
......@@ -240,53 +262,113 @@ void WaypointList::waypointListChanged()
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
// first remove all views of non existing waypoints
if (!wpViews.empty())
{
QMapIterator<Waypoint*,WaypointView*> viewIt(wpViews);
viewIt.toFront();
while(viewIt.hasNext())
// For Global Waypoints
if(isGlobalWP)
{
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++)
isLocalWP = false;
// first remove all views of non existing waypoints
if (!wpGlobalViews.empty())
{
if (waypoints[i] == cur)
QMapIterator<Waypoint*,WaypointGlobalView*> viewIt(wpGlobalViews);
viewIt.toFront();
while(viewIt.hasNext())
{
break;
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == cur)
{
break;
}
}
if (i == waypoints.size())
{
WaypointGlobalView* widget = wpGlobalViews.find(cur).value();
widget->hide();
listLayout->removeWidget(widget);
wpGlobalViews.remove(cur);
}
}
}
if (i == waypoints.size())
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(cur).value();
widget->hide();
listLayout->removeWidget(widget);
wpViews.remove(cur);
}
Waypoint *wp = waypoints[i];
if (!wpGlobalViews.contains(wp))
{
WaypointGlobalView* wpview = new WaypointGlobalView(wp, this);
wpGlobalViews.insert(wp, wpview);
// connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
// connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
// connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
// connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
}
WaypointGlobalView *wpgv = wpGlobalViews.value(wp);
wpgv->updateValues();
listLayout->addWidget(wpgv);
}
}
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++)
{
Waypoint *wp = waypoints[i];
if (!wpViews.contains(wp))
}
else
{
WaypointView* wpview = new WaypointView(wp, this);
wpViews.insert(wp, wpview);
connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
// for local Waypoints
// first remove all views of non existing waypoints
if (!wpViews.empty())
{
QMapIterator<Waypoint*,WaypointView*> viewIt(wpViews);
viewIt.toFront();
while(viewIt.hasNext())
{
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == cur)
{
break;
}
}
if (i == waypoints.size())
{
WaypointView* widget = wpViews.find(cur).value();
widget->hide();
listLayout->removeWidget(widget);
wpViews.remove(cur);
}
}
}
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++)
{
Waypoint *wp = waypoints[i];
if (!wpViews.contains(wp))
{
WaypointView* wpview = new WaypointView(wp, this);
wpViews.insert(wp, wpview);
connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
}
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues(); // update the values of the ui elements in the view
listLayout->addWidget(wpv);
}
}
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues(); // update the values of the ui elements in the view
listLayout->addWidget(wpv);
}
}
}
void WaypointList::moveUp(Waypoint* wp)
......@@ -352,3 +434,140 @@ void WaypointList::changeEvent(QEvent *e)
}
}
void WaypointList::on_clearWPListButton_clicked()
{
if (uas)
{
if(isGlobalWP)
{
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointGlobalView* widget = wpGlobalViews.find(waypoints[0]).value();
widget->remove();
}
isGlobalWP = false;
}
else
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
}
}
/** @brief Add a waypoint by mouse click over the map */
void WaypointList::addWaypointMouse(QPointF coordinate)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *last = waypoints.at(waypoints.size()-1);
Waypoint *wp = new Waypoint(0, coordinate.x(), coordinate.y(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager().localAddWaypoint(wp);
}
else
{
Waypoint *wp = new Waypoint(0, coordinate.x(), coordinate.y(), -0.8, 0.0, true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp);
}
}
}
/** @brief it notifies that a global waypoint goes to do created */
void WaypointList::setIsWPGlobal(bool value)
{
if(isLocalWP)
{
if(wpViews.size()!= 0)
{
int ret = QMessageBox::warning(this, tr("My Application"),
tr("There are Waypoints local created.\n"
"Do you want to clear them?"),
QMessageBox::Ok | QMessageBox::Cancel);
if(ret)
{
clearLocalWPWidget();
isGlobalWP = value;
isLocalWP = !(value);
}
}
}
else
{
isGlobalWP = value;
}
}
/** @brief The MapWidget informs that a waypoint global was changed on the map */
void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *temp = waypoints.at(indexWP);
temp->setX(coordinate.x());
temp->setY(coordinate.y());
WaypointGlobalView* widget = wpGlobalViews.find(waypoints[indexWP]).value();
widget->updateValues();
}
}
}
void WaypointList::clearLocalWPWidget()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
}
......@@ -41,6 +41,8 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h"
#include "UASInterface.h"
#include "WaypointView.h"
#include "WaypointGlobalView.h"
namespace Ui {
class WaypointList;
......@@ -72,6 +74,11 @@ public slots:
void add();
/** @brief Add a waypoint at the current MAV position */
void addCurrentPositonWaypoint();
/** @brief Add a waypoint by mouse click over the map */
void addWaypointMouse(QPointF coordinate);
/** @brief it notifies that a global waypoint goes to do created */
void setIsWPGlobal(bool value);
//Update events
/** @brief sets statusLabel string */
......@@ -83,25 +90,49 @@ public slots:
/** @brief The waypoint manager informs that the waypoint list was changed */
void waypointListChanged(void);
/** @brief The MapWidget informs that a waypoint global was changed on the map */
void waypointGlobalChanged(const QPointF coordinate, const int indexWP);
void clearLocalWPWidget();
// Waypoint operations
void moveUp(Waypoint* wp);
void moveDown(Waypoint* wp);
void removeWaypoint(Waypoint* wp);
signals:
void clearPathclicked();
protected:
virtual void changeEvent(QEvent *e);
protected:
QMap<Waypoint*, WaypointView*> wpViews;
QMap<Waypoint*, WaypointGlobalView*> wpGlobalViews;
QVBoxLayout* listLayout;
UASInterface* uas;
double mavX;
double mavY;
double mavZ;
double mavYaw;
bool isGlobalWP;
bool isLocalWP;
private:
Ui::WaypointList *m_ui;
private slots:
void on_clearWPListButton_clicked();
};
#endif // WAYPOINTLIST_H
......@@ -26,7 +26,7 @@
<property name="spacing">
<number>4</number>
</property>
<item row="0" column="0" colspan="9">
<item row="0" column="0" colspan="10">
<widget class="QScrollArea" name="scrollArea">
<property name="widgetResizable">
<bool>true</bool>
......@@ -37,7 +37,7 @@
<x>0</x>
<y>0</y>
<width>466</width>
<height>149</height>
<height>163</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
......@@ -54,7 +54,7 @@
</widget>
</widget>
</item>
<item row="2" column="7">
<item row="2" column="8">
<widget class="QPushButton" name="readButton">
<property name="text">
<string>Read</string>
......@@ -65,7 +65,7 @@
</property>
</widget>
</item>
<item row="2" column="8">
<item row="2" column="9">
<widget class="QPushButton" name="transmitButton">
<property name="text">
<string>Write</string>
......@@ -76,7 +76,7 @@
</property>
</widget>
</item>
<item row="3" column="0" colspan="9">
<item row="3" column="0" colspan="10">
<widget class="QLabel" name="statusLabel">
<property name="text">
<string>TextLabel</string>
......@@ -135,6 +135,17 @@
</property>
</widget>
</item>
<item row="2" column="7">
<widget class="QPushButton" name="clearWPListButton">
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/actions/process-stop.svg</normaloff>:/images/actions/process-stop.svg</iconset>
</property>
</widget>
</item>
</layout>
<action name="actionAddWaypoint">
<property name="icon">
......
......@@ -355,7 +355,7 @@ QProgressBar::chunk#thrustBar {
<string/>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<iconset>
<normaloff>:/images/actions/go-up.svg</normaloff>:/images/actions/go-up.svg</iconset>
</property>
</widget>
......@@ -375,7 +375,7 @@ QProgressBar::chunk#thrustBar {
<string/>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<iconset>
<normaloff>:/images/actions/go-down.svg</normaloff>:/images/actions/go-down.svg</iconset>
</property>
</widget>
......@@ -395,7 +395,7 @@ QProgressBar::chunk#thrustBar {
<string/>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<iconset>
<normaloff>:/images/actions/list-remove.svg</normaloff>:/images/actions/list-remove.svg</iconset>
</property>
</widget>
......@@ -405,8 +405,6 @@ QProgressBar::chunk#thrustBar {
</item>
</layout>
</widget>
<resources>
<include location="../../mavground.qrc"/>
</resources>
<resources/>
<connections/>
</ui>
......@@ -107,7 +107,7 @@ class TimeSeriesData
{
public:
TimeSeriesData(QwtPlot* plot, QString friendlyName = "data", quint64 plotInterval = 30000, quint64 maxInterval = 0, double zeroValue = 0);
TimeSeriesData(QwtPlot* plot, QString friendlyName = "data", quint64 plotInterval = 10000, quint64 maxInterval = 0, double zeroValue = 0);
~TimeSeriesData();
void append(quint64 ms, double value);
......
unix_timestamp Accel._X Accel._Y Accel._Z Battery Bottom_Rotor CPU_Load Ground_Dist. Gyro_Phi Gyro_Psi Gyro_Theta Left_Servo Mag._X Mag._Y Mag._Z Pressure Right_Servo Temperature Top_Rotor pitch_IMU roll_IMU yaw_IMU
1270125571544 5 -197 982 0 29685 29866 29888 0 0 0 96186 354 -0.112812 0.13585 -1.94192
1270125571564 6 -198 983 0 29781 29995 29871 0 0 0 96183 354 -0.112085 0.137193 -1.94139
1270125571584 10 -197 982 0 29739 30018 29867 0 0 0 96171 354 -0.111693 0.136574 -1.94353
1270125571604 7 -198 982 0 29802 29911 29803 0 0 0 96177 354 -0.112179 0.135778 -1.94617
1270125571645 4 -197 984 0 29782 29844 29844 0 0 0 96180 354 -0.113056 0.135965 -1.94715
1270125571665 4 -200 985 0 29685 29867 29884 0 0 0 96183 354 -0.113231 0.135327 -1.94586
1270125571685 7 -198 983 0 29757 30018 29829 0 0 0 96177 354 -0.112604 0.136857 -1.94508
1270125571706 6 -198 982 0 29759 29992 29867 0 0 0 96183 354 -0.1126 0.136602 -1.94915
1270125571746 7 -196 985 0 29803 29910 29800 0 0 0 96183 354 -0.112392 0.136709 -1.95079
1270125571766 4 -198 981 0 29750 29828 29888 0 0 0 96186 354 -0.113342 0.135532 -1.95064
1270125571787 5 -197 984 0 29759 29931 29881 0 0 0 96174 354 -0.112628 0.135657 -1.9488
1270125571807 10 -197 982 0 29739 29958 29819 0 0 0 96174 354 -0.112506 0.135777 -1.95001
1270125571847 4 -198 981 0 29786 29829 29864 0 0 0 96232 356 -0.112359 0.135253 -1.94825
1270125571867 5 -201 978 0 29719 29856 29890 0 0 0 96218 356 -0.11218 0.134669 -1.94657
1270125571888 7 -198 986 0 29782 29813 29845 0 0 0 96223 356 -0.111451 0.135688 -1.9455
1270125571908 10 -200 984 0 29693 30048 29885 0 0 0 96215 356 -0.110745 0.1365 -1.94668
1270125571948 5 -197 982 0 29757 29899 29844 0 0 0 96229 356 -0.110004 0.135859 -1.94573
1270125571969 6 -197 983 0 29727 29829 29814 0 0 0 96249 356 -0.110316 0.135751 -1.94565
1270125571989 6 -197 978 0 29790 29828 29815 0 0 0 96220 356 -0.111159 0.136244 -1.94416
1270125572009 5 -194 983 0 29718 29856 29890 0 0 0 96229 356 -0.111216 0.135992 -1.94196
1270125572050 3 -196 985 0 29739 29978 29827 0 0 0 96223 356 -0.110727 0.136577 -1.94402
1270125572070 8 -198 982 0 29782 29829 29815 0 0 0 96235 356 -0.111423 0.136697 -1.94566
1270125572090 8 -195 982 0 29687 29865 29894 0 0 0 96218 356 -0.112088 0.136097 -1.9442
1270125572130 8 -198 986 0 29793 29859 29844 0 0 0 96244 356 -0.110282 0.137491 -1.94235
1270125572171 6 -198 982 0 29790 29856 29879 0 0 0 96244 356 -0.112179 0.136971 -1.94365
1270125572191 3 -198 980 0 29759 30018 29829 0 0 0 96218 356 -0.111623 0.136194 -1.94286
1270125572211 7 -198 984 0 29758 29829 29846 0 0 0 96229 356 -0.112275 0.136007 -1.94387
1270125572252 8 -197 980 0 29743 30018 29824 0 0 0 96215 356 -0.111515 0.135539 -1.94281
1270125572272 11 -195 984 0 29741 29867 29844 0 0 0 96249 356 -0.111995 0.135753 -1.94527
1270125572292 4 -200 984 0 29771 29980 29865 0 0 0 96215 356 -0.111913 0.135829 -1.94455
1270125572312 6 -198 983 0 29792 29837 29845 0 0 0 96229 356 -0.111884 0.134861 -1.94478
1270125572353 5 -196 983 0 29685 29867 29884 0 0 0 96238 356 -0.111332 0.135644 -1.94784
1270125572373 5 -198 982 0 29693 29852 29904 0 0 0 96238 356 -0.110772 0.136927 -1.94698
1270125572393 6 -195 982 0 29738 29791 29818 0 0 0 96229 356 -0.109851 0.138106 -1.94592
1270125572414 8 -198 986 0 29782 29844 29829 0 0 0 96223 356 -0.111077 0.137396 -1.9428
1270125572454 11 -198 983 0 29743 29986 29833 0 0 0 96220 356 -0.110257 0.136744 -1.94155
1270125572474 6 -198 983 0 29749 29866 29813 0 0 0 96223 356 -0.110497 0.136917 -1.94351
1270125572495 6 -197 984 0 29719 29828 29890 0 0 0 96223 356 -0.111349 0.136959 -1.94295
1270125572515 7 -197 983 0 29760 29791 29818 0 0 0 96232 356 -0.111323 0.137251 -1.93972
1270125572555 10 -198 984 0 29800 30016 29857 0 0 0 96241 356 -0.110873 0.137041 -1.94196
1270125572575 5 -200 982 0 29760 29962 29866 0 0 0 96232 356 -0.110648 0.136038 -1.9445
1270125572596 4 -197 983 0 29740 30024 29867 0 0 0 96238 356 -0.110486 0.136046 -1.94576
1270125572616 8 -196 985 0 29802 29783 29808 0 0 0 96235 356 -0.111227 0.135128 -1.94567
1270125572656 5 -198 986 0 29771 29972 29867 0 0 0 96229 356 -0.111182 0.133833 -1.94823
1270125572697 8 -196 980 0 29739 29978 29803 0 0 0 96238 356 -0.111457 0.133602 -1.94682
1270125572717 4 -196 983 0 29749 30026 29867 0 0 0 96235 356 -0.116038 0.131922 -1.93861
1270125592944 5 -195 985 0 29757 29994 29871 0 0 0 96220 356 -0.115848 0.1323 -1.93916
1270125593025 5 -200 986 0 29780 29844 29845 0 0 0 96235 356 -0.115273 0.132222 -1.93576
1270125593045 5 -197 982 0 29757 29995 29871 0 0 0 96229 356 -0.114713 0.132137 -1.93723
1270125593086 4 -197 984 0 29802 29847 29819 0 0 0 96241 356 -0.114815 0.131529 -1.93626
1270125593106 6 -202 984 0 29802 29783 29803 0 0 0 96247 356 -0.115379 0.130754 -1.93546
1270125593126 8 -196 982 0 29803 29918 29793 0 0 0 96229 356 -0.116136 0.130336 -1.93339
1270125593146 6 -196 987 0 29802 29825 29802 0 0 0 96244 356 -0.117635 0.128822 -1.93292
1270125593187 7 -197 978 0 29802 29825 29864 0 0 0 96238 356 -0.117592 0.128252 -1.93468
1270125593207 7 -197 980 0 29803 29918 29771 0 0 0 96235 356 -0.116961 0.127734 -1.93337
1270125593227 6 -200 982 0 29733 29994 29867 0 0 0 96241 356 -0.11821 0.127208 -1.93399
1270125593247 7 -194 984 0 29739 29982 29888 0 0 0 96235 356 -0.116428 0.128791 -1.9378
unix_timestamp Accel._X Accel._Y Accel._Z Battery Bottom_Rotor CPU_Load Ground_Dist. Gyro_Phi Gyro_Psi Gyro_Theta Left_Servo Mag._X Mag._Y Mag._Z Pressure Right_Servo Temperature Top_Rotor pitch_IMU roll_IMU yaw_IMU
1270125571544 5 -197 982 0 29685 29866 29888 0 0 0 96186 354 -0.112812 0.13585 -1.94192
1270125571564 6 -198 983 0 29781 29995 29871 0 0 0 96183 354 -0.112085 0.137193 -1.94139
1270125571584 10 -197 982 0 29739 30018 29867 0 0 0 96171 354 -0.111693 0.136574 -1.94353
1270125571604 7 -198 982 0 29802 29911 29803 0 0 0 96177 354 -0.112179 0.135778 -1.94617
1270125571645 4 -197 984 0 29782 29844 29844 0 0 0 96180 354 -0.113056 0.135965 -1.94715
1270125571665 4 -200 985 0 29685 29867 29884 0 0 0 96183 354 -0.113231 0.135327 -1.94586
1270125571685 7 -198 983 0 29757 30018 29829 0 0 0 96177 354 -0.112604 0.136857 -1.94508
1270125571706 6 -198 982 0 29759 29992 29867 0 0 0 96183 354 -0.1126 0.136602 -1.94915
1270125571746 7 -196 985 0 29803 29910 29800 0 0 0 96183 354 -0.112392 0.136709 -1.95079
1270125571766 4 -198 981 0 29750 29828 29888 0 0 0 96186 354 -0.113342 0.135532 -1.95064
1270125571787 5 -197 984 0 29759 29931 29881 0 0 0 96174 354 -0.112628 0.135657 -1.9488
1270125571807 10 -197 982 0 29739 29958 29819 0 0 0 96174 354 -0.112506 0.135777 -1.95001
1270125571847 4 -198 981 0 29786 29829 29864 0 0 0 96232 356 -0.112359 0.135253 -1.94825
1270125571867 5 -201 978 0 29719 29856 29890 0 0 0 96218 356 -0.11218 0.134669 -1.94657
1270125571888 7 -198 986 0 29782 29813 29845 0 0 0 96223 356 -0.111451 0.135688 -1.9455
1270125571908 10 -200 984 0 29693 30048 29885 0 0 0 96215 356 -0.110745 0.1365 -1.94668
1270125571948 5 -197 982 0 29757 29899 29844 0 0 0 96229 356 -0.110004 0.135859 -1.94573
1270125571969 6 -197 983 0 29727 29829 29814 0 0 0 96249 356 -0.110316 0.135751 -1.94565
1270125571989 6 -197 978 0 29790 29828 29815 0 0 0 96220 356 -0.111159 0.136244 -1.94416
1270125572009 5 -194 983 0 29718 29856 29890 0 0 0 96229 356 -0.111216 0.135992 -1.94196
1270125572050 3 -196 985 0 29739 29978 29827 0 0 0 96223 356 -0.110727 0.136577 -1.94402
1270125572070 8 -198 982 0 29782 29829 29815 0 0 0 96235 356 -0.111423 0.136697 -1.94566
1270125572090 8 -195 982 0 29687 29865 29894 0 0 0 96218 356 -0.112088 0.136097 -1.9442
1270125572130 8 -198 986 0 29793 29859 29844 0 0 0 96244 356 -0.110282 0.137491 -1.94235
1270125572171 6 -198 982 0 29790 29856 29879 0 0 0 96244 356 -0.112179 0.136971 -1.94365
1270125572191 3 -198 980 0 29759 30018 29829 0 0 0 96218 356 -0.111623 0.136194 -1.94286
1270125572211 7 -198 984 0 29758 29829 29846 0 0 0 96229 356 -0.112275 0.136007 -1.94387
1270125572252 8 -197 980 0 29743 30018 29824 0 0 0 96215 356 -0.111515 0.135539 -1.94281
1270125572272 11 -195 984 0 29741 29867 29844 0 0 0 96249 356 -0.111995 0.135753 -1.94527
1270125572292 4 -200 984 0 29771 29980 29865 0 0 0 96215 356 -0.111913 0.135829 -1.94455
1270125572312 6 -198 983 0 29792 29837 29845 0 0 0 96229 356 -0.111884 0.134861 -1.94478
1270125572353 5 -196 983 0 29685 29867 29884 0 0 0 96238 356 -0.111332 0.135644 -1.94784
1270125572373 5 -198 982 0 29693 29852 29904 0 0 0 96238 356 -0.110772 0.136927 -1.94698
1270125572393 6 -195 982 0 29738 29791 29818 0 0 0 96229 356 -0.109851 0.138106 -1.94592
1270125572414 8 -198 986 0 29782 29844 29829 0 0 0 96223 356 -0.111077 0.137396 -1.9428
1270125572454 11 -198 983 0 29743 29986 29833 0 0 0 96220 356 -0.110257 0.136744 -1.94155
1270125572474 6 -198 983 0 29749 29866 29813 0 0 0 96223 356 -0.110497 0.136917 -1.94351
1270125572495 6 -197 984 0 29719 29828 29890 0 0 0 96223 356 -0.111349 0.136959 -1.94295
1270125572515 7 -197 983 0 29760 29791 29818 0 0 0 96232 356 -0.111323 0.137251 -1.93972
1270125572555 10 -198 984 0 29800 30016 29857 0 0 0 96241 356 -0.110873 0.137041 -1.94196
1270125572575 5 -200 982 0 29760 29962 29866 0 0 0 96232 356 -0.110648 0.136038 -1.9445
1270125572596 4 -197 983 0 29740 30024 29867 0 0 0 96238 356 -0.110486 0.136046 -1.94576
1270125572616 8 -196 985 0 29802 29783 29808 0 0 0 96235 356 -0.111227 0.135128 -1.94567
1270125572656 5 -198 986 0 29771 29972 29867 0 0 0 96229 356 -0.111182 0.133833 -1.94823
1270125572697 8 -196 980 0 29739 29978 29803 0 0 0 96238 356 -0.111457 0.133602 -1.94682
1270125572717 4 -196 983 0 29749 30026 29867 0 0 0 96235 356 -0.116038 0.131922 -1.93861
1270125592944 5 -195 985 0 29757 29994 29871 0 0 0 96220 356 -0.115848 0.1323 -1.93916
1270125593025 5 -200 986 0 29780 29844 29845 0 0 0 96235 356 -0.115273 0.132222 -1.93576
1270125593045 5 -197 982 0 29757 29995 29871 0 0 0 96229 356 -0.114713 0.132137 -1.93723
1270125593086 4 -197 984 0 29802 29847 29819 0 0 0 96241 356 -0.114815 0.131529 -1.93626
1270125593106 6 -202 984 0 29802 29783 29803 0 0 0 96247 356 -0.115379 0.130754 -1.93546
1270125593126 8 -196 982 0 29803 29918 29793 0 0 0 96229 356 -0.116136 0.130336 -1.93339
1270125593146 6 -196 987 0 29802 29825 29802 0 0 0 96244 356 -0.117635 0.128822 -1.93292
1270125593187 7 -197 978 0 29802 29825 29864 0 0 0 96238 356 -0.117592 0.128252 -1.93468
1270125593207 7 -197 980 0 29803 29918 29771 0 0 0 96235 356 -0.116961 0.127734 -1.93337
1270125593227 6 -200 982 0 29733 29994 29867 0 0 0 96241 356 -0.11821 0.127208 -1.93399
1270125593247 7 -194 984 0 29739 29982 29888 0 0 0 96235 356 -0.116428 0.128791 -1.9378
1270125593288 10 -197 985 0 29771 30000 29865 0 0 0 96238 356 -0.116243 0.128666 -1.93672
\ No newline at end of file
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