diff --git a/.cproject b/.cproject new file mode 100644 index 0000000000000000000000000000000000000000..43f99020af95d6f5d0d494e76fd4774c485bbc46 --- /dev/null +++ b/.cproject @@ -0,0 +1,148 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + mingw32-make + + release + false + false + true + + + mingw32-make + + debug + false + false + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/.project b/.project new file mode 100644 index 0000000000000000000000000000000000000000..fc9b8c2de7d855347764478762ca7b92aed604e6 --- /dev/null +++ b/.project @@ -0,0 +1,88 @@ + + + qgroundcontrol + + + + + + com.trolltech.qtcppproject.QtMakefileGenerator + + + + + org.eclipse.cdt.make.core.makeBuilder + clean,full,incremental, + + + org.eclipse.cdt.core.errorOutputParser + 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; + + + org.eclipse.cdt.make.core.append_environment + true + + + org.eclipse.cdt.make.core.build.arguments + + + + org.eclipse.cdt.make.core.build.command + mingw32-make + + + org.eclipse.cdt.make.core.build.target.auto + debug + + + org.eclipse.cdt.make.core.build.target.clean + clean + + + org.eclipse.cdt.make.core.build.target.inc + debug + + + org.eclipse.cdt.make.core.enableAutoBuild + false + + + org.eclipse.cdt.make.core.enableCleanBuild + true + + + org.eclipse.cdt.make.core.enableFullBuild + true + + + org.eclipse.cdt.make.core.enabledIncrementalBuild + true + + + org.eclipse.cdt.make.core.environment + QMAKESPEC=win32-g++|PATH=C:\\Qt\\2010.04\\qt\\bin;${env_var:PATH}| + + + org.eclipse.cdt.make.core.stopOnError + false + + + org.eclipse.cdt.make.core.useDefaultBuildCmd + false + + + + + org.eclipse.cdt.make.core.ScannerConfigBuilder + + + + + + org.eclipse.cdt.core.cnature + org.eclipse.cdt.core.ccnature + org.eclipse.cdt.make.core.makeNature + org.eclipse.cdt.make.core.ScannerConfigNature + com.trolltech.qtcppproject.QtNature + + diff --git a/images/style-mission.css b/images/style-mission.css index ceacf759608263b76ecb79a732be8246eb9dd51e..0eedac2194c997d897b99950a55c8f2caf195444 100644 --- a/images/style-mission.css +++ b/images/style-mission.css @@ -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; -} +} diff --git a/lib/QMapControl/src/geometry.cpp b/lib/QMapControl/src/geometry.cpp index e9319e6151d84d6f681246abae3bb541f5cd020b..62f45a75d7cfc07a2377fcba42f407c61c36583d 100644 --- a/lib/QMapControl/src/geometry.cpp +++ b/lib/QMapControl/src/geometry.cpp @@ -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; } + } diff --git a/lib/QMapControl/src/geometry.h b/lib/QMapControl/src/geometry.h index dca47800cb47dc934460e9fd1bac38d957be6c9c..2aefd955def97d20c30a15644b5fc10ae4420cb1 100644 --- a/lib/QMapControl/src/geometry.h +++ b/lib/QMapControl/src/geometry.h @@ -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 diff --git a/lib/QMapControl/src/layer.cpp b/lib/QMapControl/src/layer.cpp index 6083b3bec99201b9d321d472ba3f3193f93e9e2a..fa882117593c1efcbf97c6480ca56fea9c88a1d5 100644 --- a/lib/QMapControl/src/layer.cpp +++ b/lib/QMapControl/src/layer.cpp @@ -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; } diff --git a/lib/QMapControl/src/layermanager.cpp b/lib/QMapControl/src/layermanager.cpp index 286aceefcedfbcf02f98fd4a2a2f504064a89d6d..3e10bb225a580e39e6ed11dc755aef0ced94bb19 100644 --- a/lib/QMapControl/src/layermanager.cpp +++ b/lib/QMapControl/src/layermanager.cpp @@ -366,15 +366,26 @@ namespace qmapcontrol void LayerManager::mouseEvent(const QMouseEvent* evnt) { - QListIterator it(mylayers); - while (it.hasNext()) + // TODO: to review errors generated in the Windows operating system when the QListIterator is used + for(int i=0; iisVisible()) { l->mouseEvent(evnt, mapmiddle_px); } } +// QListIterator 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) diff --git a/qgroundcontrol.pri b/qgroundcontrol.pri index 31044634075b589f7d9801143e9af14ccb9d6438..f9bffcac10adb7110b14920f0d188a735f970167 100644 --- a/qgroundcontrol.pri +++ b/qgroundcontrol.pri @@ -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 \ diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 7168dd29e2e5c8c55c366e7d4358414d8e3dc3af..42a8aaf068cd7b626e0124052c23a625f8439386 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -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 diff --git a/src/Waypoint.h b/src/Waypoint.h index 053f6cbb0f60b1c187ffa8394e306a8b90b54cf6..d8baeba9e04eb181e112e663c425e469693f7153 100644 --- a/src/Waypoint.h +++ b/src/Waypoint.h @@ -59,7 +59,7 @@ public: bool load(QTextStream &loadStream); -private: +protected: quint16 id; float x; float y; diff --git a/src/WaypointGlobal.cpp b/src/WaypointGlobal.cpp new file mode 100644 index 0000000000000000000000000000000000000000..fc5526f1c1af4a735e87a1545d091feba0925b19 --- /dev/null +++ b/src/WaypointGlobal.cpp @@ -0,0 +1,10 @@ +#include "WaypointGlobal.h" + +#include + +WaypointGlobal::WaypointGlobal(const QPointF coordinate): + Waypoint(id, x, y, z, yaw, autocontinue, current, orbit, holdTime) +{ + coordinateWP = coordinate; + +} diff --git a/src/WaypointGlobal.h b/src/WaypointGlobal.h new file mode 100644 index 0000000000000000000000000000000000000000..4a3bc4e94ff188ad8415d77a94bd9c78797658c0 --- /dev/null +++ b/src/WaypointGlobal.h @@ -0,0 +1,29 @@ +#ifndef WAYPOINTGLOBAL_H +#define WAYPOINTGLOBAL_H + +#include "Waypoint.h" +#include + +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 diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index 02ef012214870789727e654e9a6e058e99b430b6..38bab37e092e8a030c78401f282fcb43a4ffb780 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -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(); diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 43a7bba314d64a619b5359d17ec8215006a478a4..0cd24dac764e3e7c3addd9635803a991a3c7decb 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -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 hostAddresses = QNetworkInterface::allAddresses(); - QString windowname = qApp->applicationName() + " " + qApp->applicationVersion(); - bool prevAddr = false; + QList 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(debugConsoleDockWidget->widget()); - if (debugConsole) - { - connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)), - debugConsole, SLOT(receiveTextMessage(int,int,int,QString))); - } + DebugConsole *debugConsole = dynamic_cast(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(infoDockWidget->widget()); - if (infoWidget) - { - infoWidget->addUAS(uas); - } + UASInfoWidget *infoWidget = dynamic_cast(infoDockWidget->widget()); + if (infoWidget) + { + infoWidget->addUAS(uas); + } } // UAS List if (listDockWidget) { - UASListWidget *listWidget = dynamic_cast(listDockWidget->widget()); - if (listWidget) - { - listWidget->addUAS(uas); - } + UASListWidget *listWidget = dynamic_cast(listDockWidget->widget()); + if (listWidget) + { + listWidget->addUAS(uas); + } } // Camera view @@ -530,7 +545,7 @@ void MainWindow::clearView() HDDisplay* hddWidget = dynamic_cast( headDown1DockWidget->widget() ); if (hddWidget) hddWidget->stop(); } - if (headDown2DockWidget) + if (headDown2DockWidget) { HDDisplay* hddWidget = dynamic_cast( headDown2DockWidget->widget() ); if (hddWidget) hddWidget->stop(); @@ -678,7 +693,7 @@ void MainWindow::loadPixhawkView() waypointsDockWidget->show(); } - // HORIZONTAL SITUATION INDICATOR + // HORIZONTAL SITUATION INDICATOR if (hsiDockWidget) { HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() ); @@ -730,7 +745,7 @@ void MainWindow::loadDataView() void MainWindow::loadDataView(QString fileName) { clearView(); - + // DATAPLOT if (dataplotWidget) { @@ -1026,8 +1041,8 @@ void MainWindow::loadAllView() // OBJECT DETECTION if (detectionDockWidget) { - addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget); - detectionDockWidget->show(); + addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget); + detectionDockWidget->show(); } // LINE CHART diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui index 79dc075a4e3e797814320283f4dae98d077bc51e..b9f967414b1a09b127484a3113fdafbfa5056da8 100644 --- a/src/ui/MainWindow.ui +++ b/src/ui/MainWindow.ui @@ -22,6 +22,9 @@ 800 + + false + MGMainWindow @@ -35,7 +38,7 @@ 0 0 1000 - 22 + 21 diff --git a/src/ui/MapWidget.cc b/src/ui/MapWidget.cc index 4811d955746e7aa9e3a1ad73d48b0a959a4fe813..5673d504387c4a8b8bc50080c71fe8dd54d6b23f 100644 --- a/src/ui/MapWidget.cc +++ b/src/ui/MapWidget.cc @@ -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 (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(); + } + +} diff --git a/src/ui/MapWidget.h b/src/ui/MapWidget.h index 17929329c47bbd9a372d4dd5589b450ce968b732..7d79949d6c2f7412b764d3f2d9f01a8b48c05056 100644 --- a/src/ui/MapWidget.h +++ b/src/ui/MapWidget.h @@ -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; diff --git a/src/ui/WaypointGlobalView.cpp b/src/ui/WaypointGlobalView.cpp new file mode 100644 index 0000000000000000000000000000000000000000..b57df7ffd96d560c8582c34c3926cea341d11bff --- /dev/null +++ b/src/ui/WaypointGlobalView.cpp @@ -0,0 +1,155 @@ +#include "WaypointGlobalView.h" +#include "ui_WaypointGlobalView.h" + +#include + +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(); + } +} + + diff --git a/src/ui/WaypointGlobalView.h b/src/ui/WaypointGlobalView.h new file mode 100644 index 0000000000000000000000000000000000000000..293b8b1228c90ab82acb318c6bc05197a2d4f0f2 --- /dev/null +++ b/src/ui/WaypointGlobalView.h @@ -0,0 +1,44 @@ +#ifndef WAYPOINTGLOBALVIEW_H +#define WAYPOINTGLOBALVIEW_H + +#include +#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 diff --git a/src/ui/WaypointGlobalView.ui b/src/ui/WaypointGlobalView.ui new file mode 100644 index 0000000000000000000000000000000000000000..7ad20e38549153917c15e4201ab4feb2cb6faf6d --- /dev/null +++ b/src/ui/WaypointGlobalView.ui @@ -0,0 +1,460 @@ + + + WaypointGlobalView + + + + 0 + 0 + 869 + 60 + + + + + 0 + 0 + + + + + 50 + 0 + + + + Form + + + 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("ICONDIR/control/emergency-button.png"); +} + +QPushButton:pressed#landButton { + color: #000000; + background: qlineargradient(x1:0, y1:0, x2:0, y2:1, + stop:0 #bbaa00, stop:1 #a05b00) url("ICONDIR/control/emergency-button.png"); +} + +QPushButton#killButton { + color: #000000; + background: qlineargradient(x1:0, y1:0, x2:0, y2:1, + stop:0 #ffb917, stop:1 #b37300) url("ICONDIR/control/emergency-button.png"); +} + +QPushButton:pressed#killButton { + color: #000000; + background: qlineargradient(x1:0, y1:0, x2:0, y2:1, + stop:0 #bb8500, stop:1 #903000) url("ICONDIR/control/emergency-button.png"); +} + +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; +} + + + + + + + 0 + 0 + + + + + + + + + + WP_id + + + + + + + Qt::Horizontal + + + + 135 + 13 + + + + + + + + Lat: + + + + + + + + 0 + 0 + + + + + 120 + 25 + + + + Qt::ScrollBarAlwaysOff + + + true + + + + + + + Qt::Horizontal + + + + 50 + 30 + + + + + + + + Lon: + + + + + + + + 120 + 25 + + + + Qt::ScrollBarAlwaysOff + + + true + + + + + + + Qt::Horizontal + + + + 50 + 30 + + + + + + + + Heigth + + + + + + + + + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 69 + 69 + 69 + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 37 + 37 + 40 + + + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 69 + 69 + 69 + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 37 + 37 + 40 + + + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 69 + 69 + 69 + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 37 + 37 + 40 + + + + + + + + Orbital + + + + + + + true + + + + + + + + + + + diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc index d8e80150914f3a99f6fa6cc56ff8d5929411cf3f..25b7171d71b6d79ea2dd8b546c057511987f120a 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -37,6 +37,8 @@ This file is part of the PIXHAWK project #include #include #include +#include "WaypointGlobalView.h" +#include 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 &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 &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 &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 &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 &waypoints = uas->getWaypointManager().getWaypointList(); - // first remove all views of non existing waypoints - if (!wpViews.empty()) - { - QMapIterator 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 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 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 &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 &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 &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 &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 &waypoints = uas->getWaypointManager().getWaypointList(); + while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++) + { + + WaypointView* widget = wpViews.find(waypoints[0]).value(); + + widget->remove(); + + } + } +} diff --git a/src/ui/WaypointList.h b/src/ui/WaypointList.h index 148749fcf7b8b8626d50646c22be72c77800f83e..b4d259338cd06a08f5a9839008f1ae40f4044ffe 100644 --- a/src/ui/WaypointList.h +++ b/src/ui/WaypointList.h @@ -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 wpViews; + QMap 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 diff --git a/src/ui/WaypointList.ui b/src/ui/WaypointList.ui index 8ada605ccf5e8502e3c28406817897b4e932a231..587a8c929dea70c5c6745fbb82d424f6e66025a9 100644 --- a/src/ui/WaypointList.ui +++ b/src/ui/WaypointList.ui @@ -26,7 +26,7 @@ 4 - + true @@ -37,7 +37,7 @@ 0 0 466 - 149 + 163 @@ -54,7 +54,7 @@ - + Read @@ -65,7 +65,7 @@ - + Write @@ -76,7 +76,7 @@ - + TextLabel @@ -135,6 +135,17 @@ + + + + + + + + :/images/actions/process-stop.svg:/images/actions/process-stop.svg + + + diff --git a/src/ui/WaypointView.ui b/src/ui/WaypointView.ui index d7e3375bbcf9ee1e67356d723eab33ac763565da..5c8f32af7721b6f5ed1093a812acf4c8f48ec843 100644 --- a/src/ui/WaypointView.ui +++ b/src/ui/WaypointView.ui @@ -355,7 +355,7 @@ QProgressBar::chunk#thrustBar { - + :/images/actions/go-up.svg:/images/actions/go-up.svg @@ -375,7 +375,7 @@ QProgressBar::chunk#thrustBar { - + :/images/actions/go-down.svg:/images/actions/go-down.svg @@ -395,7 +395,7 @@ QProgressBar::chunk#thrustBar { - + :/images/actions/list-remove.svg:/images/actions/list-remove.svg @@ -405,8 +405,6 @@ QProgressBar::chunk#thrustBar { - - - + diff --git a/testlog2.txt b/testlog2.txt index 4bf04c5f783eb23b97a6ce3ea0c488f9436c3354..05faada916c1e6f342b5fe6aa60f4550e26d7e94 100644 --- a/testlog2.txt +++ b/testlog2.txt @@ -1,59 +1,59 @@ -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