Commit 30108561 authored by Bryan Godbolt's avatar Bryan Godbolt

merged in latest pixhawk code

parents f53dea5c 5f119ac9
......@@ -24,3 +24,4 @@ doc/doxy.log
deploy/mac
deploy/linux
controller_log*
user_config.pri
* { font-family: "Bitstream Vera Sans"; font: "Roman"; font-size: 12px; }
QWidget#colorIcon {}
QWidget {
background-color: #050508;
color: #DDDDDF;
background-clip: border;
font-size: 11px;
}
QGroupBox {
border: 1px solid #66666B;
border-radius: 3px;
padding: 10px 0px 0px 0px;
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);
}
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;
color: #DDDDDF;
}
QDockWidget {
font: bold;
border: 1px solid #32345E;
}
QDockWidget::close-button, QDockWidget::float-button {
background-color: #181820;
color: #EEEEEE;
}
QDockWidget::title {
text-align: left;
background: #121214;
color: #4A4A4F;
padding-left: 5px;
height: 10px;
border-bottom: 1px solid #555555;
}
QSeparator {
color: #EEEEEE;
}
QSpinBox {
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;
}
QPushButton {
font-weight: bold;
min-height: 18px;
max-height: 18px;
border: 2px solid #4A4A4F;
border-radius: 5px;
padding-left: 10px;
padding-right: 10px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208);
}
QPushButton:checked {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #404040, stop: 1 #808080);
}
QPushButton:pressed {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0);
}
QToolButton {
font-weight: bold;
min-height: 16px;
min-width: 24px;
max-height: 18px;
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);
}
QToolButton:pressed {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0);
}
QPushButton#forceLandButton {
font-weight: bold;
min-height: 30px;
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #ffee01, stop:1 #ae8f00) url("ICONDIR/control/emergency-button.png");
background-clip: border;
border-width: 1px;
border-color: #555555;
border-radius: 5px;
}
QPushButton:pressed#forceLandButton {
font-weight: bold;
min-height: 30px;
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #bbaa00, stop:1 #a05b00) url("ICONDIR/control/emergency-button.png");
background-clip: border;
border-width: 1px;
border-color: #555555;
border-radius: 5px;
}
QPushButton#killButton {
font-weight: bold;
min-height: 30px;
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #ffb917, stop:1 #b37300) url("ICONDIR/control/emergency-button.png");
background-clip: border;
border-width: 1px;
border-color: #555555;
border-radius: 5px;
}
QPushButton:pressed#killButton {
font-weight: bold;
min-height: 30px;
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #bb8500, stop:1 #903000) url("ICONDIR/control/emergency-button.png");
background-clip: border;
border-width: 1px;
border-color: #555555;
border-radius: 5px;
}
QPushButton#controlButton {
min-height: 25px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #A0AE00, stop: 1 #909E00);
}
QPushButton:checked#controlButton {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #b76f11, stop: 1 #e1a718);
}
QProgressBar {
border: 1px solid #4A4A4F;
border-radius: 4px;
text-align: center;
padding: 2px;
color: #DDDDDF;
background-color: #111118;
}
QProgressBar:horizontal {
height: 9px;
}
QProgressBar:vertical {
width: 9px;
}
QProgressBar::chunk {
background-color: #3C7B9E;
}
QProgressBar::chunk#batteryBar {
background-color: green;
}
QProgressBar::chunk#speedBar {
background-color: yellow;
}
QProgressBar::chunk#thrustBar {
background-color: orange;
}
QWidget#colorIcon {}
QWidget {
background-color: #050508;
color: #DDDDDF;
background-clip: border;
font-size: 11px;
}
QGroupBox {
border: 1px solid #66666B;
border-radius: 3px;
padding: 10px 0px 0px 0px;
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);
}
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;
color: #DDDDDF;
}
QDockWidget {
font: bold;
border: 1px solid #32345E;
}
QDockWidget::close-button, QDockWidget::float-button {
background-color: #181820;
color: #EEEEEE;
}
QDockWidget::title {
text-align: left;
background: #121214;
color: #4A4A4F;
padding-left: 5px;
height: 10px;
border-bottom: 1px solid #555555;
}
QSeparator {
color: #EEEEEE;
}
QSpinBox {
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;
}
QPushButton {
font-weight: bold;
min-height: 18px;
max-height: 18px;
border: 2px solid #4A4A4F;
border-radius: 5px;
padding-left: 10px;
padding-right: 10px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208);
}
QPushButton:checked {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #404040, stop: 1 #808080);
}
QPushButton:pressed {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0);
}
QToolButton {
font-weight: bold;
min-height: 16px;
min-width: 24px;
max-height: 18px;
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);
}
QToolButton:pressed {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0);
}
QToolTip {
background-color: #404040;
border-radius: 3px;
}
QPushButton#forceLandButton {
font-weight: bold;
min-height: 30px;
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #ffee01, stop:1 #ae8f00) url("ICONDIR/control/emergency-button.png");
background-clip: border;
border-width: 1px;
border-color: #555555;
border-radius: 5px;
}
QPushButton:pressed#forceLandButton {
font-weight: bold;
min-height: 30px;
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #bbaa00, stop:1 #a05b00) url("ICONDIR/control/emergency-button.png");
background-clip: border;
border-width: 1px;
border-color: #555555;
border-radius: 5px;
}
QPushButton#killButton {
font-weight: bold;
min-height: 30px;
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #ffb917, stop:1 #b37300) url("ICONDIR/control/emergency-button.png");
background-clip: border;
border-width: 1px;
border-color: #555555;
border-radius: 5px;
}
QPushButton:pressed#killButton {
font-weight: bold;
min-height: 30px;
color: #000000;
background: qlineargradient(x1:0, y1:0, x2:0, y2:1,
stop:0 #bb8500, stop:1 #903000) url("ICONDIR/control/emergency-button.png");
background-clip: border;
border-width: 1px;
border-color: #555555;
border-radius: 5px;
}
QPushButton#controlButton {
min-height: 25px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #A0AE00, stop: 1 #909E00);
}
QPushButton:checked#controlButton {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #b76f11, stop: 1 #e1a718);
}
QProgressBar {
border: 1px solid #4A4A4F;
border-radius: 4px;
text-align: center;
padding: 2px;
color: #DDDDDF;
background-color: #111118;
}
QProgressBar:horizontal {
height: 9px;
}
QProgressBar:vertical {
width: 9px;
}
QProgressBar::chunk {
background-color: #3C7B9E;
}
QProgressBar::chunk#batteryBar {
background-color: green;
}
QProgressBar::chunk#speedBar {
background-color: yellow;
}
QProgressBar::chunk#thrustBar {
background-color: orange;
}
......@@ -29,7 +29,7 @@
namespace qmapcontrol
{
GoogleSatMapAdapter::GoogleSatMapAdapter()
: TileMapAdapter("khm.google.com", "/kh?v=51&x=%2&s=&y=%3&z=%1", 256, 0, 17)
: TileMapAdapter("khm.google.com", "/kh?v=51&x=%2&s=&y=%3&z=%1", 256, 0, 18)
{
// // name = "googlesat";
//
......
......@@ -97,6 +97,36 @@ namespace qmapcontrol
geometries.clear();
}
Geometry* Layer::get_Geometry(int index)
{
if(geometrySelected)
{
return geometrySelected;
}
else
{
for(int i = 0; i <= geometries.size(); i++)
{
Geometry *geometry = geometries[i];
if(geometry->name() == QString::number(index))
{
return geometry;
}
}
// foreach(Geometry *geometry, geometries)
// {
// if(geometry->name() == QString::number(index))
// {
// return geometry;
// }
// }
}
}
bool Layer::isVisible() const
{
return visible;
......@@ -323,3 +353,5 @@ namespace qmapcontrol
mapAdapter = mapadapter;
}
}
......@@ -200,6 +200,12 @@ namespace qmapcontrol
*/
void setVisible(bool visible);
//! get geometry selected by index
/*!
* @param index of geometry selected
*/
Geometry* get_Geometry(int index);
};
}
#endif
......@@ -309,6 +309,7 @@ namespace qmapcontrol
click.y()-screen_middle.y()+layermanager->getMapmiddle_px().y());
// image coordinate to world coordinate
return layermanager->layer()->mapadapter()->displayToCoordinate(displayToImage);
}
void MapControl::updateRequest(QRect rect)
......
#-------------------------------------------------
#
# MAVGround - Micro Air Vehicle Groundstation
#
# QGroundControl - Micro Air Vehicle Groundstation
#
# Please see our website at <http://qgroundcontrol.org>
#
# Original Author:
# Author:
# Lorenz Meier <mavteam@student.ethz.ch>
#
# Contributing Authors (in alphabetical order):
#
# (c) 2009 PIXHAWK Team
# (c) 2009-2010 PIXHAWK Team
#
# This file is part of the mav groundstation project
# MAVGround is free software: you can redistribute it and/or modify
# QGroundControl is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
# MAVGround is distributed in the hope that it will be useful,
# QGroundControl is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
# You should have received a copy of the GNU General Public License
# along with MAVGround. If not, see <http://www.gnu.org/licenses/>.
# along with QGroundControl. If not, see <http://www.gnu.org/licenses/>.
#
#-------------------------------------------------
......@@ -108,7 +106,7 @@ linux-g++ {
LIBS += \
-L/usr/lib \
-lm \
-lflite_cmu_us_kal16 \
-lflite_cmu_us_kal \
-lflite_usenglish \
-lflite_cmulex \
-lflite \
......@@ -150,7 +148,7 @@ linux-g++-64 {
LIBS += \
-L/usr/lib \
-lm \
-lflite_cmu_us_kal16 \
-lflite_cmu_us_kal \
-lflite_usenglish \
-lflite_cmulex \
-lflite \
......
#-------------------------------------------------
#
# QGroundControl - Micro Air Vehicle Groundstation
#
# Please see our website at <http://qgroundcontrol.org>
#
# Author:
# Lorenz Meier <mavteam@student.ethz.ch>
#
# (c) 2009-2010 PIXHAWK Team
#
# This file is part of the mav groundstation project
# QGroundControl is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
# QGroundControl is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
# You should have received a copy of the GNU General Public License
# along with QGroundControl. If not, see <http://www.gnu.org/licenses/>.
#
#-------------------------------------------------
# Include QMapControl map library
# prefer version from external directory /
# from http://github.com/pixhawk/qmapcontrol/
......@@ -5,6 +31,7 @@
# Version from GIT repository is preferred
# include ( "../qmapcontrol/QMapControl/QMapControl.pri" ) #{
# Include bundled version if necessary
include(lib/QMapControl/QMapControl.pri)
# message("Including bundled QMapControl version as FALLBACK. This is fine on Linux and MacOS, but not the best choice in Windows")
......@@ -24,6 +51,12 @@ OBJECTS_DIR = $$BUILDDIR/obj
MOC_DIR = $$BUILDDIR/moc
UI_HEADERS_DIR = src/ui/generated
exists(user_config.pri) {
message("----- USING USER QGROUNDCONTROL CONFIG FROM user_config.pri -----")
include(user_config.pri)
}
# }
# Include general settings for MAVGround
# necessary as last include to override any non-acceptable settings
......@@ -42,8 +75,8 @@ DEPENDPATH += . \
plugins
INCLUDEPATH += . \
lib/QMapControl \
$$BASEDIR/../mavlink/contrib/slugs/include \
$$BASEDIR/../mavlink/include
$$BASEDIR/../mavlink/include \
$$BASEDIR/../mavlink/include/common
# ../mavlink/include \
# MAVLink/include \
......@@ -159,7 +192,6 @@ HEADERS += src/MG.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/MAV2DIcon.h \
src/ui/QGCRemoteControlView.h \
src/WaypointGlobal.h \
src/ui/WaypointGlobalView.h \
src/ui/RadioCalibration/RadioCalibrationData.h \
src/ui/RadioCalibration/RadioCalibrationWindow.h \
......@@ -170,7 +202,13 @@ HEADERS += src/MG.h \
src/ui/map3D/Q3DWidget.h \
src/ui/map3D/CheetahModel.h \
src/ui/map3D/CheetahGL.h \
src/ui/map3D/QMap3DWidget.h
src/ui/map3D/QMap3DWidget.h \
src/ui/map3D/Texture.h \
src/ui/map3D/TextureCache.h \
src/ui/map3D/WebImage.h \
src/ui/map3D/WebImageCache.h \
src/ui/map3D/Imagery.h \
src/comm/QGCMAVLink.h
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
......@@ -242,10 +280,16 @@ SOURCES += src/main.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/WaypointGlobalView.cc \
src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/CheetahModel.cc \
src/ui/map3D/CheetahGL.cc \
src/ui/map3D/QMap3DWidget.cc
src/ui/map3D/QMap3DWidget.cc \
src/ui/map3D/Texture.cc \
src/ui/map3D/TextureCache.cc \
src/ui/map3D/WebImageCache.cc \
src/ui/map3D/WebImage.cc \
src/ui/map3D/Imagery.cc
RESOURCES = mavground.qrc
# Include RT-LAB Library
......
......@@ -81,6 +81,7 @@ public slots:
void setOrbit(float orbit);
void setHoldTime(int holdTime);
//for QDoubleSpin
void setX(double x);
void setY(double 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
......@@ -2,7 +2,7 @@
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
......
......@@ -45,7 +45,7 @@ This file is part of the QGROUNDCONTROL project
#include "ArduPilotMAV.h"
#include "configuration.h"
#include "LinkManager.h"
#include <mavlink.h>
#include <QGCMAVLink.h>
#include "QGC.h"
/**
......
......@@ -39,8 +39,7 @@ This file is part of the QGROUNDCONTROL project
#include <QByteArray>
#include "ProtocolInterface.h"
#include "LinkInterface.h"
#include "protocol.h"
#include "mavlink.h"
#include "QGCMAVLink.h"
/**
* @brief MAVLink micro air vehicle protocol reference implementation.
......
......@@ -41,7 +41,7 @@ This file is part of the QGROUNDCONTROL project
#include "MAVLinkProtocol.h"
#include "MAVLinkSimulationLink.h"
// MAVLINK includes
#include <mavlink.h>
#include <QGCMAVLink.h>
#include "QGC.h"
/**
......@@ -100,9 +100,10 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile
mavlinkLogFile = new QFile(MAVLinkProtocol::getLogfileName());
mavlinkLogFile->open(QIODevice::ReadOnly);
x = 0;
y = 0;
z = 0;
// position at Pixhawk lab @ ETHZ
x = 5247273.0f;
y = 465955.0f;
z = -0.2f;
yaw = 0;
}
......@@ -376,18 +377,20 @@ void MAVLinkSimulationLink::mainloop()
{
rate10hzCounter = 1;
// Move X Position
x += sin(QGC::groundTimeUsecs()*1000) * 0.05f;
y += sin(QGC::groundTimeUsecs()) * 0.05f;
z += sin(QGC::groundTimeUsecs()) * 0.009f;
x = (x > 5.0f) ? 5.0f : x;
y = (y > 5.0f) ? 5.0f : y;
z = (z > 3.0f) ? 3.0f : z;
x = (x < -5.0f) ? -5.0f : x;
y = (y < -5.0f) ? -5.0f : y;
z = (z < -3.0f) ? -3.0f : z;
// Move X Position
x = x*0.93f + 0.07f*(x+sin(QGC::groundTimeUsecs()) * 0.08f);
y = y*0.93f + 0.07f*(y+sin(QGC::groundTimeUsecs()) * 0.5f);
z = z*0.93f + 0.07f*(z+sin(QGC::groundTimeUsecs()*100000) * 0.1f);
// x = (x > 5.0f) ? 5.0f : x;
// y = (y > 5.0f) ? 5.0f : y;
// z = (z > 3.0f) ? 3.0f : z;
//
// x = (x < -5.0f) ? -5.0f : x;
// y = (y < -5.0f) ? -5.0f : y;
// z = (z < -3.0f) ? -3.0f : z;
// Send back new setpoint
mavlink_message_t ret;
......@@ -398,7 +401,7 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength;
// Send back new position
mavlink_msg_local_position_pack(systemId, componentId, &ret, 0, x, y, z, 0, 0, 0);
mavlink_msg_local_position_pack(systemId, componentId, &ret, 0, y+z, y, -fabs(z), 0, 0, 0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......
......@@ -39,7 +39,7 @@ This file is part of the QGROUNDCONTROL project
#include <QMutex>
#include <QMap>
#include <inttypes.h>
#include <mavlink.h>
#include "QGCMAVLink.h"
#include "LinkInterface.h"
......
......@@ -71,7 +71,13 @@ bool MAVLinkXMLParser::generate()
bool success = true;
// Only generate if output dir is correctly set
if (outputDirName == "") return false;
if (outputDirName == "")
{
emit parseState(tr("<font color=\"red\">ERROR: No output directory given.\nAbort.</font>"));
return false;
}
QString topLevelOutputDirName = outputDirName;
// print out the element names of all elements that are direct children
// of the outermost element.
......@@ -87,6 +93,31 @@ bool MAVLinkXMLParser::generate()
QString lcmStructDefs = "";
QString pureFileName;
QString pureIncludeFileName;
QFileInfo fInfo(this->fileName);
pureFileName = fInfo.baseName().split(".", QString::SkipEmptyParts).first();
// XML parsed and converted to C code. Now generating the files
outputDirName += QDir::separator() + pureFileName;
QDateTime now = QDateTime::currentDateTime().toUTC();
QLocale loc(QLocale::English);
QString dateFormat = "dddd, MMMM d yyyy, hh:mm UTC";
QString date = loc.toString(now, dateFormat);
QString includeLine = "#include \"%1\"\n";
QString mainHeaderName = pureFileName + ".h";
QString messagesDirName = ".";//"generated";
QDir dir(outputDirName + "/" + messagesDirName);
// Start main header
QString mainHeader = QString("/** @file\n *\t@brief MAVLink comm protocol.\n *\t@see http://pixhawk.ethz.ch/software/mavlink\n *\t Generated on %1\n */\n#ifndef " + pureFileName.toUpper() + "_H\n#define " + pureFileName.toUpper() + "_H\n\n").arg(date); // The main header includes all messages
// Mark all code as C code
mainHeader += "#ifdef __cplusplus\nextern \"C\" {\n#endif\n\n";
mainHeader += "\n#include \"../protocol.h\"\n";
mainHeader += "\n#define MAVLINK_ENABLED_" + pureFileName.toUpper() + "\n\n";
// Run through root children
while(!n.isNull())
......@@ -107,47 +138,55 @@ bool MAVLinkXMLParser::generate()
// Handle all include tags
if (e.tagName() == "include")
{
QString fileName = e.text();
QString incFileName = e.text();
// Load file
QDomDocument includeDoc = QDomDocument();
//QDomDocument includeDoc = QDomDocument();
// Prepend file path if it is a relative path and
// make it relative to opened file
QFileInfo fInfo(fileName);
QFileInfo fInfo(incFileName);
QString incFilePath;
if (fInfo.isRelative())
{
QFileInfo rInfo(this->fileName);
fileName = rInfo.absoluteDir().canonicalPath() + "/" + fileName;
pureFileName = rInfo.baseName().split(".").first();
incFilePath = rInfo.absoluteDir().canonicalPath() + "/" + incFileName;
pureIncludeFileName = fInfo.baseName().split(".", QString::SkipEmptyParts).first();
}
QFile file(fileName);
QFile file(incFilePath);
if (file.open(QIODevice::ReadOnly | QIODevice::Text))
{
const QString instanceText(QString::fromUtf8(file.readAll()));
includeDoc.setContent(instanceText);
// Get all messages
QDomNode in = includeDoc.documentElement().firstChild();
//while (!in.isNull())
//{
QDomElement ie = in.toElement();
if (!ie.isNull())
{
if (ie.tagName() == "messages" || ie.tagName() == "include")
{
QDomNode ref = n.parentNode().insertAfter(in, n);
if (ref.isNull())
{
emit parseState(QString("<font color=\"red\">ERROR: Inclusion failed: XML syntax error in file %1. Wrong/misspelled XML?\nAbort.</font>").arg(fileName));
return false;
}
}
}
//in = in.nextSibling();
//}
emit parseState(QString("<font color=\"green\">Included messages from file: %1</font>").arg(fileName));
emit parseState(QString("<font color=\"green\">Included messages from file: %1</font>").arg(incFileName));
// NEW MODE: CREATE INDIVIDUAL FOLDERS
// Create new output directory, parse included XML and generate C-code
MAVLinkXMLParser includeParser(incFilePath, topLevelOutputDirName, this);
connect(&includeParser, SIGNAL(parseState(QString)), this, SIGNAL(parseState(QString)));
// Generate and write
includeParser.generate();
mainHeader += "\n#include \"../" + pureIncludeFileName + "/" + pureIncludeFileName + ".h\"\n";
// OLD MODE: MERGE BOTH FILES
// const QString instanceText(QString::fromUtf8(file.readAll()));
// includeDoc.setContent(instanceText);
// // Get all messages
// QDomNode in = includeDoc.documentElement().firstChild();
// QDomElement ie = in.toElement();
// if (!ie.isNull())
// {
// if (ie.tagName() == "messages" || ie.tagName() == "include")
// {
// QDomNode ref = n.parentNode().insertAfter(in, n);
// if (ref.isNull())
// {
// emit parseState(QString("<font color=\"red\">ERROR: Inclusion failed: XML syntax error in file %1. Wrong/misspelled XML?\nAbort.</font>").arg(fileName));
// return false;
// }
// }
// }
emit parseState(QString("<font color=\"green\">End of inclusion from file: %1</font>").arg(incFileName));
}
else
{
......@@ -406,20 +445,7 @@ bool MAVLinkXMLParser::generate()
n = n.nextSibling();
} // While through root children
// XML parsed and converted to C code. Now generating the files
QDateTime now = QDateTime::currentDateTime().toUTC();
QLocale loc(QLocale::English);
QString dateFormat = "dddd, MMMM d yyyy, hh:mm UTC";
QString date = loc.toString(now, dateFormat);
QString mainHeader = QString("/** @file\n *\t@brief MAVLink comm protocol.\n *\t@see http://pixhawk.ethz.ch/software/mavlink\n *\t Generated on %1\n */\n#ifndef MAVLINK_H\n#define MAVLINK_H\n\n").arg(date); // The main header includes all messages
// Mark all code as C code
mainHeader += "#ifdef __cplusplus\nextern \"C\" {\n#endif\n\n";
mainHeader += "\n#include \"protocol.h\"\n";
mainHeader += "\n#define MAVLINK_ENABLED_" + pureFileName.toUpper() + "\n\n";
QString includeLine = "#include \"%1\"\n";
QString mainHeaderName = "mavlink.h";
QString messagesDirName = "generated";
QDir dir(outputDirName + "/" + messagesDirName);
// Create directory if it doesn't exist, report result in success
if (!dir.exists()) success = success && dir.mkpath(outputDirName + "/" + messagesDirName);
for (int i = 0; i < cFiles.size(); i++)
......@@ -428,6 +454,7 @@ bool MAVLinkXMLParser::generate()
bool ok = rawFile.open(QIODevice::WriteOnly | QIODevice::Text);
success = success && ok;
rawFile.write(cFiles.at(i).second.toLatin1());
rawFile.close();
mainHeader += includeLine.arg(messagesDirName + "/" + cFiles.at(i).first);
}
......@@ -441,6 +468,18 @@ bool MAVLinkXMLParser::generate()
bool ok = rawHeader.open(QIODevice::WriteOnly | QIODevice::Text);
success = success && ok;
rawHeader.write(mainHeader.toLatin1());
rawHeader.close();
// Write alias mavlink header
QFile mavlinkHeader(outputDirName + "/mavlink.h");
ok = mavlinkHeader.open(QIODevice::WriteOnly | QIODevice::Text);
success = success && ok;
QString mHeader = QString("/** @file\n *\t@brief MAVLink comm protocol.\n *\t@see http://pixhawk.ethz.ch/software/mavlink\n *\t Generated on %1\n */\n#ifndef MAVLINK_H\n#define MAVLINK_H\n\n").arg(date); // The main header includes all messages
// Mark all code as C code
mHeader += "#include \"" + mainHeaderName + "\"\n\n";
mHeader += "#endif\n";
mavlinkHeader.write(mHeader.toLatin1());
mavlinkHeader.close();
// Write C structs / lcm definitions
// QFile lcmStructs(outputDirName + "/mavlink.lcm");
......
......@@ -43,8 +43,7 @@ This file is part of the QGROUNDCONTROL project
#include "LinkInterface.h"
#include "LinkManager.h"
#include "MG.h"
#include "mavlink.h"
#include "mavlink_types.h"
#include "QGCMAVLink.h"
#include "configuration.h"
#include "OpalRT.h"
#include "ParameterList.h"
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief MAVLink header file for QGroundControl
* @author Lorenz Meier <pixhawk@switched.com>
*/
#ifndef QGCMAVLINK_H
#define QGCMAVLINK_H
#include <mavlink_types.h>
#include <mavlink.h>
#ifdef QGC_USE_PIXHAWK_MESSAGES
#include <pixhawk.h>
#endif
#ifdef QGC_USE_SLUGS_MESSAGES
#include <slugs.h>
#endif
#ifdef QGC_USE_UALBERTA_MESSAGES
#include <ualberta.h>
#endif
#ifdef QGC_USE_ARDUPILOT_MESSAGES
#include <ardupilot.h>
#endif
#endif // QGCMAVLINK_H
......@@ -2,7 +2,7 @@
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
......
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
QGroundControl Open Source Ground Control Station
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
PIXHAWK is distributed in the hope that it will be useful,
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
......
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
QGroundControl Open Source Ground Control Station
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
PIXHAWK is distributed in the hope that it will be useful,
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
......
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
QGroundControl Open Source Ground Control Station
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
PIXHAWK is distributed in the hope that it will be useful,
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
......
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
QGroundControl Open Source Ground Control Station
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the PIXHAWK project
This file is part of the QGROUNDCONTROL project
PIXHAWK is free software: you can redistribute it and/or modify
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
PIXHAWK is distributed in the hope that it will be useful,
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
......
......@@ -53,7 +53,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break;
}
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES_QGC
case MAVLINK_MSG_ID_CPU_LOAD:
{
......
......@@ -42,7 +42,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGC.h"
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include <mavlink.h>
#include "QGCMAVLink.h"
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id),
......@@ -646,6 +646,27 @@ void UAS::startRadioControlCalibration()
sendMessage(msg);
}
void UAS::startDataRecording()
{
mavlink_message_t msg;
mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_START);
sendMessage(msg);
}
void UAS::pauseDataRecording()
{
mavlink_message_t msg;
mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_PAUSE);
sendMessage(msg);
}
void UAS::stopDataRecording()
{
mavlink_message_t msg;
mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_STOP);
sendMessage(msg);
}
void UAS::startMagnetometerCalibration()
{
mavlink_message_t msg;
......
......@@ -35,7 +35,7 @@ This file is part of the QGROUNDCONTROL project
#include "UASInterface.h"
#include "MG.h"
#include <MAVLinkProtocol.h>
#include <mavlink.h>
#include "QGCMAVLink.h"
/**
* @brief A generic MAVLINK-connected MAV/UAV
......@@ -247,6 +247,10 @@ public slots:
void startGyroscopeCalibration();
void startPressureCalibration();
void startDataRecording();
void pauseDataRecording();
void stopDataRecording();
signals:
/** @brief The main/battery voltage has changed/was updated */
......
......@@ -36,7 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include <QVector>
#include <QTimer>
#include "Waypoint.h"
#include <mavlink.h>
#include "QGCMAVLink.h"
class UAS;
/**
......
......@@ -405,7 +405,7 @@ void HUD::paintCenterBackground(float roll, float pitch, float yaw)
// Translate in the direction of the rotation based
// on the pitch. On the 777, a pitch of 1 degree = 2 mm
//glTranslatef(0, ((-pitch/M_PI)*180.0f * vPitchPerDeg), 0);
glTranslatef(0.0f, (pitch * vPitchPerDeg * 16.5f), 0.0f);
glTranslatef(0.0f, (-pitch * vPitchPerDeg * 16.5f), 0.0f);
// Ground
glColor3ub(179,102,0);
......@@ -574,6 +574,9 @@ void HUD::paintHUD()
if ((yawTrans < 5.0) && (yawTrans > -5.0)) yawTrans = 0;
// Negate to correct direction
yawTrans = -yawTrans;
//qDebug() << "yaw translation" << yawTrans << "integral" << yawInt << "difference" << yawDiff << "yaw" << yaw;
// Update scaling factor
......@@ -718,7 +721,7 @@ void HUD::paintHUD()
// Rotate view and draw all roll-dependent indicators
painter.rotate((roll/M_PI)* -180.0f);
painter.translate(0, (pitch/M_PI)* -180.0f * refToScreenY(1.8));
painter.translate(0, (-pitch/M_PI)* -180.0f * refToScreenY(1.8));
//qDebug() << "ROLL" << roll << "PITCH" << pitch << "YAW DIFF" << valuesDot.value("roll", 0.0f);
......
......@@ -171,6 +171,9 @@ void MainWindow::buildWidgets()
rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
headUpDockWidget = new QDockWidget(tr("Control Indicator"), this);
headUpDockWidget->setWidget( new HUD(320, 240, this));
// Dialogue widgets
//FIXME: free memory in destructor
joystick = new JoystickInput();
......@@ -203,8 +206,13 @@ void MainWindow::connectWidgets()
// 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(createGlobalWP(bool, QPointF)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool, QPointF)));
connect(mapWidget, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypointsDockWidget->widget(), SLOT(waypointGlobalChanged(QPointF,int)) );
// it notifies that a waypoint global goes to do create and a map graphic too
connect(waypointsDockWidget->widget(), SIGNAL(createWaypointAtMap(QPointF)), mapWidget, SLOT(createWaypointGraphAtMap(QPointF)));
// it notifies that a waypoint global change its position by spinBox on Widget WaypointView
connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
}
}
......@@ -213,7 +221,6 @@ void MainWindow::arrangeCenterStack()
QStackedWidget *centerStack = new QStackedWidget(this);
if (!centerStack) return;
if (linechartWidget) centerStack->addWidget(linechartWidget);
if (protocolWidget) centerStack->addWidget(protocolWidget);
if (mapWidget) centerStack->addWidget(mapWidget);
......@@ -362,7 +369,7 @@ void MainWindow::connectActions()
connect(ui.actionShow_MAVLink_view, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
connect(ui.actionShow_data_analysis_view, SIGNAL(triggered()), this, SLOT(loadDataView()));
connect(ui.actionStyleConfig, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
connect(ui.actionGlobalOperatorView, SIGNAL(triggered()), this, SLOT(loadGlobalOperatorView()));
connect(ui.actionOnline_documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
connect(ui.actionCredits_Developers, SIGNAL(triggered()), this, SLOT(showCredits()));
connect(ui.actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap()));
......@@ -808,6 +815,7 @@ void MainWindow::loadOperatorView()
centerStack->setCurrentWidget(mapWidget);
}
}
// UAS CONTROL
if (controlDockWidget)
{
......@@ -865,6 +873,83 @@ void MainWindow::loadOperatorView()
this->show();
}
void MainWindow::loadGlobalOperatorView()
{
clearView();
// MAP
if (mapWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(mapWidget);
}
}
// UAS CONTROL
if (controlDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// UAS LIST
if (listDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS
if (infoDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// WAYPOINT LIST
if (waypointsDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// // HORIZONTAL SITUATION INDICATOR
// if (hsiDockWidget)
// {
// HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
// if (hsi)
// {
// addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
// hsiDockWidget->show();
// hsi->start();
// }
// }
// PROCESS CONTROL
if (watchdogControlDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
watchdogControlDockWidget->show();
}
// HEAD UP DISPLAY
if (headUpDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, headUpDockWidget);
// FIXME Replace with default ->show() call
HUD* hud = dynamic_cast<HUD*>(headUpDockWidget->widget());
if (hud)
{
headUpDockWidget->show();
hud->start();
}
}
}
void MainWindow::load3DView()
{
clearView();
......
......@@ -122,6 +122,8 @@ public slots:
void loadDataView();
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
/** @brief Load view for global operator, allowing to flight on earth */
void loadGlobalOperatorView();
/** @brief Show the online help for users */
void showHelp();
......@@ -174,6 +176,7 @@ protected:
QPointer<QDockWidget> headDown1DockWidget;
QPointer<QDockWidget> headDown2DockWidget;
QPointer<QDockWidget> watchdogControlDockWidget;
QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget;
......
......@@ -76,6 +76,7 @@
<addaction name="actionPilotView"/>
<addaction name="actionOperatorView"/>
<addaction name="action3DView"/>
<addaction name="actionGlobalOperatorView"/>
<addaction name="separator"/>
<addaction name="actionShow_MAVLink_view"/>
<addaction name="actionShow_data_analysis_view"/>
......@@ -308,6 +309,15 @@
<string>Credits / Developers</string>
</property>
</action>
<action name="actionGlobalOperatorView">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/categories/applications-internet.svg</normaloff>:/images/categories/applications-internet.svg</iconset>
</property>
<property name="text">
<string>Show Global operator view</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......
......@@ -47,10 +47,13 @@ MapWidget::MapWidget(QWidget *parent) :
zoomLevel(0),
uasIcons(),
uasTrails(),
mav(NULL),
m_ui(new Ui::MapWidget)
{
m_ui->setupUi(this);
waypointIsDrag = false;
// Accept focus by clicking or keyboard
this->setFocusPolicy(Qt::StrongFocus);
......@@ -314,8 +317,9 @@ void MapWidget::createPathButtonClicked(bool checked)
this->setCursor(Qt::PointingHandCursor);
mc->setMouseMode(qmapcontrol::MapControl::None);
// emit signal start to create a Waypoint global
emit createGlobalWP(true);
emit createGlobalWP(true, mc->currentCoordinate());
// // Clear the previous WP track
// // TODO: Move this to an actual clear track button and add a warning dialog
......@@ -337,9 +341,11 @@ void MapWidget::createPathButtonClicked(bool checked)
}
void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate){
void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate)
{
if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked()){
if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked())
{
// Create waypoint name
QString str;
......@@ -373,18 +379,45 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
}
}
void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){
void MapWidget::createWaypointGraphAtMap(const QPointF coordinate)
{
// Create waypoint name
QString str;
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);
mc->layer("Waypoints")->addGeometry(tempCirclePoint);
Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str);
wps.append(tempPoint);
path->addPoint(tempPoint);
wpIndex.insert(str,tempPoint);
// Refresh the screen
mc->updateRequestNew();
//// // emit signal mouse was clicked
// emit captureMapCoordinateClick(coordinate);
}
void MapWidget::captureGeometryClick(Geometry* geom, QPoint point)
{
Q_UNUSED(geom);
Q_UNUSED(point);
mc->setMouseMode(qmapcontrol::MapControl::None);
}
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
{
Q_UNUSED(coordinate);
waypointIsDrag = true;
// Refresh the screen
mc->updateRequestNew();
......@@ -412,6 +445,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
{
waypointIsDrag = false;
mc->setMouseMode(qmapcontrol::MapControl::Panning);
......@@ -603,10 +637,35 @@ void MapWidget::clearPath()
wpIndex.clear();
mc->updateRequestNew();
// si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicket
if(createPath->isChecked())
{
createPath->click();
}
}
void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon)
{
if(!waypointIsDrag)
{
qDebug() <<"indice WP= "<<index <<"\n";
QPointF coordinate;
coordinate.setX(lon);
coordinate.setY(lat);
Point* point2Find;
point2Find = wpIndex[QString::number(index)];
point2Find->setCoordinate(coordinate);
point2Find = dynamic_cast <Point*> (mc->layer("Waypoints")->get_Geometry(index));
point2Find->setCoordinate(coordinate);
// Refresh the screen
mc->updateRequestNew();
}
}
......@@ -66,6 +66,7 @@ public slots:
//ROCA
void clearPath();
void changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon);
protected:
void changeEvent(QEvent* e);
......@@ -106,6 +107,7 @@ protected:
protected slots:
void captureMapClick (const QMouseEvent* event, const QPointF coordinate);
void createWaypointGraphAtMap (const QPointF coordinate);
void createPathButtonClicked(bool checked);
void captureGeometryClick(Geometry*, QPoint);
void mapproviderSelected(QAction* action);
......@@ -114,10 +116,11 @@ protected:
signals:
//void movePoint(QPointF newCoord);
void captureMapCoordinateClick(const QPointF coordinate); //ROCA
void createGlobalWP(bool value);
void createGlobalWP(bool value, QPointF centerCoordinate);
void sendGeometryEndDrag(const QPointF coordinate, const int index);
......@@ -127,6 +130,7 @@ private:
QHash <QString, qmapcontrol::Point*> wpIndex;
qmapcontrol::LineString* path;
QPen* pointPen;
bool waypointIsDrag;
};
#endif // MAPWIDGET_H
......@@ -12,14 +12,30 @@ WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) :
ui->m_orbitalSpinBox->hide();
// Read values and set user interface
updateValues();
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)));
//for spinBox Latitude
connect(ui->m_latitudGrados_spinBox, SIGNAL(valueChanged(int)), this, SLOT(updateLatitudeWP(int)));
connect(ui->m_latitudMinutos_spinBox, SIGNAL(valueChanged(double)), this, SLOT(updateLatitudeMinuteWP(double)));
connect(ui->m_dirLatitudeN_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLatitudeWP()));
connect(ui->m_dirLatitudeS_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLatitudeWP()));
//for spinBox Longitude
connect(ui->m_longitudGrados_spinBox, SIGNAL(valueChanged(int)), this, SLOT(updateLongitudeWP(int)));
connect(ui->m_longitudMinutos_spinBox, SIGNAL(valueChanged(double)), this, SLOT(updateLongitudeMinuteWP(double)));
connect(ui->m_dirLongitudeW_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLongitudeWP()));
connect(ui->m_dirLongitudeE_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLongitudeWP()));
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)));
......@@ -48,9 +64,46 @@ WaypointGlobalView::~WaypointGlobalView()
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()));\
int gradoLat, gradoLon;
float minLat, minLon;
QString dirLat, dirLon;
getLatitudeGradoMin(wp->getY(), &gradoLat, &minLat, &dirLat);
getLongitudGradoMin(wp->getX(), &gradoLon, &minLon, &dirLon);
//latitude on spinBox
ui->m_latitudGrados_spinBox->setValue(gradoLat);
ui->m_latitudMinutos_spinBox->setValue(minLat);
if(dirLat == "N")
{
ui->m_dirLatitudeN_radioButton->setChecked(true);
ui->m_dirLatitudeS_radioButton->setChecked(false);
}
else
{
ui->m_dirLatitudeS_radioButton->setChecked(true);
ui->m_dirLatitudeN_radioButton->setChecked(false);
}
//longitude on spinBox
ui->m_longitudGrados_spinBox->setValue(gradoLon);
ui->m_longitudMinutos_spinBox->setValue(minLon);
if(dirLon == "W")
{
ui->m_dirLongitudeW_radioButton->setChecked(true);
ui->m_dirLongitudeE_radioButton->setChecked(false);
}
else
{
ui->m_dirLongitudeE_radioButton->setChecked(true);
ui->m_dirLongitudeW_radioButton->setChecked(false);
}
ui->idWP_label->setText(QString("WP-%1").arg(wp->getId()));
}
......@@ -152,4 +205,258 @@ void WaypointGlobalView::changeOrbitalState(int state)
}
}
void WaypointGlobalView::getLatitudeGradoMin(float latitud, int *gradoLat, float *minLat, QString *dirLat)
{
float minutos = 0;
float grados = 0;
float entero = 0;
float dec = 0;
if (latitud<0){*dirLat="S"; latitud = latitud * -1;}
else {*dirLat="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);
*gradoLat = grados;
*minLat = minutos;
}
else
{
*gradoLat = -1;
*minLat = -1;
*dirLat="N/A";
}
}
void WaypointGlobalView::getLongitudGradoMin(float longitud, int *gradoLon, float *minLon, QString *dirLon)
{
float minutos = 0;
float grados = 0;
float entero = 0;
float dec = 0;
if (longitud<0){*dirLon="W"; longitud = longitud * -1;}
else {*dirLon="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);
*gradoLon = grados;
*minLon = minutos;
}
else
{
*gradoLon = -1;
*minLon = -1;
*dirLon="N/A";
}
}
void WaypointGlobalView::updateCoordValues(float lat, float lon)
{
}
void WaypointGlobalView::updateLatitudeWP(int value)
{
Q_UNUSED(value);
int gradoLat;
float minLat;
float Latitud;
QString dirLat;
gradoLat = ui->m_latitudGrados_spinBox->value();
minLat = ui->m_latitudMinutos_spinBox->value();
if(ui->m_dirLatitudeN_radioButton->isChecked())
{
dirLat = "N";
}
else
{
dirLat = "S";
}
//dirLat = ui->m_dirLatitud_label->text();
Latitud = gradoLat + (minLat/60);
if(dirLat == "S"){Latitud = Latitud * -1;}
wp->setY(Latitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::updateLatitudeMinuteWP(double value)
{
Q_UNUSED(value);
int gradoLat;
float minLat;
float Latitud;
QString dirLat;
gradoLat = ui->m_latitudGrados_spinBox->value();
minLat = ui->m_latitudMinutos_spinBox->value();
//dirLat = ui->m_dirLatitud_label->text();
if(ui->m_dirLatitudeN_radioButton->isChecked())
{
dirLat = "N";
}
else
{
dirLat = "S";
}
Latitud = gradoLat + (minLat/60);
if(dirLat == "S"){Latitud = Latitud * -1;}
wp->setY(Latitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::updateLongitudeWP(int value)
{
Q_UNUSED(value);
int gradoLon;
float minLon;
float Longitud;
QString dirLon;
gradoLon = ui->m_longitudGrados_spinBox->value();
minLon = ui->m_longitudMinutos_spinBox->value();
// dirLon = ui->m_dirLongitud_label->text();
if(ui->m_dirLongitudeW_radioButton->isChecked())
{
dirLon = "W";
}
else
{
dirLon = "E";
}
Longitud = gradoLon + (minLon/60);
if(dirLon == "W"){Longitud = Longitud * -1;}
wp->setX(Longitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::updateLongitudeMinuteWP(double value)
{
Q_UNUSED(value);
int gradoLon;
float minLon;
float Longitud;
QString dirLon;
gradoLon = ui->m_longitudGrados_spinBox->value();
minLon = ui->m_longitudMinutos_spinBox->value();
// dirLon = ui->m_dirLongitud_label->text();
if(ui->m_dirLongitudeW_radioButton->isChecked())
{
dirLon = "W";
}
else
{
dirLon = "E";
}
Longitud = gradoLon + (minLon/60);
if(dirLon == "W"){Longitud = Longitud * -1;}
wp->setX(Longitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::changeDirectionLatitudeWP()
{
if(ui->m_dirLatitudeN_radioButton->isChecked())
{
if(wp->getY() < 0)
{
wp->setY(wp->getY()* -1);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
}
if(ui->m_dirLatitudeS_radioButton->isChecked())
{
if(wp->getY() > 0)
{
wp->setY(wp->getY()*-1);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
}
}
void WaypointGlobalView::changeDirectionLongitudeWP()
{
if(ui->m_dirLongitudeW_radioButton->isChecked())
{
if(wp->getX() > 0)
{
wp->setX(wp->getX()*-1);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
}
if(ui->m_dirLongitudeE_radioButton->isChecked())
{
if(wp->getX() < 0)
{
wp->setX(wp->getX()*-1);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
}
}
......@@ -22,12 +22,30 @@ public slots:
void remove();
QString getLatitudString(float lat);
QString getLongitudString(float lon);
void getLatitudeGradoMin(float lat, int *gradoLat, float *minLat, QString *dirLat);
void getLongitudGradoMin(float lon, int *gradoLon, float *minLon, QString *dirLon);
void changeOrbitalState(int state);
void updateCoordValues(float lat, float lon);
//update latitude
void updateLatitudeWP(int value);
void updateLatitudeMinuteWP(double value);
void changeDirectionLatitudeWP();
//update longitude
void updateLongitudeWP(int value);
void updateLongitudeMinuteWP(double value);
void changeDirectionLongitudeWP();
signals:
void removeWaypoint(Waypoint*);
void changePositionWP(Waypoint*);
protected:
virtual void changeEvent(QEvent *e);
......
......@@ -6,12 +6,12 @@
<rect>
<x>0</x>
<y>0</y>
<width>774</width>
<height>184</height>
<width>824</width>
<height>79</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<sizepolicy hsizetype="Maximum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
......@@ -48,21 +48,21 @@ 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::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 {
 QDockWidget {
font: bold;
border: 1px solid #32345E;
    border: 1px solid #32345E;
}
QPushButton {
......@@ -85,25 +85,25 @@ QPushButton:pressed {
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;);
                             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;);
                             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;);
                             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;);
                             stop:0 #bb8500, stop:1 #903000) url(&quot;ICONDIR/control/emergency-button.png&quot;);
}
QProgressBar {
......@@ -143,10 +143,7 @@ QProgressBar::chunk#thrustBar {
background-color: orange;
}</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum>
</property>
<layout class="QGridLayout" name="gridLayout_5">
<property name="margin">
<number>0</number>
</property>
......@@ -164,279 +161,699 @@ QProgressBar::chunk#thrustBar {
<property name="title">
<string/>
</property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="20,0,0,50,0,0,50,10,0,20,20,20">
<property name="spacing">
<layout class="QGridLayout" name="gridLayout_4">
<property name="leftMargin">
<number>2</number>
</property>
<property name="margin">
<property name="topMargin">
<number>4</number>
</property>
<property name="rightMargin">
<number>2</number>
</property>
<item>
<property name="bottomMargin">
<number>4</number>
</property>
<item row="0" column="0">
<widget class="QLabel" name="idWP_label">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>WP_id</string>
</property>
</widget>
</item>
<item>
<item row="0" column="1">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>2</width>
<height>0</height>
<width>16</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="Latitud_label">
<property name="text">
<string>Lat:</string>
<item row="0" column="2">
<widget class="QGroupBox" name="m_latitud_groupBox">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="title">
<string/>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<property name="flat">
<bool>true</bool>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<property name="margin">
<number>2</number>
</property>
<property name="spacing">
<number>2</number>
</property>
<item row="0" column="0" rowspan="3">
<widget class="QLabel" name="label_6">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>LAT:</string>
</property>
</widget>
</item>
<item row="0" column="1" rowspan="3">
<widget class="QSpinBox" name="m_latitudGrados_spinBox">
<property name="suffix">
<string>°</string>
</property>
<property name="minimum">
<number>0</number>
</property>
<property name="maximum">
<number>89</number>
</property>
</widget>
</item>
<item row="0" column="2" rowspan="3">
<widget class="QDoubleSpinBox" name="m_latitudMinutos_spinBox">
<property name="suffix">
<string>'</string>
</property>
<property name="minimum">
<double>0.000000000000000</double>
</property>
<property name="maximum">
<double>59.990000000000002</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QRadioButton" name="m_dirLatitudeS_radioButton">
<property name="text">
<string>S</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QRadioButton" name="m_dirLatitudeN_radioButton">
<property name="text">
<string>N</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QLineEdit" name="m_latitudtextEdit"/>
</item>
<item>
<spacer name="horizontalSpacer_2">
<item row="0" column="3">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>2</width>
<height>0</height>
<width>11</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="Longitud_label">
<property name="text">
<string>Lon:</string>
<item row="0" column="4">
<widget class="QGroupBox" name="m_longitud_groupBox">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="title">
<string/>
</property>
<layout class="QGridLayout" name="gridLayout">
<property name="margin">
<number>2</number>
</property>
<property name="spacing">
<number>2</number>
</property>
<item row="0" column="0" rowspan="3">
<widget class="QLabel" name="label_7">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>LON:</string>
</property>
</widget>
</item>
<item row="0" column="1" rowspan="3">
<widget class="QSpinBox" name="m_longitudGrados_spinBox">
<property name="suffix">
<string>°</string>
</property>
<property name="minimum">
<number>-179</number>
</property>
<property name="maximum">
<number>179</number>
</property>
</widget>
</item>
<item row="0" column="2" rowspan="3">
<widget class="QDoubleSpinBox" name="m_longitudMinutos_spinBox">
<property name="suffix">
<string>'</string>
</property>
<property name="minimum">
<double>0.000000000000000</double>
</property>
<property name="maximum">
<double>59.990000000000002</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QRadioButton" name="m_dirLongitudeE_radioButton">
<property name="text">
<string>E</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QRadioButton" name="m_dirLongitudeW_radioButton">
<property name="text">
<string>W</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QLineEdit" name="m_longitudtextEdit"/>
</item>
<item>
<spacer name="horizontalSpacer_3">
<item row="0" column="5">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>2</width>
<height>0</height>
<width>16</width>
<height>20</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>
<item row="0" column="6">
<widget class="QGroupBox" name="m_vueloOrbita_groupBox">
<property name="title">
<string/>
</property>
<layout class="QGridLayout" name="gridLayout_3">
<property name="margin">
<number>2</number>
</property>
<property name="spacing">
<number>2</number>
</property>
<item row="0" column="0">
<widget class="QLabel" name="height_label">
<property name="text">
<string>Alt</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QDoubleSpinBox" name="m_heigthSpinBox"/>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Orbital</string>
</property>
</widget>
</item>
<item row="0" column="3">
<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="Light">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Midlight">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Dark">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>127</red>
<green>127</green>
<blue>127</blue>
</color>
</brush>
</colorrole>
<colorrole role="Mid">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>170</red>
<green>170</green>
<blue>170</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="BrightText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</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>
<colorrole role="Shadow">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="AlternateBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>220</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</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="Light">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Midlight">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Dark">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>127</red>
<green>127</green>
<blue>127</blue>
</color>
</brush>
</colorrole>
<colorrole role="Mid">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>170</red>
<green>170</green>
<blue>170</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="BrightText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</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>
<colorrole role="Shadow">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="AlternateBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>220</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</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="Light">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Midlight">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Dark">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>127</red>
<green>127</green>
<blue>127</blue>
</color>
</brush>
</colorrole>
<colorrole role="Mid">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>170</red>
<green>170</green>
<blue>170</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="BrightText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</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>
<colorrole role="Shadow">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="AlternateBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>220</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QDoubleSpinBox" name="m_orbitalSpinBox">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
......
......@@ -39,6 +39,7 @@ This file is part of the PIXHAWK project
#include <QFileDialog>
#include "WaypointGlobalView.h"
#include <QMessageBox>
#include <QMouseEvent>
WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
QWidget(parent),
......@@ -90,6 +91,9 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
this->setVisible(false);
isGlobalWP = false;
isLocalWP = false;
centerMapCoordinate.setX(0.0);
centerMapCoordinate.setY(0.0);
}
WaypointList::~WaypointList()
......@@ -168,24 +172,44 @@ void WaypointList::add()
{
if (uas)
{
if(isGlobalWP)
{
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());
Waypoint *wp = new Waypoint(0, centerMapCoordinate.x(), centerMapCoordinate.y(), 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);
Waypoint *wp = new Waypoint(0, centerMapCoordinate.x(), centerMapCoordinate.y(), -0.8, 0.0, true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp);
}
isLocalWP = true;
emit createWaypointAtMap(centerMapCoordinate);
}
else
{
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
{
isLocalWP = true;
Waypoint *wp = new Waypoint(0, 1.1, 1.1, -0.8, 0.0, true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp);
}
}
}
}
......@@ -301,9 +325,11 @@ void WaypointList::waypointListChanged()
{
WaypointGlobalView* wpview = new WaypointGlobalView(wp, this);
wpGlobalViews.insert(wp, wpview);
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(changePositionWP(Waypoint*)), this, SLOT(changeWPPositionBySpinBox(Waypoint*)));
// 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(changePositionWP(Waypoint*)), this, SLOT(waypointGlobalPositionChanged(Waypoint*)));
// connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
// connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
}
......@@ -498,13 +524,16 @@ void WaypointList::addWaypointMouse(QPointF coordinate)
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)
/** @brief Notifies the user that a global waypoint will be created */
void WaypointList::setIsWPGlobal(bool value, QPointF centerCoordinate)
{
centerMapCoordinate = centerCoordinate;
if(isLocalWP)
......@@ -512,18 +541,21 @@ void WaypointList::setIsWPGlobal(bool value)
if(wpViews.size()!= 0)
{
int ret = QMessageBox::warning(this, tr("My Application"),
tr("There are Waypoints local created.\n"
int ret = QMessageBox::warning(this, tr("QGroundControl"),
tr("There are Local Waypoints created.\n"
"Do you want to clear them?"),
QMessageBox::Ok | QMessageBox::Cancel);
if(ret)
{
clearLocalWPWidget();
isGlobalWP = value;
isLocalWP = !(value);
}
}
isLocalWP = !value;
isGlobalWP = value;
}
......@@ -556,6 +588,19 @@ void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP)
}
///** @brief The MapWidget informs that a waypoint global was changed on the map */
//void WaypointList::waypointGlobalPositionChanged(Waypoint* wp)
//{
// QPointF coordinate;
// coordinate.setX(wp->getX());
// coordinate.setY(wp->getY());
// emit ChangeWaypointGlobalPosition(wp->getId(), coordinate);
//}
void WaypointList::clearLocalWPWidget()
{
if (uas)
......@@ -571,3 +616,9 @@ void WaypointList::clearLocalWPWidget()
}
}
}
void WaypointList::changeWPPositionBySpinBox(Waypoint *wp)
{
emit changePositionWPGlobalBySpinBox(wp->getId(), wp->getY(), wp->getX());
}
......@@ -77,7 +77,7 @@ public slots:
/** @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);
void setIsWPGlobal(bool value, QPointF centerCoordinate);
//Update events
......@@ -95,6 +95,8 @@ public slots:
void clearLocalWPWidget();
void changeWPPositionBySpinBox(Waypoint* wp);
// Waypoint operations
void moveUp(Waypoint* wp);
void moveDown(Waypoint* wp);
......@@ -105,6 +107,9 @@ public slots:
signals:
void clearPathclicked();
void createWaypointAtMap(const QPointF coordinate);
// void ChangeWaypointGlobalPosition(int index, QPointF coord);
void changePositionWPGlobalBySpinBox(int indexWP, float lat, float lon);
......@@ -122,6 +127,7 @@ protected:
double mavYaw;
bool isGlobalWP;
bool isLocalWP;
QPointF centerMapCoordinate;
private:
Ui::WaypointList *m_ui;
......
......@@ -254,7 +254,7 @@ QProgressBar::chunk#thrustBar {
<item>
<widget class="QDoubleSpinBox" name="zSpinBox">
<property name="toolTip">
<string>Position Z coordinate</string>
<string>Position Z coordinate (negative)</string>
</property>
<property name="suffix">
<string> m</string>
......@@ -313,9 +313,12 @@ QProgressBar::chunk#thrustBar {
</item>
<item>
<widget class="QSpinBox" name="holdTimeSpinBox">
<property name="statusTip">
<property name="toolTip">
<string>Time in milliseconds that the MAV has to stay inside the orbit before advancing</string>
</property>
<property name="statusTip">
<string/>
</property>
<property name="suffix">
<string> ms</string>
</property>
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of the class Imagery.
*
* @author Lionel Heng <hengli@student.ethz.ch>
*
*/
#include "Imagery.h"
#include <cmath>
#include <sstream>
const double WGS84_A = 6378137.0;
const double WGS84_ECCSQ = 0.00669437999013;
const int32_t MAX_ZOOM_LEVEL = 20;
Imagery::Imagery()
: textureCache(new TextureCache(1000))
{
}
void
Imagery::setImageryType(ImageryType type)
{
currentImageryType = type;
}
void
Imagery::setOffset(double xOffset, double yOffset)
{
this->xOffset = xOffset;
this->yOffset = yOffset;
}
void
Imagery::prefetch2D(double windowWidth, double windowHeight,
double zoom, double xOrigin, double yOrigin,
double viewXOffset, double viewYOffset,
const QString& utmZone)
{
double tileResolution;
if (currentImageryType == SATELLITE)
{
tileResolution = 1.0;
while (tileResolution * 3.0 / 2.0 < 1.0 / zoom)
{
tileResolution *= 2.0;
}
if (tileResolution > 512.0)
{
tileResolution = 512.0;
}
}
int32_t minTileX, minTileY, maxTileX, maxTileY;
int32_t zoomLevel;
tileBounds(tileResolution,
xOrigin + viewXOffset - windowWidth / 2.0 / zoom,
yOrigin + viewYOffset - windowHeight / 2.0 / zoom,
xOrigin + viewXOffset + windowWidth / 2.0 / zoom,
yOrigin + viewYOffset + windowHeight / 2.0 / zoom, utmZone,
minTileX, minTileY, maxTileX, maxTileY, zoomLevel);
for (int32_t r = minTileY; r <= maxTileY; ++r)
{
for (int32_t c = minTileX; c <= maxTileX; ++c)
{
QString url = getTileURL(c, r, zoomLevel);
TexturePtr t = textureCache->get(url);
}
}
}
void
Imagery::draw2D(double windowWidth, double windowHeight,
double zoom, double xOrigin, double yOrigin,
double viewXOffset, double viewYOffset,
const QString& utmZone)
{
double tileResolution;
if (currentImageryType == SATELLITE)
{
tileResolution = 1.0;
while (tileResolution * 3.0 / 2.0 < 1.0 / zoom)
{
tileResolution *= 2.0;
}
if (tileResolution > 512.0)
{
tileResolution = 512.0;
}
}
int32_t minTileX, minTileY, maxTileX, maxTileY;
int32_t zoomLevel;
tileBounds(tileResolution,
xOrigin + viewXOffset - windowWidth / 2.0 / zoom * 1.5,
yOrigin + viewYOffset - windowHeight / 2.0 / zoom * 1.5,
xOrigin + viewXOffset + windowWidth / 2.0 / zoom * 1.5,
yOrigin + viewYOffset + windowHeight / 2.0 / zoom * 1.5, utmZone,
minTileX, minTileY, maxTileX, maxTileY, zoomLevel);
for (int32_t r = minTileY; r <= maxTileY; ++r)
{
for (int32_t c = minTileX; c <= maxTileX; ++c)
{
QString tileURL = getTileURL(c, r, zoomLevel);
double x1, y1, x2, y2, x3, y3, x4, y4;
imageBounds(c, r, tileResolution, x1, y1, x2, y2, x3, y3, x4, y4);
TexturePtr t = textureCache->get(tileURL);
if (!t.isNull())
{
t->draw(x1 - xOrigin, y1 - yOrigin,
x2 - xOrigin, y2 - yOrigin,
x3 - xOrigin, y3 - yOrigin,
x4 - xOrigin, y4 - yOrigin, true);
}
}
}
}
void
Imagery::prefetch3D(double radius, double tileResolution,
double xOrigin, double yOrigin,
double viewXOffset, double viewYOffset,
const QString& utmZone)
{
int32_t minTileX, minTileY, maxTileX, maxTileY;
int32_t zoomLevel;
tileBounds(tileResolution,
xOrigin + viewXOffset - radius,
yOrigin + viewYOffset - radius,
xOrigin + viewXOffset + radius,
yOrigin + viewYOffset + radius, utmZone,
minTileX, minTileY, maxTileX, maxTileY, zoomLevel);
for (int32_t r = minTileY; r <= maxTileY; ++r)
{
for (int32_t c = minTileX; c <= maxTileX; ++c)
{
QString url = getTileURL(c, r, zoomLevel);
TexturePtr t = textureCache->get(url);
}
}
}
void
Imagery::draw3D(double radius, double tileResolution,
double xOrigin, double yOrigin,
double viewXOffset, double viewYOffset,
const QString& utmZone)
{
int32_t minTileX, minTileY, maxTileX, maxTileY;
int32_t zoomLevel;
tileBounds(tileResolution,
xOrigin + viewXOffset - radius,
yOrigin + viewYOffset - radius,
xOrigin + viewXOffset + radius,
yOrigin + viewYOffset + radius, utmZone,
minTileX, minTileY, maxTileX, maxTileY, zoomLevel);
for (int32_t r = minTileY; r <= maxTileY; ++r)
{
for (int32_t c = minTileX; c <= maxTileX; ++c)
{
QString tileURL = getTileURL(c, r, zoomLevel);
double x1, y1, x2, y2, x3, y3, x4, y4;
imageBounds(c, r, tileResolution, x1, y1, x2, y2, x3, y3, x4, y4);
TexturePtr t = textureCache->get(tileURL);
if (!t.isNull())
{
t->draw(x1 - xOrigin, y1 - yOrigin,
x2 - xOrigin, y2 - yOrigin,
x3 - xOrigin, y3 - yOrigin,
x4 - xOrigin, y4 - yOrigin, true);
}
}
}
}
bool
Imagery::update(void)
{
textureCache->sync();
return true;
}
void
Imagery::imageBounds(int32_t tileX, int32_t tileY, double tileResolution,
double& x1, double& y1, double& x2, double& y2,
double& x3, double& y3, double& x4, double& y4) const
{
int32_t zoomLevel = MAX_ZOOM_LEVEL - static_cast<int32_t>(rint(log2(tileResolution)));
int32_t numTiles = static_cast<int32_t>(exp2(static_cast<double>(zoomLevel)));
double lon1 = tileXToLongitude(tileX, numTiles);
double lon2 = tileXToLongitude(tileX + 1, numTiles);
double lat1 = tileYToLatitude(tileY, numTiles);
double lat2 = tileYToLatitude(tileY + 1, numTiles);
QString utmZone;
LLtoUTM(lat1, lon1, x1, y1, utmZone);
LLtoUTM(lat1, lon2, x2, y2, utmZone);
LLtoUTM(lat2, lon2, x3, y3, utmZone);
LLtoUTM(lat2, lon1, x4, y4, utmZone);
}
void
Imagery::tileBounds(double tileResolution,
double minUtmX, double minUtmY,
double maxUtmX, double maxUtmY, const QString& utmZone,
int32_t& minTileX, int32_t& minTileY,
int32_t& maxTileX, int32_t& maxTileY,
int32_t& zoomLevel) const
{
double centerUtmX = (maxUtmX - minUtmX) / 2.0 + minUtmX;
double centerUtmY = (maxUtmY - minUtmY) / 2.0 + minUtmY;
int32_t centerTileX, centerTileY;
UTMtoTile(minUtmX, minUtmY, utmZone, tileResolution,
minTileX, maxTileY, zoomLevel);
UTMtoTile(centerUtmX, centerUtmY, utmZone, tileResolution,
centerTileX, centerTileY, zoomLevel);
UTMtoTile(maxUtmX, maxUtmY, utmZone, tileResolution,
maxTileX, minTileY, zoomLevel);
if (maxTileX - minTileX + 1 > 14)
{
minTileX = centerTileX - 7;
maxTileX = centerTileX + 6;
}
if (maxTileY - minTileY + 1 > 14)
{
minTileY = centerTileY - 7;
maxTileY = centerTileY + 6;
}
}
double
Imagery::tileXToLongitude(int32_t tileX, int32_t numTiles) const
{
return 360.0 * (static_cast<double>(tileX)
/ static_cast<double>(numTiles)) - 180.0;
}
double
Imagery::tileYToLatitude(int32_t tileY, int32_t numTiles) const
{
double unnormalizedRad =
(static_cast<double>(tileY) / static_cast<double>(numTiles))
* 2.0 * M_PI - M_PI;
double rad = 2.0 * atan(exp(unnormalizedRad)) - M_PI / 2.0;
return -rad * 180.0 / M_PI;
}
int32_t
Imagery::longitudeToTileX(double longitude, int32_t numTiles) const
{
return static_cast<int32_t>((longitude / 180.0 + 1.0) / 2.0 * numTiles);
}
int32_t
Imagery::latitudeToTileY(double latitude, int32_t numTiles) const
{
double rad = latitude * M_PI / 180.0;
double normalizedRad = -log(tan(rad) + 1.0 / cos(rad));
return static_cast<int32_t>((normalizedRad + M_PI)
/ (2.0 * M_PI) * numTiles);
}
void
Imagery::UTMtoTile(double northing, double easting, const QString& utmZone,
double tileResolution, int32_t& tileX, int32_t& tileY,
int32_t& zoomLevel) const
{
double latitude, longitude;
UTMtoLL(northing, easting, utmZone, latitude, longitude);
zoomLevel = MAX_ZOOM_LEVEL - static_cast<int32_t>(rint(log2(tileResolution)));
int32_t numTiles = static_cast<int32_t>(exp2(static_cast<double>(zoomLevel)));
tileX = longitudeToTileX(longitude, numTiles);
tileY = latitudeToTileY(latitude, numTiles);
}
QChar
Imagery::UTMLetterDesignator(double latitude) const
{
// This routine determines the correct UTM letter designator for the given latitude
// returns 'Z' if latitude is outside the UTM limits of 84N to 80S
// Written by Chuck Gantz- chuck.gantz@globalstar.com
char letterDesignator;
if ((84.0 >= latitude) && (latitude >= 72.0)) letterDesignator = 'X';
else if ((72.0 > latitude) && (latitude >= 64.0)) letterDesignator = 'W';
else if ((64.0 > latitude) && (latitude >= 56.0)) letterDesignator = 'V';
else if ((56.0 > latitude) && (latitude >= 48.0)) letterDesignator = 'U';
else if ((48.0 > latitude) && (latitude >= 40.0)) letterDesignator = 'T';
else if ((40.0 > latitude) && (latitude >= 32.0)) letterDesignator = 'S';
else if ((32.0 > latitude) && (latitude >= 24.0)) letterDesignator = 'R';
else if ((24.0 > latitude) && (latitude >= 16.0)) letterDesignator = 'Q';
else if ((16.0 > latitude) && (latitude >= 8.0)) letterDesignator = 'P';
else if (( 8.0 > latitude) && (latitude >= 0.0)) letterDesignator = 'N';
else if (( 0.0 > latitude) && (latitude >= -8.0)) letterDesignator = 'M';
else if ((-8.0 > latitude) && (latitude >= -16.0)) letterDesignator = 'L';
else if ((-16.0 > latitude) && (latitude >= -24.0)) letterDesignator = 'K';
else if ((-24.0 > latitude) && (latitude >= -32.0)) letterDesignator = 'J';
else if ((-32.0 > latitude) && (latitude >= -40.0)) letterDesignator = 'H';
else if ((-40.0 > latitude) && (latitude >= -48.0)) letterDesignator = 'G';
else if ((-48.0 > latitude) && (latitude >= -56.0)) letterDesignator = 'F';
else if ((-56.0 > latitude) && (latitude >= -64.0)) letterDesignator = 'E';
else if ((-64.0 > latitude) && (latitude >= -72.0)) letterDesignator = 'D';
else if ((-72.0 > latitude) && (latitude >= -80.0)) letterDesignator = 'C';
else letterDesignator = 'Z'; //This is here as an error flag to show that the Latitude is outside the UTM limits
return letterDesignator;
}
void
Imagery::LLtoUTM(double latitude, double longitude,
double& utmNorthing, double& utmEasting,
QString& utmZone) const
{
// converts lat/long to UTM coords. Equations from USGS Bulletin 1532
// East Longitudes are positive, West longitudes are negative.
// North latitudes are positive, South latitudes are negative
// Lat and Long are in decimal degrees
// Written by Chuck Gantz- chuck.gantz@globalstar.com
double k0 = 0.9996;
double LongOrigin;
double eccPrimeSquared;
double N, T, C, A, M;
double LatRad = latitude * M_PI / 180.0;
double LongRad = longitude * M_PI / 180.0;
double LongOriginRad;
int32_t ZoneNumber = static_cast<int32_t>((longitude + 180.0) / 6.0) + 1;
if (latitude >= 56.0 && latitude < 64.0 &&
longitude >= 3.0 && longitude < 12.0)
{
ZoneNumber = 32;
}
// Special zones for Svalbard
if (latitude >= 72.0 && latitude < 84.0)
{
if ( longitude >= 0.0 && longitude < 9.0) ZoneNumber = 31;
else if (longitude >= 9.0 && longitude < 21.0) ZoneNumber = 33;
else if (longitude >= 21.0 && longitude < 33.0) ZoneNumber = 35;
else if (longitude >= 33.0 && longitude < 42.0) ZoneNumber = 37;
}
LongOrigin = static_cast<double>((ZoneNumber - 1) * 6 - 180 + 3); //+3 puts origin in middle of zone
LongOriginRad = LongOrigin * M_PI / 180.0;
// compute the UTM Zone from the latitude and longitude
utmZone = QString("%1%2").arg(ZoneNumber).arg(UTMLetterDesignator(latitude));
eccPrimeSquared = WGS84_ECCSQ / (1.0 - WGS84_ECCSQ);
N = WGS84_A / sqrt(1.0f - WGS84_ECCSQ * sin(LatRad) * sin(LatRad));
T = tan(LatRad) * tan(LatRad);
C = eccPrimeSquared * cos(LatRad) * cos(LatRad);
A = cos(LatRad) * (LongRad - LongOriginRad);
M = WGS84_A * ((1.0 - WGS84_ECCSQ / 4.0
- 3.0 * WGS84_ECCSQ * WGS84_ECCSQ / 64.0
- 5.0 * WGS84_ECCSQ * WGS84_ECCSQ * WGS84_ECCSQ / 256.0)
* LatRad
- (3.0 * WGS84_ECCSQ / 8.0
+ 3.0 * WGS84_ECCSQ * WGS84_ECCSQ / 32.0
+ 45.0 * WGS84_ECCSQ * WGS84_ECCSQ * WGS84_ECCSQ / 1024.0)
* sin(2.0 * LatRad)
+ (15.0 * WGS84_ECCSQ * WGS84_ECCSQ / 256.0
+ 45.0 * WGS84_ECCSQ * WGS84_ECCSQ * WGS84_ECCSQ / 1024.0)
* sin(4.0 * LatRad)
- (35.0 * WGS84_ECCSQ * WGS84_ECCSQ * WGS84_ECCSQ / 3072.0)
* sin(6.0 * LatRad));
utmEasting = k0 * N * (A + (1.0 - T + C) * A * A * A / 6.0
+ (5.0 - 18.0 * T + T * T + 72.0 * C
- 58.0 * eccPrimeSquared)
* A * A * A * A * A / 120.0)
+ 500000.0;
utmNorthing = k0 * (M + N * tan(LatRad) *
(A * A / 2.0 +
(5.0 - T + 9.0 * C + 4.0 * C * C) * A * A * A * A / 24.0
+ (61.0 - 58.0 * T + T * T + 600.0 * C
- 330.0 * eccPrimeSquared)
* A * A * A * A * A * A / 720.0));
if (latitude < 0.0)
{
utmNorthing += 10000000.0; //10000000 meter offset for southern hemisphere
}
}
void
Imagery::UTMtoLL(double utmNorthing, double utmEasting, const QString& utmZone,
double& latitude, double& longitude) const
{
// converts UTM coords to lat/long. Equations from USGS Bulletin 1532
// East Longitudes are positive, West longitudes are negative.
// North latitudes are positive, South latitudes are negative
// Lat and Long are in decimal degrees.
// Written by Chuck Gantz- chuck.gantz@globalstar.com
double k0 = 0.9996;
double eccPrimeSquared;
double e1 = (1.0 - sqrt(1.0 - WGS84_ECCSQ)) / (1.0 + sqrt(1.0 - WGS84_ECCSQ));
double N1, T1, C1, R1, D, M;
double LongOrigin;
double mu, phi1, phi1Rad;
double x, y;
int32_t ZoneNumber;
char ZoneLetter;
bool NorthernHemisphere;
x = utmEasting - 500000.0; //remove 500,000 meter offset for longitude
y = utmNorthing;
std::istringstream iss(utmZone.toStdString());
iss >> ZoneNumber >> ZoneLetter;
if ((ZoneLetter - 'N') >= 0)
{
NorthernHemisphere = true;//point is in northern hemisphere
}
else
{
NorthernHemisphere = false;//point is in southern hemisphere
y -= 10000000.0;//remove 10,000,000 meter offset used for southern hemisphere
}
LongOrigin = (ZoneNumber - 1.0) * 6.0 - 180.0 + 3.0; //+3 puts origin in middle of zone
eccPrimeSquared = WGS84_ECCSQ / (1.0 - WGS84_ECCSQ);
M = y / k0;
mu = M / (WGS84_A * (1.0 - WGS84_ECCSQ / 4.0
- 3.0 * WGS84_ECCSQ * WGS84_ECCSQ / 64.0
- 5.0 * WGS84_ECCSQ * WGS84_ECCSQ * WGS84_ECCSQ / 256.0));
phi1Rad = mu + (3.0 * e1 / 2.0 - 27.0 * e1 * e1 * e1 / 32.0) * sin(2.0 * mu)
+ (21.0 * e1 * e1 / 16.0 - 55.0 * e1 * e1 * e1 * e1 / 32.0)
* sin(4.0 * mu)
+ (151.0 * e1 * e1 * e1 / 96.0) * sin(6.0 * mu);
phi1 = phi1Rad / M_PI * 180.0;
N1 = WGS84_A / sqrt(1.0 - WGS84_ECCSQ * sin(phi1Rad) * sin(phi1Rad));
T1 = tan(phi1Rad) * tan(phi1Rad);
C1 = eccPrimeSquared * cos(phi1Rad) * cos(phi1Rad);
R1 = WGS84_A * (1.0 - WGS84_ECCSQ) /
pow(1.0 - WGS84_ECCSQ * sin(phi1Rad) * sin(phi1Rad), 1.5);
D = x / (N1 * k0);
latitude = phi1Rad - (N1 * tan(phi1Rad) / R1)
* (D * D / 2.0 - (5.0 + 3.0 * T1 + 10.0 * C1 - 4.0 * C1 * C1
- 9.0 * eccPrimeSquared) * D * D * D * D / 24.0
+ (61.0 + 90.0 * T1 + 298.0 * C1 + 45.0 * T1 * T1
- 252.0 * eccPrimeSquared - 3.0 * C1 * C1)
* D * D * D * D * D * D / 720.0);
latitude *= 180.0 / M_PI;
longitude = (D - (1.0 + 2.0 * T1 + C1) * D * D * D / 6.0
+ (5.0 - 2.0 * C1 + 28.0 * T1 - 3.0 * C1 * C1
+ 8.0 * eccPrimeSquared + 24.0 * T1 * T1)
* D * D * D * D * D / 120.0) / cos(phi1Rad);
longitude = LongOrigin + longitude / M_PI * 180.0;
}
QString
Imagery::getTileURL(int32_t tileX, int32_t tileY, int32_t zoomLevel) const
{
std::ostringstream oss;
switch (currentImageryType)
{
case MAP:
oss << "http://mt0.google.com/vt/lyrs=m@120&x=" << tileX
<< "&y=" << tileY << "&z=" << zoomLevel;
break;
case SATELLITE:
oss << "http://khm.google.com/vt/lbw/lyrs=y&x=" << tileX
<< "&y=" << tileY << "&z=" << zoomLevel;
break;
default:
{};
}
QString url(oss.str().c_str());
return url;
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of the class Imagery.
*
* @author Lionel Heng <hengli@student.ethz.ch>
*
*/
#ifndef IMAGERY_H
#define IMAGERY_H
#include <inttypes.h>
#include "TextureCache.h"
class Imagery
{
public:
Imagery();
enum ImageryType
{
MAP = 0,
SATELLITE = 1
};
void setImageryType(ImageryType type);
void setOffset(double xOffset, double yOffset);
void prefetch2D(double windowWidth, double windowHeight,
double zoom, double xOrigin, double yOrigin,
double viewXOffset, double viewYOffset,
const QString& utmZone);
void draw2D(double windowWidth, double windowHeight,
double zoom, double xOrigin, double yOrigin,
double viewXOffset, double viewYOffset,
const QString& utmZone);
void prefetch3D(double radius, double tileResolution,
double xOrigin, double yOrigin,
double viewXOffset, double viewYOffset,
const QString& utmZone);
void draw3D(double radius, double tileResolution,
double xOrigin, double yOrigin,
double viewXOffset, double viewYOffset,
const QString& utmZone);
bool update(void);
private:
void imageBounds(int32_t tileX, int32_t tileY, double tileResolution,
double& x1, double& y1, double& x2, double& y2,
double& x3, double& y3, double& x4, double& y4) const;
void tileBounds(double tileResolution,
double minUtmX, double minUtmY,
double maxUtmX, double maxUtmY, const QString& utmZone,
int32_t& minTileX, int32_t& minTileY,
int32_t& maxTileX, int32_t& maxTileY,
int32_t& zoomLevel) const;
double tileXToLongitude(int32_t tileX, int32_t numTiles) const;
double tileYToLatitude(int32_t tileY, int32_t numTiles) const;
int32_t longitudeToTileX(double longitude, int32_t numTiles) const;
int32_t latitudeToTileY(double latitude, int32_t numTiles) const;
void UTMtoTile(double northing, double easting, const QString& utmZone,
double tileResolution, int32_t& tileX, int32_t& tileY,
int32_t& zoomLevel) const;
QChar UTMLetterDesignator(double latitude) const;
void LLtoUTM(double latitude, double longitude,
double& utmNorthing, double& utmEasting,
QString& utmZone) const;
void UTMtoLL(double utmNorthing, double utmEasting, const QString& utmZone,
double& latitude, double& longitude) const;
QString getTileURL(int32_t tileX, int32_t tileY, int32_t zoomLevel) const;
ImageryType currentImageryType;
QScopedPointer<TextureCache> textureCache;
double xOffset, yOffset;
};
#endif // IMAGERY_H
......@@ -33,11 +33,8 @@ This file is part of the QGROUNDCONTROL project
#include <cmath>
//#include <GL/gl.h>
//#include <GL/glu.h>
static const float KEY_ROTATE_AMOUNT = 5.0f;
static const float KEY_MOVE_AMOUNT = 10.0f;
static const float KEY_MOVE_AMOUNT = 5.0f;
static const float KEY_ZOOM_AMOUNT = 5.0f;
Q3DWidget::Q3DWidget(QWidget* parent)
......@@ -474,13 +471,13 @@ Q3DWidget::setDisplayMode3D()
}
float
Q3DWidget::r2d(float angle)
Q3DWidget::r2d(float angle) const
{
return angle * 57.295779513082320876f;
}
float
Q3DWidget::d2r(float angle)
Q3DWidget::d2r(float angle) const
{
return angle * 0.0174532925199432957692f;
}
......@@ -866,156 +863,173 @@ Q3DWidget::closeEvent(QCloseEvent *)
// exit application
}
void Q3DWidget::wireSphere(double radius, int slices, int stacks)
void
Q3DWidget::wireSphere(double radius, int slices, int stacks) const
{
static GLUquadricObj* quadObj;
// Make sure quad object exists
if(!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_LINE);
gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state
of quadObj, we'd need to change it to the defaults here
with gluQuadricTexture and/or gluQuadricOrientation. */
gluSphere(quadObj, radius, slices, stacks);
if (!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_LINE);
gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state
of quadObj, we'd need to change it to the defaults here
with gluQuadricTexture and/or gluQuadricOrientation. */
gluSphere(quadObj, radius, slices, stacks);
}
void Q3DWidget::solidSphere(double radius, int slices, int stacks)
void
Q3DWidget::solidSphere(double radius, int slices, int stacks) const
{
static GLUquadricObj* quadObj;
// Make sure quad object exists
if(!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_FILL);
gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state
of quadObj, we'd need to change it to the defaults here
with gluQuadricTexture and/or gluQuadricOrientation. */
gluSphere(quadObj, radius, slices, stacks);
if (!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_FILL);
gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state
of quadObj, we'd need to change it to the defaults here
with gluQuadricTexture and/or gluQuadricOrientation. */
gluSphere(quadObj, radius, slices, stacks);
}
void Q3DWidget::wireCone(double base, double height, int slices, int stacks)
void
Q3DWidget::wireCone(double base, double height, int slices, int stacks) const
{
static GLUquadricObj* quadObj;
// Make sure quad object exists
if(!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_LINE);
gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state
of quadObj, we'd need to change it to the defaults here
with gluQuadricTexture and/or gluQuadricOrientation. */
gluCylinder(quadObj, base, 0.0, height, slices, stacks);
if (!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_LINE);
gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state
of quadObj, we'd need to change it to the defaults here
with gluQuadricTexture and/or gluQuadricOrientation. */
gluCylinder(quadObj, base, 0.0, height, slices, stacks);
}
void Q3DWidget::solidCone(double base, double height, int slices, int stacks)
void
Q3DWidget::solidCone(double base, double height, int slices, int stacks) const
{
static GLUquadricObj* quadObj;
// Make sure quad object exists
if(!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_FILL);
gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state
of quadObj, we'd need to change it to the defaults here
with gluQuadricTexture and/or gluQuadricOrientation. */
gluCylinder(quadObj, base, 0.0, height, slices, stacks);
}
void Q3DWidget::drawBox(float size, GLenum type)
{
static GLfloat n[6][3] =
{
{-1.0, 0.0, 0.0},
{0.0, 1.0, 0.0},
{1.0, 0.0, 0.0},
{0.0, -1.0, 0.0},
{0.0, 0.0, 1.0},
{0.0, 0.0, -1.0}
};
static GLint faces[6][4] =
{
{0, 1, 2, 3},
{3, 2, 6, 7},
{7, 6, 5, 4},
{4, 5, 1, 0},
{5, 6, 2, 1},
{7, 4, 0, 3}
};
GLfloat v[8][3];
GLint i;
v[0][0] = v[1][0] = v[2][0] = v[3][0] = -size / 2;
v[4][0] = v[5][0] = v[6][0] = v[7][0] = size / 2;
v[0][1] = v[1][1] = v[4][1] = v[5][1] = -size / 2;
v[2][1] = v[3][1] = v[6][1] = v[7][1] = size / 2;
v[0][2] = v[3][2] = v[4][2] = v[7][2] = -size / 2;
v[1][2] = v[2][2] = v[5][2] = v[6][2] = size / 2;
for (i = 5; i >= 0; i--) {
glBegin(type);
glNormal3fv(&n[i][0]);
glVertex3fv(&v[faces[i][0]][0]);
glVertex3fv(&v[faces[i][1]][0]);
glVertex3fv(&v[faces[i][2]][0]);
glVertex3fv(&v[faces[i][3]][0]);
glEnd();
}
}
void Q3DWidget::wireCube(double size)
{
drawBox(size, GL_LINE_LOOP);
}
void Q3DWidget::solidCube(double size)
{
drawBox(size, GL_QUADS);
}
void Q3DWidget::doughnut(float r, float R, int nsides, int rings)
{
int i, j;
GLfloat theta, phi, theta1;
GLfloat cosTheta, sinTheta;
GLfloat cosTheta1, sinTheta1;
GLfloat ringDelta, sideDelta;
ringDelta = 2.0 * M_PI / rings;
sideDelta = 2.0 * M_PI / nsides;
theta = 0.0;
cosTheta = 1.0;
sinTheta = 0.0;
for (i = rings - 1; i >= 0; i--) {
theta1 = theta + ringDelta;
cosTheta1 = cos(theta1);
sinTheta1 = sin(theta1);
glBegin(GL_QUAD_STRIP);
phi = 0.0;
for (j = nsides; j >= 0; j--) {
GLfloat cosPhi, sinPhi, dist;
phi += sideDelta;
cosPhi = cos(phi);
sinPhi = sin(phi);
dist = R + r * cosPhi;
glNormal3f(cosTheta1 * cosPhi, -sinTheta1 * cosPhi, sinPhi);
glVertex3f(cosTheta1 * dist, -sinTheta1 * dist, r * sinPhi);
glNormal3f(cosTheta * cosPhi, -sinTheta * cosPhi, sinPhi);
glVertex3f(cosTheta * dist, -sinTheta * dist, r * sinPhi);
if (!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_FILL);
gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state
of quadObj, we'd need to change it to the defaults here
with gluQuadricTexture and/or gluQuadricOrientation. */
gluCylinder(quadObj, base, 0.0, height, slices, stacks);
}
void
Q3DWidget::drawBox(float size, GLenum type) const
{
static GLfloat n[6][3] =
{
{-1.0, 0.0, 0.0},
{0.0, 1.0, 0.0},
{1.0, 0.0, 0.0},
{0.0, -1.0, 0.0},
{0.0, 0.0, 1.0},
{0.0, 0.0, -1.0}
};
static GLint faces[6][4] =
{
{0, 1, 2, 3},
{3, 2, 6, 7},
{7, 6, 5, 4},
{4, 5, 1, 0},
{5, 6, 2, 1},
{7, 4, 0, 3}
};
GLfloat v[8][3];
GLint i;
v[0][0] = v[1][0] = v[2][0] = v[3][0] = -size / 2;
v[4][0] = v[5][0] = v[6][0] = v[7][0] = size / 2;
v[0][1] = v[1][1] = v[4][1] = v[5][1] = -size / 2;
v[2][1] = v[3][1] = v[6][1] = v[7][1] = size / 2;
v[0][2] = v[3][2] = v[4][2] = v[7][2] = -size / 2;
v[1][2] = v[2][2] = v[5][2] = v[6][2] = size / 2;
for (i = 5; i >= 0; i--)
{
glBegin(type);
glNormal3fv(&n[i][0]);
glVertex3fv(&v[faces[i][0]][0]);
glVertex3fv(&v[faces[i][1]][0]);
glVertex3fv(&v[faces[i][2]][0]);
glVertex3fv(&v[faces[i][3]][0]);
glEnd();
}
}
void
Q3DWidget::wireCube(double size) const
{
drawBox(size, GL_LINE_LOOP);
}
void
Q3DWidget::solidCube(double size) const
{
drawBox(size, GL_QUADS);
}
void
Q3DWidget::doughnut(float r, float R, int nsides, int rings) const
{
int i, j;
GLfloat theta, phi, theta1;
GLfloat cosTheta, sinTheta;
GLfloat cosTheta1, sinTheta1;
GLfloat ringDelta, sideDelta;
ringDelta = 2.0 * M_PI / rings;
sideDelta = 2.0 * M_PI / nsides;
theta = 0.0;
cosTheta = 1.0;
sinTheta = 0.0;
for (i = rings - 1; i >= 0; i--)
{
theta1 = theta + ringDelta;
cosTheta1 = cos(theta1);
sinTheta1 = sin(theta1);
glBegin(GL_QUAD_STRIP);
phi = 0.0;
for (j = nsides; j >= 0; j--)
{
GLfloat cosPhi, sinPhi, dist;
phi += sideDelta;
cosPhi = cos(phi);
sinPhi = sin(phi);
dist = R + r * cosPhi;
glNormal3f(cosTheta1 * cosPhi, -sinTheta1 * cosPhi, sinPhi);
glVertex3f(cosTheta1 * dist, -sinTheta1 * dist, r * sinPhi);
glNormal3f(cosTheta * cosPhi, -sinTheta * cosPhi, sinPhi);
glVertex3f(cosTheta * dist, -sinTheta * dist, r * sinPhi);
}
glEnd();
theta = theta1;
cosTheta = cosTheta1;
sinTheta = sinTheta1;
}
glEnd();
theta = theta1;
cosTheta = cosTheta1;
sinTheta = sinTheta1;
}
}
void Q3DWidget::wireTorus(double innerRadius, double outerRadius,
int nsides, int rings)
void
Q3DWidget::wireTorus(double innerRadius, double outerRadius,
int nsides, int rings) const
{
glPushAttrib(GL_POLYGON_BIT);
glPolygonMode(GL_FRONT_AND_BACK, GL_LINE);
doughnut(innerRadius, outerRadius, nsides, rings);
glPopAttrib();
glPushAttrib(GL_POLYGON_BIT);
glPolygonMode(GL_FRONT_AND_BACK, GL_LINE);
doughnut(innerRadius, outerRadius, nsides, rings);
glPopAttrib();
}
void Q3DWidget::solidTorus(double innerRadius, double outerRadius,
int nsides, int rings)
void
Q3DWidget::solidTorus(double innerRadius, double outerRadius,
int nsides, int rings) const
{
doughnut(innerRadius, outerRadius, nsides, rings);
doughnut(innerRadius, outerRadius, nsides, rings);
}
......@@ -162,23 +162,24 @@ protected:
void switchTo3DMode(void);
void setDisplayMode3D(void);
float r2d(float angle);
float d2r(float angle);
void wireSphere(double radius, int slices, int stacks);
void solidSphere(double radius, int slices, int stacks);
void wireCone(double base, double height, int slices, int stacks);
void solidCone(double base, double height, int slices, int stacks);
void drawBox(float size, GLenum type);
void wireCube(double size);
void solidCube(double size);
void doughnut(float r, float R, int nsides, int rings);
void wireTorus(double innerRadius, double outerRadius, int nsides, int rings);
void solidTorus(double innerRadius, double outerRadius, int nsides, int rings);
float r2d(float angle) const;
float d2r(float angle) const;
void wireSphere(double radius, int slices, int stacks) const;
void solidSphere(double radius, int slices, int stacks) const;
void wireCone(double base, double height, int slices, int stacks) const;
void solidCone(double base, double height, int slices, int stacks) const;
void drawBox(float size, GLenum type) const;
void wireCube(double size) const;
void solidCube(double size) const;
void doughnut(float r, float R, int nsides, int rings) const;
void wireTorus(double innerRadius, double outerRadius,
int nsides, int rings) const;
void solidTorus(double innerRadius, double outerRadius,
int nsides, int rings) const;
GLUquadricObj* quadObj;
private:
// QGLWidget events
void initializeGL(void);
void paintGL(void);
......
......@@ -38,21 +38,25 @@ This file is part of the QGROUNDCONTROL project
#include "CheetahModel.h"
#include "UASManager.h"
#include "UASInterface.h"
#include "QGC.h"
QMap3DWidget::QMap3DWidget(QWidget* parent)
: Q3DWidget(parent)
, uas(NULL)
, lastRedrawTime(0.0)
, displayGrid(true)
, displayImagery(false)
, displayTrail(false)
, lockCamera(true)
, updateLastUnlockedPose(true)
, displayTarget(false)
, displayWaypoints(true)
, imagery(0)
{
setFocusPolicy(Qt::StrongFocus);
initialize(10, 10, 1000, 900, 15.0f);
setCameraParams(0.05f, 0.5f, 0.01f, 0.5f, 30.0f, 0.01f, 400.0f);
setCameraParams(0.05f, 0.5f, 0.01f, 0.5f, 30.0f, 0.01f, 1000000.0f);
setDisplayFunc(display, this);
setMouseFunc(mouse, this);
......@@ -60,8 +64,6 @@ QMap3DWidget::QMap3DWidget(QWidget* parent)
buildLayout();
//font.reset(new FTTextureFont("images/Vera.ttf"));
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
this, SLOT(setActiveUAS(UASInterface*)));
}
......@@ -82,6 +84,18 @@ QMap3DWidget::buildLayout(void)
trailCheckBox->setText("Trail");
trailCheckBox->setChecked(displayTrail);
QCheckBox* waypointsCheckBox = new QCheckBox(this);
waypointsCheckBox->setText("Waypoints");
waypointsCheckBox->setChecked(displayWaypoints);
QLabel* imageryLabel = new QLabel(this);
imageryLabel->setText("Imagery");
imageryComboBox = new QComboBox(this);
imageryComboBox->addItem("None");
imageryComboBox->addItem("Map (Google)");
imageryComboBox->addItem("Satellite (Google)");
QPushButton* recenterButton = new QPushButton(this);
recenterButton->setText("Recenter Camera");
......@@ -97,19 +111,25 @@ QMap3DWidget::buildLayout(void)
layout->setSpacing(2);
layout->addWidget(gridCheckBox, 1, 0);
layout->addWidget(trailCheckBox, 1, 1);
layout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 2);
layout->addWidget(recenterButton, 1, 3);
layout->addWidget(lockCameraCheckBox, 1, 4);
layout->addWidget(waypointsCheckBox, 1, 2);
layout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 3);
layout->addWidget(imageryLabel, 1, 4);
layout->addWidget(imageryComboBox, 1, 5);
layout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 6);
layout->addWidget(recenterButton, 1, 7);
layout->addWidget(lockCameraCheckBox, 1, 8);
layout->setRowStretch(0, 100);
layout->setRowStretch(1, 1);
//layout->setColumnStretch(0, 1);
layout->setColumnStretch(2, 50);
layout->setColumnStretch(3, 50);
layout->setColumnStretch(6, 50);
setLayout(layout);
connect(gridCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(showGrid(int)));
connect(trailCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(showTrail(int)));
connect(imageryComboBox, SIGNAL(currentIndexChanged(const QString &)),
this, SLOT(showImagery(const QString &)));
connect(recenterButton, SIGNAL(clicked()), this, SLOT(recenterCamera()));
connect(lockCameraCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(toggleLockCamera(int)));
......@@ -122,6 +142,13 @@ QMap3DWidget::display(void* clientData)
map3d->displayHandler();
}
//void QMap3DWidget::paintEvent(QPaintEvent *event)
//{
// Q_UNUSED(event);
//}
void
QMap3DWidget::displayHandler(void)
{
......@@ -143,7 +170,7 @@ QMap3DWidget::displayHandler(void)
robotYaw = uas->getYaw();
}
if (updateLastUnlockedPose)
if (updateLastUnlockedPose && uas != NULL)
{
lastUnlockedPose.x = robotX;
lastUnlockedPose.y = robotY;
......@@ -164,6 +191,7 @@ QMap3DWidget::displayHandler(void)
}
// turn on smooth lines
makeCurrent();
glEnable(GL_LINE_SMOOTH);
glHint(GL_LINE_SMOOTH_HINT, GL_NICEST);
glEnable(GL_BLEND);
......@@ -181,7 +209,7 @@ QMap3DWidget::displayHandler(void)
if (displayGrid)
{
drawGrid();
drawGrid(-camOffset.x, -camOffset.y, robotZ);
}
if (displayTrail)
......@@ -194,19 +222,40 @@ QMap3DWidget::displayHandler(void)
drawTarget(robotX, robotY, robotZ);
}
if (displayWaypoints)
{
drawWaypoints();
}
if (displayImagery)
{
drawImagery(robotX, robotY, robotZ, "32T", true);
}
glPopMatrix();
// switch to 2D
setDisplayMode2D();
drawLegend();
// display pose information
glColor4f(0.0f, 0.0f, 0.0f, 0.5f);
glColor4f(0.0f, 0.0f, 0.0f, 1.0f);
glBegin(GL_POLYGON);
glVertex2f(0.0f, 0.0f);
glVertex2f(0.0f, 45.0f);
glVertex2f(getWindowWidth(), 45.0f);
glVertex2f(0.0f, 30.0f);
glVertex2f(getWindowWidth(), 30.0f);
glVertex2f(getWindowWidth(), 0.0f);
glEnd();
glColor4f(0.1f, 0.1f, 0.1f, 1.0f);
glBegin(GL_POLYGON);
glVertex2f(0.0f, getWindowHeight());
glVertex2f(0.0f, getWindowHeight() - 25.0f);
glVertex2f(getWindowWidth(), getWindowHeight() - 25.0f);
glVertex2f(getWindowWidth(), getWindowHeight());
glEnd();
glFlush();
std::pair<float,float> mouseWorldCoords =
getPositionIn3DMode(getMouseX(), getMouseY());
......@@ -219,13 +268,127 @@ QMap3DWidget::displayHandler(void)
painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
paintText(QString("x = %1 y = %2 z = %3 r = %4 p = %5 y = %6 Cursor [%7 %8]").arg(robotX, 0, 'f', 2).arg(robotY, 0, 'f', 2).arg(robotZ, 0, 'f', 2).arg(robotRoll, 0, 'f', 2).arg(robotPitch, 0, 'f', 2).arg(robotYaw, 0, 'f', 2).arg( mouseWorldCoords.first + robotX, 0, 'f', 2).arg( mouseWorldCoords.second + robotY, 0, 'f', 2),
QColor(255, 255, 255),
12,
11,
5,
5,
&painter);
painter.end();
}
void QMap3DWidget::paintText(QString text, QColor color, float fontSize, float refX, float refY, QPainter* painter)
void QMap3DWidget::drawWaypoints(void) const
{
if (uas)
{
const QVector<Waypoint*>& list = uas->getWaypointManager().getWaypointList();
QColor color;
QPointF lastWaypoint;
for (int i = 0; i < list.size(); i++)
{
QPointF in(list.at(i)->getX(), list.at(i)->getY());
// Transform from world to body coordinates
//in = metricWorldToBody(in);
// DRAW WAYPOINT
float waypointRadius = 0.1f;// = vwidth / 20.0f * 2.0f;
// Select color based on if this is the current waypoint
if (list.at(i)->getCurrent())
{
color = QGC::colorCyan;//uas->getColor();
}
else
{
color = uas->getColor();
}
//float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
// Draw yaw
// Draw sphere
static double radius = 0.2;
glPushMatrix();
glTranslatef(in.x() - uas->getLocalX(), in.y() - uas->getLocalY(), 0.0f);
glColor3f(1.0f, 0.3f, 0.3f);
glLineWidth(1.0f);
wireSphere(radius, 10, 10);
glPopMatrix();
// DRAW CONNECTING LINE
// Draw line from last waypoint to this one
if (!lastWaypoint.isNull())
{
// OpenGL line
}
lastWaypoint = in;
}
}
}
void
QMap3DWidget::drawLegend(void)
{
// draw marker outlines
glColor3f(1.0f, 1.0f, 1.0f);
glLineWidth(3.0f);
glBegin(GL_LINES);
glVertex2f(20.0f, 60.0f);
glVertex2f(20.0f, 80.0f);
glVertex2f(20.0f, 70.0f);
glVertex2f(100.0f, 70.0f);
glVertex2f(100.0f, 60.0f);
glVertex2f(100.0f, 80.0f);
glEnd();
// draw markers
glColor3f(0.0f, 0.0f, 0.0f);
glLineWidth(1.5f);
glBegin(GL_LINES);
glVertex2f(20.0f, 60.0f);
glVertex2f(20.0f, 80.0f);
glVertex2f(20.0f, 70.0f);
glVertex2f(100.0f, 70.0f);
glVertex2f(100.0f, 60.0f);
glVertex2f(100.0f, 80.0f);
glEnd();
float f = windowHeight / 2.0f / tanf(d2r(cameraParams.cameraFov / 2.0f));
float dist = cameraPose.distance / f * 80.0f;
QPainter painter;
painter.begin(this);
painter.setRenderHint(QPainter::Antialiasing, true);
painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
QColor rgb(255, 255, 255);
if (imageryComboBox->currentText().compare("Map (Google)") == 0)
{
rgb.setRgb(0, 0, 0);
}
paintText(QString("%1 m").arg(dist, 0, 'f', 2),
rgb,
10,
25,
getWindowHeight() - 65,
&painter);
painter.end();
}
void
QMap3DWidget::paintText(QString text, QColor color, float fontSize,
float refX, float refY, QPainter* painter) const
{
QPen prevPen = painter->pen();
......@@ -281,9 +444,15 @@ QMap3DWidget::timer(void* clientData)
void
QMap3DWidget::timerHandler(void)
{
if (imagery.isNull())
{
imagery.reset(new Imagery);
}
double timeLapsed = getTime() - lastRedrawTime;
if (timeLapsed > 0.1)
{
imagery->update();
forceRedraw();
lastRedrawTime = getTime();
}
......@@ -336,8 +505,11 @@ QMap3DWidget::markTarget(void)
displayTarget = true;
if (uas) uas->setTargetPosition(targetPosition.x, targetPosition.y,
targetPosition.z, 0.0f);
if (uas)
{
uas->setTargetPosition(targetPosition.x, targetPosition.y,
targetPosition.z, 0.0f);
}
}
void
......@@ -353,6 +525,28 @@ QMap3DWidget::showGrid(int32_t state)
}
}
void
QMap3DWidget::showImagery(const QString& text)
{
if (text.compare("None") == 0)
{
displayImagery = false;
}
else
{
if (text.compare("Map (Google)") == 0)
{
imagery->setImageryType(Imagery::MAP);
}
else if (text.compare("Satellite (Google)") == 0)
{
imagery->setImageryType(Imagery::SATELLITE);
}
displayImagery = true;
}
}
void
QMap3DWidget::showTrail(int32_t state)
{
......@@ -393,13 +587,13 @@ QMap3DWidget::toggleLockCamera(int32_t state)
}
void
QMap3DWidget::drawPlatform(float roll, float pitch, float yaw)
QMap3DWidget::drawPlatform(float roll, float pitch, float yaw) const
{
glPushMatrix();
glRotatef((yaw*180.0f)/M_PI, 0.0f, 0.0f, 1.0f);
glRotatef((pitch*180.0f)/M_PI, 0.0f, 1.0f, 0.0f);
glRotatef((roll*180.0f)/M_PI, 1.0f, 0.0f, 0.0f);
glRotatef(yaw * 180.0f / M_PI, 0.0f, 0.0f, 1.0f);
glRotatef(pitch * 180.0f / M_PI, 0.0f, 1.0f, 0.0f);
glRotatef(roll * 180.0f / M_PI, 1.0f, 0.0f, 0.0f);
glLineWidth(3.0f);
......@@ -430,7 +624,7 @@ QMap3DWidget::drawPlatform(float roll, float pitch, float yaw)
}
void
QMap3DWidget::drawGrid(void)
QMap3DWidget::drawGrid(float x, float y, float z) const
{
float radius = 10.0f;
float resolution = 0.25f;
......@@ -451,16 +645,77 @@ QMap3DWidget::drawGrid(void)
}
glBegin(GL_LINES);
glVertex3f(i, -radius, 0.0f);
glVertex3f(i, radius, 0.0f);
glVertex3f(-radius, i, 0.0f);
glVertex3f(radius, i, 0.0f);
glVertex3f(x + i, y - radius, -z);
glVertex3f(x + i, y + radius, -z);
glVertex3f(x - radius, y + i, -z);
glVertex3f(x + radius, y + i, -z);
glEnd();
}
glPopMatrix();
}
void
QMap3DWidget::drawImagery(double originX, double originY, double originZ,
const QString& zone, bool prefetch) const
{
glPushMatrix();
glEnable(GL_BLEND);
glTranslatef(0, 0, -originZ);
double viewingRadius = cameraPose.distance / 4000.0 * 3000.0;
if (viewingRadius < 100.0)
{
viewingRadius = 100.0;
}
double minResolution = 0.25;
double centerResolution = cameraPose.distance / 100.0;
double maxResolution = 1048576.0;
if (imageryComboBox->currentText().compare("Map (Google)") == 0)
{
minResolution = 0.25;
}
else if (imageryComboBox->currentText().compare("Satellite (Google)") == 0)
{
minResolution = 0.5;
}
double resolution = minResolution;
while (resolution * 2.0 < centerResolution)
{
resolution *= 2.0;
}
if (resolution > maxResolution)
{
resolution = maxResolution;
}
imagery->draw3D(viewingRadius, resolution, originX, originY,
cameraPose.xOffset, cameraPose.yOffset, zone);
if (prefetch)
{
if (resolution / 2.0 >= minResolution)
{
imagery->prefetch3D(viewingRadius / 2.0, resolution / 2.0,
originX, originY,
cameraPose.xOffset, cameraPose.yOffset, zone);
}
if (resolution * 2.0 <= maxResolution)
{
imagery->prefetch3D(viewingRadius * 2.0, resolution * 2.0,
originX, originY,
cameraPose.xOffset, cameraPose.yOffset, zone);
}
}
glDisable(GL_BLEND);
glPopMatrix();
}
void
QMap3DWidget::drawTrail(float x, float y, float z)
{
......@@ -505,7 +760,7 @@ QMap3DWidget::drawTrail(float x, float y, float z)
}
void
QMap3DWidget::drawTarget(float x, float y, float z)
QMap3DWidget::drawTarget(float x, float y, float z) const
{
static double radius = 0.2;
static bool expand = true;
......@@ -524,14 +779,7 @@ QMap3DWidget::drawTarget(float x, float y, float z)
glColor3f(0.0f, 0.7f, 1.0f);
glLineWidth(1.0f);
// Make sure quad object exists
if(!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_LINE);
gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state
of quadObj, we'd need to change it to the defaults here
with gluQuadricTexture and/or gluQuadricOrientation. */
gluSphere(quadObj, radius, 10, 10);
wireSphere(radius, 10, 10);
if (expand)
{
......
......@@ -34,6 +34,7 @@ This file is part of the QGROUNDCONTROL project
#include <QLabel>
#include "Imagery.h"
#include "Q3DWidget.h"
class CheetahModel;
......@@ -54,6 +55,7 @@ public:
static void display(void* clientData);
void displayHandler(void);
// void paintEvent(QPaintEvent *event);
static void mouse(Qt::MouseButton button, MouseState state,
int32_t x, int32_t y, void* clientData);
......@@ -72,22 +74,30 @@ public slots:
private slots:
void showGrid(int state);
void showTrail(int state);
void showImagery(const QString& text);
void recenterCamera(void);
void toggleLockCamera(int state);
protected:
UASInterface* uas;
void paintText(QString text, QColor color, float fontSize, float refX, float refY, QPainter* painter);
void paintText(QString text, QColor color, float fontSize,
float refX, float refY, QPainter* painter) const;
void drawWaypoints(void) const;
private:
void drawPlatform(float roll, float pitch, float yaw);
void drawGrid(void);
void drawPlatform(float roll, float pitch, float yaw) const;
void drawGrid(float x, float y, float z) const;
void drawImagery(double originX, double originY, double originZ,
const QString& zone, bool prefetch) const;
void drawTrail(float x, float y, float z);
void drawTarget(float x, float y, float z);
void drawTarget(float x, float y, float z) const;
void drawLegend(void);
double lastRedrawTime;
bool displayGrid;
bool displayImagery;
bool displayTrail;
typedef struct
......@@ -105,9 +115,13 @@ private:
QVarLengthArray<Pose3D, 10000> trail;
bool displayTarget;
bool displayWaypoints;
Pose3D targetPosition;
QScopedPointer<CheetahModel> cheetahModel;
QScopedPointer<Imagery> imagery;
QComboBox* imageryComboBox;
};
#endif // QMAP3DWIDGET_H
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of the class Texture.
*
* @author Lionel Heng <hengli@student.ethz.ch>
*
*/
#include "Texture.h"
Texture::Texture()
{
}
const QString&
Texture::getSourceURL(void) const
{
return sourceURL;
}
void
Texture::setID(GLuint id)
{
this->id = id;
}
void
Texture::sync(const WebImagePtr& image)
{
state = static_cast<State>(image->getState());
if (image->getState() != WebImage::UNINITIALIZED &&
sourceURL != image->getSourceURL())
{
sourceURL = image->getSourceURL();
}
if (image->getState() == WebImage::READY && image->getSyncFlag())
{
image->setSyncFlag(false);
if (image->getWidth() != imageWidth ||
image->getHeight() != imageHeight)
{
imageWidth = image->getWidth();
textureWidth = 32;
while (textureWidth < imageWidth)
{
textureWidth *= 2;
}
imageHeight = image->getHeight();
textureHeight = 32;
while (textureHeight < imageHeight)
{
textureHeight *= 2;
}
maxU = static_cast<double>(imageWidth)
/ static_cast<double>(textureWidth);
maxV = static_cast<double>(imageHeight)
/ static_cast<double>(textureHeight);
glBindTexture(GL_TEXTURE_2D, id);
glTexImage2D(GL_TEXTURE_2D, 0, 3, textureWidth, textureHeight,
0, GL_RGBA, GL_UNSIGNED_BYTE, NULL);
}
glBindTexture(GL_TEXTURE_2D, id);
glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, imageWidth, imageHeight,
GL_RGBA, GL_UNSIGNED_BYTE, image->getData());
}
}
void
Texture::draw(float x1, float y1, float x2, float y2,
bool smoothInterpolation) const
{
draw(x1, y1, x2, y1, x2, y2, x1, y2, smoothInterpolation);
}
void
Texture::draw(float x1, float y1, float x2, float y2,
float x3, float y3, float x4, float y4,
bool smoothInterpolation) const
{
if (state == REQUESTED)
{
glBegin(GL_LINE_LOOP);
glColor3f(0.0f, 0.0f, 1.0f);
glVertex2f(x1, y1);
glVertex2f(x2, y2);
glVertex2f(x3, y3);
glVertex2f(x4, y4);
glEnd();
return;
}
glEnable(GL_TEXTURE_2D);
glBindTexture(GL_TEXTURE_2D, id);
float dx, dy;
if (smoothInterpolation)
{
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
dx = 1.0f / (2.0f * textureWidth);
dy = 1.0f / (2.0f * textureHeight);
}
else
{
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
dx = 0.0f;
dy = 0.0f;
}
glColor3f(1.0f, 1.0f, 1.0f);
glBegin(GL_QUADS);
glTexCoord2f(dx, maxV - dy);
glVertex2f(x1, y1);
glTexCoord2f(maxU - dx, maxV - dy);
glVertex2f(x2, y2);
glTexCoord2f(maxU - dx, dy);
glVertex2f(x3, y3);
glTexCoord2f(dx, dy);
glVertex2f(x4, y4);
glEnd();
glDisable(GL_TEXTURE_2D);
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of the class Texture.
*
* @author Lionel Heng <hengli@student.ethz.ch>
*
*/
#ifndef TEXTURE_H
#define TEXTURE_H
#if (defined __APPLE__) & (defined __MACH__)
#include <OpenGL/gl.h>
#else
#include <GL/gl.h>
#endif
#include <inttypes.h>
#include <QSharedPointer>
#include "WebImage.h"
class Texture
{
public:
Texture();
const QString& getSourceURL(void) const;
void setID(GLuint id);
void sync(const WebImagePtr& image);
void draw(float x1, float y1, float x2, float y2,
bool smoothInterpolation) const;
void draw(float x1, float y1, float x2, float y2,
float x3, float y3, float x4, float y4,
bool smoothInterpolation) const;
private:
enum State
{
UNINITIALIZED = 0,
REQUESTED = 1,
READY = 2
};
State state;
QString sourceURL;
GLuint id;
int32_t textureWidth;
int32_t textureHeight;
int32_t imageWidth;
int32_t imageHeight;
float maxU;
float maxV;
};
typedef QSharedPointer<Texture> TexturePtr;
#endif // TEXTURE_H
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of the class TextureCache.
*
* @author Lionel Heng <hengli@student.ethz.ch>
*
*/
#include "TextureCache.h"
TextureCache::TextureCache(uint32_t _cacheSize)
: cacheSize(_cacheSize)
, imageCache(new WebImageCache(0, cacheSize))
{
for (uint32_t i = 0; i < cacheSize; ++i)
{
TexturePtr t(new Texture);
GLuint id;
glGenTextures(1, &id);
t->setID(id);
glBindTexture(GL_TEXTURE_2D, id);
glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
textures.push_back(t);
}
}
TexturePtr
TextureCache::get(const QString& tileURL)
{
QPair<TexturePtr, int32_t> p1 = lookup(tileURL);
if (!p1.first.isNull())
{
return p1.first;
}
QPair<WebImagePtr, int32_t> p2 = imageCache->lookup(tileURL);
if (!p2.first.isNull())
{
textures[p2.second]->sync(p2.first);
p1 = lookup(tileURL);
return p1.first;
}
return TexturePtr();
}
void
TextureCache::sync(void)
{
if (requireSync())
{
for (int32_t i = 0; i < textures.size(); ++i)
{
textures[i]->sync(imageCache->at(i));
}
}
}
QPair<TexturePtr, int32_t>
TextureCache::lookup(const QString& tileURL)
{
for (int32_t i = 0; i < textures.size(); ++i)
{
if (textures[i]->getSourceURL() == tileURL)
{
return qMakePair(textures[i], i);
}
}
return qMakePair(TexturePtr(), -1);
}
bool
TextureCache::requireSync(void) const
{
for (uint32_t i = 0; i < cacheSize; ++i)
{
if (imageCache->at(i)->getSyncFlag())
{
return true;
}
}
return false;
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of the class TextureCache.
*
* @author Lionel Heng <hengli@student.ethz.ch>
*
*/
#ifndef TEXTURECACHE_H
#define TEXTURECACHE_H
#include <QVector>
#include "Texture.h"
#include "WebImageCache.h"
class TextureCache
{
public:
explicit TextureCache(uint32_t cacheSize);
TexturePtr get(const QString& tileURL);
void sync(void);
private:
QPair<TexturePtr, int32_t> lookup(const QString& tileURL);
bool requireSync(void) const;
uint32_t cacheSize;
QVector<TexturePtr> textures;
QScopedPointer<WebImageCache> imageCache;
};
#endif // TEXTURECACHE_H
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of the class WebImage.
*
* @author Lionel Heng <hengli@student.ethz.ch>
*
*/
#include "WebImage.h"
#include <QDebug>
#include <QGLWidget>
WebImage::WebImage()
: state(WebImage::UNINITIALIZED)
, sourceURL("")
, image(0)
, lastReference(0)
, syncFlag(false)
{
}
void
WebImage::clear(void)
{
image.reset();
sourceURL.clear();
state = WebImage::UNINITIALIZED;
lastReference = 0;
}
WebImage::State
WebImage::getState(void) const
{
return state;
}
void
WebImage::setState(State state)
{
this->state = state;
}
const QString&
WebImage::getSourceURL(void) const
{
return sourceURL;
}
void
WebImage::setSourceURL(const QString& url)
{
sourceURL = url;
}
const uint8_t*
WebImage::getData(void) const
{
return image->scanLine(0);
}
void
WebImage::setData(const QByteArray& data)
{
QImage tempImage;
if (tempImage.loadFromData(data))
{
if (image.isNull())
{
image.reset(new QImage);
}
*image = QGLWidget::convertToGLFormat(tempImage);
}
else
{
qDebug() << "# WARNING: cannot load image data for" << sourceURL;
}
}
int32_t
WebImage::getWidth(void) const
{
return image->width();
}
int32_t
WebImage::getHeight(void) const
{
return image->height();
}
int32_t
WebImage::getByteCount(void) const
{
return image->byteCount();
}
uint64_t
WebImage::getLastReference(void) const
{
return lastReference;
}
void
WebImage::setLastReference(uint64_t value)
{
lastReference = value;
}
bool
WebImage::getSyncFlag(void) const
{
return syncFlag;
}
void
WebImage::setSyncFlag(bool onoff)
{
syncFlag = onoff;
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of the class WebImage.
*
* @author Lionel Heng <hengli@student.ethz.ch>
*
*/
#ifndef WEBIMAGE_H
#define WEBIMAGE_H
#include <inttypes.h>
#include <QImage>
#include <QScopedPointer>
#include <QSharedPointer>
class WebImage
{
public:
WebImage();
void clear(void);
enum State
{
UNINITIALIZED = 0,
REQUESTED = 1,
READY = 2
};
State getState(void) const;
void setState(State state);
const QString& getSourceURL(void) const;
void setSourceURL(const QString& url);
const uint8_t* getData(void) const;
void setData(const QByteArray& data);
int32_t getWidth(void) const;
int32_t getHeight(void) const;
int32_t getByteCount(void) const;
uint64_t getLastReference(void) const;
void setLastReference(uint64_t value);
bool getSyncFlag(void) const;
void setSyncFlag(bool onoff);
private:
State state;
QString sourceURL;
QScopedPointer<QImage> image;
uint64_t lastReference;
bool syncFlag;
};
typedef QSharedPointer<WebImage> WebImagePtr;
#endif // WEBIMAGE_H
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of the class WebImageCache.
*
* @author Lionel Heng <hengli@student.ethz.ch>
*
*/
#include "WebImageCache.h"
#include <QNetworkReply>
#include <QPixmap>
WebImageCache::WebImageCache(QObject* parent, uint32_t _cacheSize)
: QObject(parent)
, cacheSize(_cacheSize)
, currentReference(0)
, networkManager(new QNetworkAccessManager)
{
for (uint32_t i = 0; i < cacheSize; ++i)
{
WebImagePtr image(new WebImage);
webImages.push_back(image);
}
connect(networkManager.data(), SIGNAL(finished(QNetworkReply*)),
this, SLOT(downloadFinished(QNetworkReply*)));
}
QPair<WebImagePtr, int32_t>
WebImageCache::lookup(const QString& url)
{
QPair<WebImagePtr, int32_t> cacheEntry;
for (int32_t i = 0; i < webImages.size(); ++i)
{
if (webImages[i]->getState() != WebImage::UNINITIALIZED &&
webImages[i]->getSourceURL() == url)
{
cacheEntry.first = webImages[i];
cacheEntry.second = i;
break;
}
}
if (cacheEntry.first.isNull())
{
for (int32_t i = 0; i < webImages.size(); ++i)
{
// get uninitialized image
if (webImages[i]->getState() == WebImage::UNINITIALIZED)
{
cacheEntry.first = webImages[i];
cacheEntry.second = i;
break;
}
// get oldest image
else if (webImages[i]->getState() == WebImage::READY &&
(cacheEntry.first.isNull() ||
webImages[i]->getLastReference() <
cacheEntry.first->getLastReference()))
{
cacheEntry.first = webImages[i];
cacheEntry.second = i;
}
}
if (cacheEntry.first.isNull())
{
return qMakePair(WebImagePtr(), -1);
}
else
{
if (cacheEntry.first->getState() == WebImage::READY)
{
cacheEntry.first->clear();
}
cacheEntry.first->setSourceURL(url);
cacheEntry.first->setLastReference(currentReference);
++currentReference;
cacheEntry.first->setState(WebImage::REQUESTED);
networkManager->get(QNetworkRequest(QUrl(url)));
return cacheEntry;
}
}
else
{
if (cacheEntry.first->getState() == WebImage::READY)
{
cacheEntry.first->setLastReference(currentReference);
++currentReference;
return cacheEntry;
}
else
{
return qMakePair(WebImagePtr(), -1);
}
}
}
WebImagePtr
WebImageCache::at(int32_t index) const
{
return webImages[index];
}
void
WebImageCache::downloadFinished(QNetworkReply* reply)
{
reply->deleteLater();
if (reply->error() != QNetworkReply::NoError)
{
return;
}
QVariant attribute = reply->attribute(QNetworkRequest::RedirectionTargetAttribute);
if (attribute.isValid())
{
return;
}
WebImagePtr image;
foreach(image, webImages)
{
if (reply->url().toString() == image->getSourceURL())
{
image->setData(reply->readAll());
image->setSyncFlag(true);
image->setState(WebImage::READY);
return;
}
}
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of the class WebImageCache.
*
* @author Lionel Heng <hengli@student.ethz.ch>
*
*/
#ifndef WEBIMAGECACHE_H
#define WEBIMAGECACHE_H
#include <QNetworkAccessManager>
#include <QObject>
#include <QPair>
#include "WebImage.h"
class WebImageCache : public QObject
{
Q_OBJECT
public:
WebImageCache(QObject* parent, uint32_t cacheSize);
QPair<WebImagePtr, int32_t> lookup(const QString& url);
WebImagePtr at(int32_t index) const;
private Q_SLOTS:
void downloadFinished(QNetworkReply* reply);
private:
uint32_t cacheSize;
QVector<WebImagePtr> webImages;
uint64_t currentReference;
QScopedPointer<QNetworkAccessManager> networkManager;
};
#endif // WEBIMAGECACHE_H
......@@ -41,7 +41,6 @@ This file is part of the PIXHAWK project
#include "UASControlWidget.h"
#include <UASManager.h>
#include <UAS.h>
//#include <mavlink.h>
#define CONTROL_MODE_LOCKED "MODE LOCKED"
#define CONTROL_MODE_MANUAL "MODE MANUAL"
......@@ -104,6 +103,24 @@ void UASControlWidget::setUAS(UASInterface* uas)
ui.controlStatusLabel->setText(tr("Connected to ") + uas->getUASName());
// Check if additional controls should be loaded
UAS* mav = dynamic_cast<UAS*>(uas);
if (mav)
{
QPushButton* startRecButton = new QPushButton(tr("Record"));
connect(startRecButton, SIGNAL(clicked()), mav, SLOT(startDataRecording()));
ui.gridLayout->addWidget(startRecButton, 10, 1);
QPushButton* pauseRecButton = new QPushButton(tr("Pause"));
connect(pauseRecButton, SIGNAL(clicked()), mav, SLOT(pauseDataRecording()));
ui.gridLayout->addWidget(pauseRecButton, 10, 2);
QPushButton* stopRecButton = new QPushButton(tr("Stop"));
connect(stopRecButton, SIGNAL(clicked()), mav, SLOT(stopDataRecording()));
ui.gridLayout->addWidget(stopRecButton, 10, 3);
}
this->uas = uas->getUASID();
setBackgroundColor(uas->getColor());
}
......
......@@ -335,7 +335,7 @@ void UASView::refresh()
//repaint();
static quint64 lastupdate = 0;
qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
//qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
lastupdate = MG::TIME::getGroundTimeNow();
// FIXME
......@@ -344,7 +344,7 @@ void UASView::refresh()
if (generalUpdateCount == 4)
{
generalUpdateCount = 0;
qDebug() << "UPDATING EVERYTHING";
//qDebug() << "UPDATING EVERYTHING";
// State
m_ui->stateLabel->setText(state);
m_ui->statusTextLabel->setText(stateDesc);
......@@ -431,7 +431,7 @@ void UASView::refresh()
// Fade heartbeat icon
// Make color darker
heartbeatColor = heartbeatColor.darker(110);
heartbeatColor = heartbeatColor.darker(150);
QString colorstyle;
colorstyle = colorstyle.sprintf("QGroupBox { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}",
......
#-------------------------------------------------
#
# QGroundControl - Micro Air Vehicle Groundstation
#
# Please see our website at <http://qgroundcontrol.org>
#
# Author:
# Lorenz Meier <mavteam@student.ethz.ch>
#
# (c) 2009-2010 PIXHAWK Team
#
# This file is part of the mav groundstation project
# QGroundControl is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
# QGroundControl is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
# You should have received a copy of the GNU General Public License
# along with QGroundControl. If not, see <http://www.gnu.org/licenses/>.
#
#-------------------------------------------------
# Uncomment ONE of these lines to enable the special message set of a project.
# Several message sets can be also enabled in parallel, as long as function names
# and message ids do not conflict.
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# PIXHAWK SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/pixhawk
DEFINES += QGC_USE_PIXHAWK_MESSAGES
# SLUGS SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/slugs
DEFINES += QGC_USE_SLUGS_MESSAGES
# UALBERTA SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/ualberta
DEFINES += QGC_USE_UALBERTA_MESSAGES
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