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 ...@@ -24,3 +24,4 @@ doc/doxy.log
deploy/mac deploy/mac
deploy/linux deploy/linux
controller_log* controller_log*
user_config.pri
...@@ -180,6 +180,11 @@ QToolButton:pressed { ...@@ -180,6 +180,11 @@ QToolButton:pressed {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0); 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 { QPushButton#forceLandButton {
font-weight: bold; font-weight: bold;
min-height: 30px; min-height: 30px;
......
...@@ -29,7 +29,7 @@ ...@@ -29,7 +29,7 @@
namespace qmapcontrol namespace qmapcontrol
{ {
GoogleSatMapAdapter::GoogleSatMapAdapter() 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"; // // name = "googlesat";
// //
......
...@@ -97,6 +97,36 @@ namespace qmapcontrol ...@@ -97,6 +97,36 @@ namespace qmapcontrol
geometries.clear(); 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 bool Layer::isVisible() const
{ {
return visible; return visible;
...@@ -323,3 +353,5 @@ namespace qmapcontrol ...@@ -323,3 +353,5 @@ namespace qmapcontrol
mapAdapter = mapadapter; mapAdapter = mapadapter;
} }
} }
...@@ -200,6 +200,12 @@ namespace qmapcontrol ...@@ -200,6 +200,12 @@ namespace qmapcontrol
*/ */
void setVisible(bool visible); void setVisible(bool visible);
//! get geometry selected by index
/*!
* @param index of geometry selected
*/
Geometry* get_Geometry(int index);
}; };
} }
#endif #endif
...@@ -309,6 +309,7 @@ namespace qmapcontrol ...@@ -309,6 +309,7 @@ namespace qmapcontrol
click.y()-screen_middle.y()+layermanager->getMapmiddle_px().y()); click.y()-screen_middle.y()+layermanager->getMapmiddle_px().y());
// image coordinate to world coordinate // image coordinate to world coordinate
return layermanager->layer()->mapadapter()->displayToCoordinate(displayToImage); return layermanager->layer()->mapadapter()->displayToCoordinate(displayToImage);
} }
void MapControl::updateRequest(QRect rect) void MapControl::updateRequest(QRect rect)
......
#------------------------------------------------- #-------------------------------------------------
# #
# MAVGround - Micro Air Vehicle Groundstation # QGroundControl - Micro Air Vehicle Groundstation
# #
# Please see our website at <http://qgroundcontrol.org> # Please see our website at <http://qgroundcontrol.org>
# #
# Original Author: # Author:
# Lorenz Meier <mavteam@student.ethz.ch> # Lorenz Meier <mavteam@student.ethz.ch>
# #
# Contributing Authors (in alphabetical order): # (c) 2009-2010 PIXHAWK Team
#
# (c) 2009 PIXHAWK Team
# #
# This file is part of the mav groundstation project # 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 # it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or # the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version. # (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 # but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details. # GNU General Public License for more details.
# You should have received a copy of the GNU General Public License # 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++ { ...@@ -108,7 +106,7 @@ linux-g++ {
LIBS += \ LIBS += \
-L/usr/lib \ -L/usr/lib \
-lm \ -lm \
-lflite_cmu_us_kal16 \ -lflite_cmu_us_kal \
-lflite_usenglish \ -lflite_usenglish \
-lflite_cmulex \ -lflite_cmulex \
-lflite \ -lflite \
...@@ -150,7 +148,7 @@ linux-g++-64 { ...@@ -150,7 +148,7 @@ linux-g++-64 {
LIBS += \ LIBS += \
-L/usr/lib \ -L/usr/lib \
-lm \ -lm \
-lflite_cmu_us_kal16 \ -lflite_cmu_us_kal \
-lflite_usenglish \ -lflite_usenglish \
-lflite_cmulex \ -lflite_cmulex \
-lflite \ -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 # Include QMapControl map library
# prefer version from external directory / # prefer version from external directory /
# from http://github.com/pixhawk/qmapcontrol/ # from http://github.com/pixhawk/qmapcontrol/
...@@ -5,6 +31,7 @@ ...@@ -5,6 +31,7 @@
# Version from GIT repository is preferred # Version from GIT repository is preferred
# include ( "../qmapcontrol/QMapControl/QMapControl.pri" ) #{ # include ( "../qmapcontrol/QMapControl/QMapControl.pri" ) #{
# Include bundled version if necessary # Include bundled version if necessary
include(lib/QMapControl/QMapControl.pri) 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") # 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 ...@@ -24,6 +51,12 @@ OBJECTS_DIR = $$BUILDDIR/obj
MOC_DIR = $$BUILDDIR/moc MOC_DIR = $$BUILDDIR/moc
UI_HEADERS_DIR = src/ui/generated 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 # Include general settings for MAVGround
# necessary as last include to override any non-acceptable settings # necessary as last include to override any non-acceptable settings
...@@ -42,8 +75,8 @@ DEPENDPATH += . \ ...@@ -42,8 +75,8 @@ DEPENDPATH += . \
plugins plugins
INCLUDEPATH += . \ INCLUDEPATH += . \
lib/QMapControl \ lib/QMapControl \
$$BASEDIR/../mavlink/contrib/slugs/include \ $$BASEDIR/../mavlink/include \
$$BASEDIR/../mavlink/include $$BASEDIR/../mavlink/include/common
# ../mavlink/include \ # ../mavlink/include \
# MAVLink/include \ # MAVLink/include \
...@@ -159,7 +192,6 @@ HEADERS += src/MG.h \ ...@@ -159,7 +192,6 @@ HEADERS += src/MG.h \
src/ui/map/Waypoint2DIcon.h \ src/ui/map/Waypoint2DIcon.h \
src/ui/map/MAV2DIcon.h \ src/ui/map/MAV2DIcon.h \
src/ui/QGCRemoteControlView.h \ src/ui/QGCRemoteControlView.h \
src/WaypointGlobal.h \
src/ui/WaypointGlobalView.h \ src/ui/WaypointGlobalView.h \
src/ui/RadioCalibration/RadioCalibrationData.h \ src/ui/RadioCalibration/RadioCalibrationData.h \
src/ui/RadioCalibration/RadioCalibrationWindow.h \ src/ui/RadioCalibration/RadioCalibrationWindow.h \
...@@ -170,7 +202,13 @@ HEADERS += src/MG.h \ ...@@ -170,7 +202,13 @@ HEADERS += src/MG.h \
src/ui/map3D/Q3DWidget.h \ src/ui/map3D/Q3DWidget.h \
src/ui/map3D/CheetahModel.h \ src/ui/map3D/CheetahModel.h \
src/ui/map3D/CheetahGL.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 \ SOURCES += src/main.cc \
src/Core.cc \ src/Core.cc \
src/uas/UASManager.cc \ src/uas/UASManager.cc \
...@@ -242,10 +280,16 @@ SOURCES += src/main.cc \ ...@@ -242,10 +280,16 @@ SOURCES += src/main.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \ src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \ src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \ src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/WaypointGlobalView.cc \
src/ui/map3D/Q3DWidget.cc \ src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/CheetahModel.cc \ src/ui/map3D/CheetahModel.cc \
src/ui/map3D/CheetahGL.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 RESOURCES = mavground.qrc
# Include RT-LAB Library # Include RT-LAB Library
......
...@@ -81,6 +81,7 @@ public slots: ...@@ -81,6 +81,7 @@ public slots:
void setOrbit(float orbit); void setOrbit(float orbit);
void setHoldTime(int holdTime); void setHoldTime(int holdTime);
//for QDoubleSpin //for QDoubleSpin
void setX(double x); void setX(double x);
void setY(double y); 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 @@ ...@@ -2,7 +2,7 @@
QGroundControl Open Source Ground Control Station 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 This file is part of the QGROUNDCONTROL project
......
...@@ -45,7 +45,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -45,7 +45,7 @@ This file is part of the QGROUNDCONTROL project
#include "ArduPilotMAV.h" #include "ArduPilotMAV.h"
#include "configuration.h" #include "configuration.h"
#include "LinkManager.h" #include "LinkManager.h"
#include <mavlink.h> #include <QGCMAVLink.h>
#include "QGC.h" #include "QGC.h"
/** /**
......
...@@ -39,8 +39,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -39,8 +39,7 @@ This file is part of the QGROUNDCONTROL project
#include <QByteArray> #include <QByteArray>
#include "ProtocolInterface.h" #include "ProtocolInterface.h"
#include "LinkInterface.h" #include "LinkInterface.h"
#include "protocol.h" #include "QGCMAVLink.h"
#include "mavlink.h"
/** /**
* @brief MAVLink micro air vehicle protocol reference implementation. * @brief MAVLink micro air vehicle protocol reference implementation.
......
...@@ -41,7 +41,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -41,7 +41,7 @@ This file is part of the QGROUNDCONTROL project
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "MAVLinkSimulationLink.h" #include "MAVLinkSimulationLink.h"
// MAVLINK includes // MAVLINK includes
#include <mavlink.h> #include <QGCMAVLink.h>
#include "QGC.h" #include "QGC.h"
/** /**
...@@ -100,9 +100,10 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile ...@@ -100,9 +100,10 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile
mavlinkLogFile = new QFile(MAVLinkProtocol::getLogfileName()); mavlinkLogFile = new QFile(MAVLinkProtocol::getLogfileName());
mavlinkLogFile->open(QIODevice::ReadOnly); mavlinkLogFile->open(QIODevice::ReadOnly);
x = 0; // position at Pixhawk lab @ ETHZ
y = 0; x = 5247273.0f;
z = 0; y = 465955.0f;
z = -0.2f;
yaw = 0; yaw = 0;
} }
...@@ -376,18 +377,20 @@ void MAVLinkSimulationLink::mainloop() ...@@ -376,18 +377,20 @@ void MAVLinkSimulationLink::mainloop()
{ {
rate10hzCounter = 1; 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; // Move X Position
y = (y < -5.0f) ? -5.0f : y; x = x*0.93f + 0.07f*(x+sin(QGC::groundTimeUsecs()) * 0.08f);
z = (z < -3.0f) ? -3.0f : z; 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 // Send back new setpoint
mavlink_message_t ret; mavlink_message_t ret;
...@@ -398,7 +401,7 @@ void MAVLinkSimulationLink::mainloop() ...@@ -398,7 +401,7 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength; streampointer += bufferlength;
// Send back new position // 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); bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream //add data into datastream
memcpy(stream+streampointer,buffer, bufferlength); memcpy(stream+streampointer,buffer, bufferlength);
......
...@@ -39,7 +39,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -39,7 +39,7 @@ This file is part of the QGROUNDCONTROL project
#include <QMutex> #include <QMutex>
#include <QMap> #include <QMap>
#include <inttypes.h> #include <inttypes.h>
#include <mavlink.h> #include "QGCMAVLink.h"
#include "LinkInterface.h" #include "LinkInterface.h"
......
...@@ -71,7 +71,13 @@ bool MAVLinkXMLParser::generate() ...@@ -71,7 +71,13 @@ bool MAVLinkXMLParser::generate()
bool success = true; bool success = true;
// Only generate if output dir is correctly set // 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 // print out the element names of all elements that are direct children
// of the outermost element. // of the outermost element.
...@@ -87,6 +93,31 @@ bool MAVLinkXMLParser::generate() ...@@ -87,6 +93,31 @@ bool MAVLinkXMLParser::generate()
QString lcmStructDefs = ""; QString lcmStructDefs = "";
QString pureFileName; 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 // Run through root children
while(!n.isNull()) while(!n.isNull())
...@@ -107,47 +138,55 @@ bool MAVLinkXMLParser::generate() ...@@ -107,47 +138,55 @@ bool MAVLinkXMLParser::generate()
// Handle all include tags // Handle all include tags
if (e.tagName() == "include") if (e.tagName() == "include")
{ {
QString fileName = e.text(); QString incFileName = e.text();
// Load file // Load file
QDomDocument includeDoc = QDomDocument(); //QDomDocument includeDoc = QDomDocument();
// Prepend file path if it is a relative path and // Prepend file path if it is a relative path and
// make it relative to opened file // make it relative to opened file
QFileInfo fInfo(fileName); QFileInfo fInfo(incFileName);
QString incFilePath;
if (fInfo.isRelative()) if (fInfo.isRelative())
{ {
QFileInfo rInfo(this->fileName); QFileInfo rInfo(this->fileName);
fileName = rInfo.absoluteDir().canonicalPath() + "/" + fileName; incFilePath = rInfo.absoluteDir().canonicalPath() + "/" + incFileName;
pureFileName = rInfo.baseName().split(".").first(); pureIncludeFileName = fInfo.baseName().split(".", QString::SkipEmptyParts).first();
} }
QFile file(fileName); QFile file(incFilePath);
if (file.open(QIODevice::ReadOnly | QIODevice::Text)) if (file.open(QIODevice::ReadOnly | QIODevice::Text))
{ {
const QString instanceText(QString::fromUtf8(file.readAll())); emit parseState(QString("<font color=\"green\">Included messages from file: %1</font>").arg(incFileName));
includeDoc.setContent(instanceText); // NEW MODE: CREATE INDIVIDUAL FOLDERS
// Create new output directory, parse included XML and generate C-code
// Get all messages MAVLinkXMLParser includeParser(incFilePath, topLevelOutputDirName, this);
QDomNode in = includeDoc.documentElement().firstChild(); connect(&includeParser, SIGNAL(parseState(QString)), this, SIGNAL(parseState(QString)));
//while (!in.isNull()) // Generate and write
//{ includeParser.generate();
QDomElement ie = in.toElement(); mainHeader += "\n#include \"../" + pureIncludeFileName + "/" + pureIncludeFileName + ".h\"\n";
if (!ie.isNull())
{
if (ie.tagName() == "messages" || ie.tagName() == "include") // OLD MODE: MERGE BOTH FILES
{ // const QString instanceText(QString::fromUtf8(file.readAll()));
QDomNode ref = n.parentNode().insertAfter(in, n); // includeDoc.setContent(instanceText);
if (ref.isNull()) // // Get all messages
{ // QDomNode in = includeDoc.documentElement().firstChild();
emit parseState(QString("<font color=\"red\">ERROR: Inclusion failed: XML syntax error in file %1. Wrong/misspelled XML?\nAbort.</font>").arg(fileName)); // QDomElement ie = in.toElement();
return false; // if (!ie.isNull())
} // {
} // if (ie.tagName() == "messages" || ie.tagName() == "include")
} // {
//in = in.nextSibling(); // QDomNode ref = n.parentNode().insertAfter(in, n);
//} // if (ref.isNull())
// {
emit parseState(QString("<font color=\"green\">Included messages from file: %1</font>").arg(fileName)); // 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 else
{ {
...@@ -406,20 +445,7 @@ bool MAVLinkXMLParser::generate() ...@@ -406,20 +445,7 @@ bool MAVLinkXMLParser::generate()
n = n.nextSibling(); n = n.nextSibling();
} // While through root children } // 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 // Create directory if it doesn't exist, report result in success
if (!dir.exists()) success = success && dir.mkpath(outputDirName + "/" + messagesDirName); if (!dir.exists()) success = success && dir.mkpath(outputDirName + "/" + messagesDirName);
for (int i = 0; i < cFiles.size(); i++) for (int i = 0; i < cFiles.size(); i++)
...@@ -428,6 +454,7 @@ bool MAVLinkXMLParser::generate() ...@@ -428,6 +454,7 @@ bool MAVLinkXMLParser::generate()
bool ok = rawFile.open(QIODevice::WriteOnly | QIODevice::Text); bool ok = rawFile.open(QIODevice::WriteOnly | QIODevice::Text);
success = success && ok; success = success && ok;
rawFile.write(cFiles.at(i).second.toLatin1()); rawFile.write(cFiles.at(i).second.toLatin1());
rawFile.close();
mainHeader += includeLine.arg(messagesDirName + "/" + cFiles.at(i).first); mainHeader += includeLine.arg(messagesDirName + "/" + cFiles.at(i).first);
} }
...@@ -441,6 +468,18 @@ bool MAVLinkXMLParser::generate() ...@@ -441,6 +468,18 @@ bool MAVLinkXMLParser::generate()
bool ok = rawHeader.open(QIODevice::WriteOnly | QIODevice::Text); bool ok = rawHeader.open(QIODevice::WriteOnly | QIODevice::Text);
success = success && ok; success = success && ok;
rawHeader.write(mainHeader.toLatin1()); 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 // Write C structs / lcm definitions
// QFile lcmStructs(outputDirName + "/mavlink.lcm"); // QFile lcmStructs(outputDirName + "/mavlink.lcm");
......
...@@ -43,8 +43,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -43,8 +43,7 @@ This file is part of the QGROUNDCONTROL project
#include "LinkInterface.h" #include "LinkInterface.h"
#include "LinkManager.h" #include "LinkManager.h"
#include "MG.h" #include "MG.h"
#include "mavlink.h" #include "QGCMAVLink.h"
#include "mavlink_types.h"
#include "configuration.h" #include "configuration.h"
#include "OpalRT.h" #include "OpalRT.h"
#include "ParameterList.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 @@ ...@@ -2,7 +2,7 @@
QGroundControl Open Source Ground Control Station 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 This file is part of the QGROUNDCONTROL project
......
/*===================================================================== /*=====================================================================
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 it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (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 but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License 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 it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (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 but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License 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 it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (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 but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License 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 it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (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 but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License 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) ...@@ -53,7 +53,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break; break;
} }
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES #ifdef MAVLINK_ENABLED_SLUGS_MESSAGES_QGC
case MAVLINK_MSG_ID_CPU_LOAD: case MAVLINK_MSG_ID_CPU_LOAD:
{ {
......
...@@ -42,7 +42,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -42,7 +42,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGC.h" #include "QGC.h"
#include "GAudioOutput.h" #include "GAudioOutput.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include <mavlink.h> #include "QGCMAVLink.h"
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id), uasId(id),
...@@ -646,6 +646,27 @@ void UAS::startRadioControlCalibration() ...@@ -646,6 +646,27 @@ void UAS::startRadioControlCalibration()
sendMessage(msg); 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() void UAS::startMagnetometerCalibration()
{ {
mavlink_message_t msg; mavlink_message_t msg;
......
...@@ -35,7 +35,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -35,7 +35,7 @@ This file is part of the QGROUNDCONTROL project
#include "UASInterface.h" #include "UASInterface.h"
#include "MG.h" #include "MG.h"
#include <MAVLinkProtocol.h> #include <MAVLinkProtocol.h>
#include <mavlink.h> #include "QGCMAVLink.h"
/** /**
* @brief A generic MAVLINK-connected MAV/UAV * @brief A generic MAVLINK-connected MAV/UAV
...@@ -247,6 +247,10 @@ public slots: ...@@ -247,6 +247,10 @@ public slots:
void startGyroscopeCalibration(); void startGyroscopeCalibration();
void startPressureCalibration(); void startPressureCalibration();
void startDataRecording();
void pauseDataRecording();
void stopDataRecording();
signals: signals:
/** @brief The main/battery voltage has changed/was updated */ /** @brief The main/battery voltage has changed/was updated */
......
...@@ -36,7 +36,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -36,7 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include <QVector> #include <QVector>
#include <QTimer> #include <QTimer>
#include "Waypoint.h" #include "Waypoint.h"
#include <mavlink.h> #include "QGCMAVLink.h"
class UAS; class UAS;
/** /**
......
...@@ -405,7 +405,7 @@ void HUD::paintCenterBackground(float roll, float pitch, float yaw) ...@@ -405,7 +405,7 @@ void HUD::paintCenterBackground(float roll, float pitch, float yaw)
// Translate in the direction of the rotation based // Translate in the direction of the rotation based
// on the pitch. On the 777, a pitch of 1 degree = 2 mm // on the pitch. On the 777, a pitch of 1 degree = 2 mm
//glTranslatef(0, ((-pitch/M_PI)*180.0f * vPitchPerDeg), 0); //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 // Ground
glColor3ub(179,102,0); glColor3ub(179,102,0);
...@@ -574,6 +574,9 @@ void HUD::paintHUD() ...@@ -574,6 +574,9 @@ void HUD::paintHUD()
if ((yawTrans < 5.0) && (yawTrans > -5.0)) yawTrans = 0; 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; //qDebug() << "yaw translation" << yawTrans << "integral" << yawInt << "difference" << yawDiff << "yaw" << yaw;
// Update scaling factor // Update scaling factor
...@@ -718,7 +721,7 @@ void HUD::paintHUD() ...@@ -718,7 +721,7 @@ void HUD::paintHUD()
// Rotate view and draw all roll-dependent indicators // Rotate view and draw all roll-dependent indicators
painter.rotate((roll/M_PI)* -180.0f); 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); //qDebug() << "ROLL" << roll << "PITCH" << pitch << "YAW DIFF" << valuesDot.value("roll", 0.0f);
......
...@@ -171,6 +171,9 @@ void MainWindow::buildWidgets() ...@@ -171,6 +171,9 @@ void MainWindow::buildWidgets()
rcViewDockWidget = new QDockWidget(tr("Radio Control"), this); rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
rcViewDockWidget->setWidget( new QGCRemoteControlView(this) ); rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
headUpDockWidget = new QDockWidget(tr("Control Indicator"), this);
headUpDockWidget->setWidget( new HUD(320, 240, this));
// Dialogue widgets // Dialogue widgets
//FIXME: free memory in destructor //FIXME: free memory in destructor
joystick = new JoystickInput(); joystick = new JoystickInput();
...@@ -203,8 +206,13 @@ void MainWindow::connectWidgets() ...@@ -203,8 +206,13 @@ void MainWindow::connectWidgets()
// add Waypoint widget in the WaypointList widget when mouse clicked // add Waypoint widget in the WaypointList widget when mouse clicked
connect(mapWidget, SIGNAL(captureMapCoordinateClick(QPointF)), waypointsDockWidget->widget(), SLOT(addWaypointMouse(QPointF))); connect(mapWidget, SIGNAL(captureMapCoordinateClick(QPointF)), waypointsDockWidget->widget(), SLOT(addWaypointMouse(QPointF)));
// it notifies that a waypoint global goes to do create // 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)) ); 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() ...@@ -213,7 +221,6 @@ void MainWindow::arrangeCenterStack()
QStackedWidget *centerStack = new QStackedWidget(this); QStackedWidget *centerStack = new QStackedWidget(this);
if (!centerStack) return; if (!centerStack) return;
if (linechartWidget) centerStack->addWidget(linechartWidget); if (linechartWidget) centerStack->addWidget(linechartWidget);
if (protocolWidget) centerStack->addWidget(protocolWidget); if (protocolWidget) centerStack->addWidget(protocolWidget);
if (mapWidget) centerStack->addWidget(mapWidget); if (mapWidget) centerStack->addWidget(mapWidget);
...@@ -362,7 +369,7 @@ void MainWindow::connectActions() ...@@ -362,7 +369,7 @@ void MainWindow::connectActions()
connect(ui.actionShow_MAVLink_view, SIGNAL(triggered()), this, SLOT(loadMAVLinkView())); connect(ui.actionShow_MAVLink_view, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
connect(ui.actionShow_data_analysis_view, SIGNAL(triggered()), this, SLOT(loadDataView())); connect(ui.actionShow_data_analysis_view, SIGNAL(triggered()), this, SLOT(loadDataView()));
connect(ui.actionStyleConfig, SIGNAL(triggered()), this, SLOT(reloadStylesheet())); 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.actionOnline_documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
connect(ui.actionCredits_Developers, SIGNAL(triggered()), this, SLOT(showCredits())); connect(ui.actionCredits_Developers, SIGNAL(triggered()), this, SLOT(showCredits()));
connect(ui.actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap())); connect(ui.actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap()));
...@@ -808,6 +815,7 @@ void MainWindow::loadOperatorView() ...@@ -808,6 +815,7 @@ void MainWindow::loadOperatorView()
centerStack->setCurrentWidget(mapWidget); centerStack->setCurrentWidget(mapWidget);
} }
} }
// UAS CONTROL // UAS CONTROL
if (controlDockWidget) if (controlDockWidget)
{ {
...@@ -865,6 +873,83 @@ void MainWindow::loadOperatorView() ...@@ -865,6 +873,83 @@ void MainWindow::loadOperatorView()
this->show(); 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() void MainWindow::load3DView()
{ {
clearView(); clearView();
......
...@@ -122,6 +122,8 @@ public slots: ...@@ -122,6 +122,8 @@ public slots:
void loadDataView(); void loadDataView();
/** @brief Load data view, allowing to plot flight data */ /** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName); void loadDataView(QString fileName);
/** @brief Load view for global operator, allowing to flight on earth */
void loadGlobalOperatorView();
/** @brief Show the online help for users */ /** @brief Show the online help for users */
void showHelp(); void showHelp();
...@@ -174,6 +176,7 @@ protected: ...@@ -174,6 +176,7 @@ protected:
QPointer<QDockWidget> headDown1DockWidget; QPointer<QDockWidget> headDown1DockWidget;
QPointer<QDockWidget> headDown2DockWidget; QPointer<QDockWidget> headDown2DockWidget;
QPointer<QDockWidget> watchdogControlDockWidget; QPointer<QDockWidget> watchdogControlDockWidget;
QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> hsiDockWidget; QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget; QPointer<QDockWidget> rcViewDockWidget;
......
...@@ -76,6 +76,7 @@ ...@@ -76,6 +76,7 @@
<addaction name="actionPilotView"/> <addaction name="actionPilotView"/>
<addaction name="actionOperatorView"/> <addaction name="actionOperatorView"/>
<addaction name="action3DView"/> <addaction name="action3DView"/>
<addaction name="actionGlobalOperatorView"/>
<addaction name="separator"/> <addaction name="separator"/>
<addaction name="actionShow_MAVLink_view"/> <addaction name="actionShow_MAVLink_view"/>
<addaction name="actionShow_data_analysis_view"/> <addaction name="actionShow_data_analysis_view"/>
...@@ -308,6 +309,15 @@ ...@@ -308,6 +309,15 @@
<string>Credits / Developers</string> <string>Credits / Developers</string>
</property> </property>
</action> </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> </widget>
<layoutdefault spacing="6" margin="11"/> <layoutdefault spacing="6" margin="11"/>
<resources> <resources>
......
...@@ -47,10 +47,13 @@ MapWidget::MapWidget(QWidget *parent) : ...@@ -47,10 +47,13 @@ MapWidget::MapWidget(QWidget *parent) :
zoomLevel(0), zoomLevel(0),
uasIcons(), uasIcons(),
uasTrails(), uasTrails(),
mav(NULL),
m_ui(new Ui::MapWidget) m_ui(new Ui::MapWidget)
{ {
m_ui->setupUi(this); m_ui->setupUi(this);
waypointIsDrag = false;
// Accept focus by clicking or keyboard // Accept focus by clicking or keyboard
this->setFocusPolicy(Qt::StrongFocus); this->setFocusPolicy(Qt::StrongFocus);
...@@ -314,8 +317,9 @@ void MapWidget::createPathButtonClicked(bool checked) ...@@ -314,8 +317,9 @@ void MapWidget::createPathButtonClicked(bool checked)
this->setCursor(Qt::PointingHandCursor); this->setCursor(Qt::PointingHandCursor);
mc->setMouseMode(qmapcontrol::MapControl::None); mc->setMouseMode(qmapcontrol::MapControl::None);
// emit signal start to create a Waypoint global // emit signal start to create a Waypoint global
emit createGlobalWP(true); emit createGlobalWP(true, mc->currentCoordinate());
// // Clear the previous WP track // // Clear the previous WP track
// // TODO: Move this to an actual clear track button and add a warning dialog // // TODO: Move this to an actual clear track button and add a warning dialog
...@@ -337,9 +341,11 @@ void MapWidget::createPathButtonClicked(bool checked) ...@@ -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 // Create waypoint name
QString str; QString str;
...@@ -373,18 +379,45 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina ...@@ -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(geom);
Q_UNUSED(point); Q_UNUSED(point);
mc->setMouseMode(qmapcontrol::MapControl::None); mc->setMouseMode(qmapcontrol::MapControl::None);
} }
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
{
Q_UNUSED(coordinate); Q_UNUSED(coordinate);
waypointIsDrag = true;
// Refresh the screen // Refresh the screen
mc->updateRequestNew(); mc->updateRequestNew();
...@@ -412,6 +445,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){ ...@@ -412,6 +445,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate) void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
{ {
waypointIsDrag = false;
mc->setMouseMode(qmapcontrol::MapControl::Panning); mc->setMouseMode(qmapcontrol::MapControl::Panning);
...@@ -603,10 +637,35 @@ void MapWidget::clearPath() ...@@ -603,10 +637,35 @@ void MapWidget::clearPath()
wpIndex.clear(); wpIndex.clear();
mc->updateRequestNew(); mc->updateRequestNew();
// si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicket
if(createPath->isChecked()) if(createPath->isChecked())
{ {
createPath->click(); 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: ...@@ -66,6 +66,7 @@ public slots:
//ROCA //ROCA
void clearPath(); void clearPath();
void changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon);
protected: protected:
void changeEvent(QEvent* e); void changeEvent(QEvent* e);
...@@ -106,6 +107,7 @@ protected: ...@@ -106,6 +107,7 @@ protected:
protected slots: protected slots:
void captureMapClick (const QMouseEvent* event, const QPointF coordinate); void captureMapClick (const QMouseEvent* event, const QPointF coordinate);
void createWaypointGraphAtMap (const QPointF coordinate);
void createPathButtonClicked(bool checked); void createPathButtonClicked(bool checked);
void captureGeometryClick(Geometry*, QPoint); void captureGeometryClick(Geometry*, QPoint);
void mapproviderSelected(QAction* action); void mapproviderSelected(QAction* action);
...@@ -114,10 +116,11 @@ protected: ...@@ -114,10 +116,11 @@ protected:
signals: signals:
//void movePoint(QPointF newCoord); //void movePoint(QPointF newCoord);
void captureMapCoordinateClick(const QPointF coordinate); //ROCA void captureMapCoordinateClick(const QPointF coordinate); //ROCA
void createGlobalWP(bool value); void createGlobalWP(bool value, QPointF centerCoordinate);
void sendGeometryEndDrag(const QPointF coordinate, const int index); void sendGeometryEndDrag(const QPointF coordinate, const int index);
...@@ -127,6 +130,7 @@ private: ...@@ -127,6 +130,7 @@ private:
QHash <QString, qmapcontrol::Point*> wpIndex; QHash <QString, qmapcontrol::Point*> wpIndex;
qmapcontrol::LineString* path; qmapcontrol::LineString* path;
QPen* pointPen; QPen* pointPen;
bool waypointIsDrag;
}; };
#endif // MAPWIDGET_H #endif // MAPWIDGET_H
...@@ -12,14 +12,30 @@ WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) : ...@@ -12,14 +12,30 @@ WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) :
ui->m_orbitalSpinBox->hide(); 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_orbitalSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setOrbit(double)));
connect(ui->m_heigthSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double))); connect(ui->m_heigthSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
//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))); connect(ui->m_orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int)));
// Read values and set user interface
updateValues();
// connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double))); // connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
...@@ -48,9 +64,46 @@ WaypointGlobalView::~WaypointGlobalView() ...@@ -48,9 +64,46 @@ WaypointGlobalView::~WaypointGlobalView()
void WaypointGlobalView::updateValues() void WaypointGlobalView::updateValues()
{ {
ui->m_latitudtextEdit->setText(getLatitudString(wp->getY()));
ui->m_longitudtextEdit->setText(getLongitudString(wp->getX())); int gradoLat, gradoLon;
ui->idWP_label->setText(QString("%1").arg(wp->getId()));\ 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) ...@@ -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: ...@@ -22,12 +22,30 @@ public slots:
void remove(); void remove();
QString getLatitudString(float lat); QString getLatitudString(float lat);
QString getLongitudString(float lon); 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 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: signals:
void removeWaypoint(Waypoint*); void removeWaypoint(Waypoint*);
void changePositionWP(Waypoint*);
protected: protected:
virtual void changeEvent(QEvent *e); virtual void changeEvent(QEvent *e);
......
This diff is collapsed.
...@@ -39,6 +39,7 @@ This file is part of the PIXHAWK project ...@@ -39,6 +39,7 @@ This file is part of the PIXHAWK project
#include <QFileDialog> #include <QFileDialog>
#include "WaypointGlobalView.h" #include "WaypointGlobalView.h"
#include <QMessageBox> #include <QMessageBox>
#include <QMouseEvent>
WaypointList::WaypointList(QWidget *parent, UASInterface* uas) : WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
QWidget(parent), QWidget(parent),
...@@ -90,6 +91,9 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) : ...@@ -90,6 +91,9 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
this->setVisible(false); this->setVisible(false);
isGlobalWP = false; isGlobalWP = false;
isLocalWP = false; isLocalWP = false;
centerMapCoordinate.setX(0.0);
centerMapCoordinate.setY(0.0);
} }
WaypointList::~WaypointList() WaypointList::~WaypointList()
...@@ -168,24 +172,44 @@ void WaypointList::add() ...@@ -168,24 +172,44 @@ void WaypointList::add()
{ {
if (uas) if (uas)
{ {
if(isGlobalWP)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList(); const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0) if (waypoints.size() > 0)
{ {
Waypoint *last = waypoints.at(waypoints.size()-1); 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); uas->getWaypointManager().localAddWaypoint(wp);
} }
else 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); 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() ...@@ -301,9 +325,11 @@ void WaypointList::waypointListChanged()
{ {
WaypointGlobalView* wpview = new WaypointGlobalView(wp, this); WaypointGlobalView* wpview = new WaypointGlobalView(wp, this);
wpGlobalViews.insert(wp, wpview); 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(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
// connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(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(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
// connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16))); // connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
} }
...@@ -498,13 +524,16 @@ void WaypointList::addWaypointMouse(QPointF coordinate) ...@@ -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); Waypoint *wp = new Waypoint(0, coordinate.x(), coordinate.y(), -0.8, 0.0, true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp); uas->getWaypointManager().localAddWaypoint(wp);
} }
} }
} }
/** @brief it notifies that a global waypoint goes to do created */ /** @brief Notifies the user that a global waypoint will be created */
void WaypointList::setIsWPGlobal(bool value) void WaypointList::setIsWPGlobal(bool value, QPointF centerCoordinate)
{ {
centerMapCoordinate = centerCoordinate;
if(isLocalWP) if(isLocalWP)
...@@ -512,18 +541,21 @@ void WaypointList::setIsWPGlobal(bool value) ...@@ -512,18 +541,21 @@ void WaypointList::setIsWPGlobal(bool value)
if(wpViews.size()!= 0) if(wpViews.size()!= 0)
{ {
int ret = QMessageBox::warning(this, tr("My Application"), int ret = QMessageBox::warning(this, tr("QGroundControl"),
tr("There are Waypoints local created.\n" tr("There are Local Waypoints created.\n"
"Do you want to clear them?"), "Do you want to clear them?"),
QMessageBox::Ok | QMessageBox::Cancel); QMessageBox::Ok | QMessageBox::Cancel);
if(ret) if(ret)
{ {
clearLocalWPWidget(); clearLocalWPWidget();
isGlobalWP = value;
isLocalWP = !(value);
} }
} }
isLocalWP = !value;
isGlobalWP = value;
} }
...@@ -556,6 +588,19 @@ void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP) ...@@ -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() void WaypointList::clearLocalWPWidget()
{ {
if (uas) if (uas)
...@@ -571,3 +616,9 @@ void WaypointList::clearLocalWPWidget() ...@@ -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: ...@@ -77,7 +77,7 @@ public slots:
/** @brief Add a waypoint by mouse click over the map */ /** @brief Add a waypoint by mouse click over the map */
void addWaypointMouse(QPointF coordinate); void addWaypointMouse(QPointF coordinate);
/** @brief it notifies that a global waypoint goes to do created */ /** @brief it notifies that a global waypoint goes to do created */
void setIsWPGlobal(bool value); void setIsWPGlobal(bool value, QPointF centerCoordinate);
//Update events //Update events
...@@ -95,6 +95,8 @@ public slots: ...@@ -95,6 +95,8 @@ public slots:
void clearLocalWPWidget(); void clearLocalWPWidget();
void changeWPPositionBySpinBox(Waypoint* wp);
// Waypoint operations // Waypoint operations
void moveUp(Waypoint* wp); void moveUp(Waypoint* wp);
void moveDown(Waypoint* wp); void moveDown(Waypoint* wp);
...@@ -105,6 +107,9 @@ public slots: ...@@ -105,6 +107,9 @@ public slots:
signals: signals:
void clearPathclicked(); 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: ...@@ -122,6 +127,7 @@ protected:
double mavYaw; double mavYaw;
bool isGlobalWP; bool isGlobalWP;
bool isLocalWP; bool isLocalWP;
QPointF centerMapCoordinate;
private: private:
Ui::WaypointList *m_ui; Ui::WaypointList *m_ui;
......
...@@ -254,7 +254,7 @@ QProgressBar::chunk#thrustBar { ...@@ -254,7 +254,7 @@ QProgressBar::chunk#thrustBar {
<item> <item>
<widget class="QDoubleSpinBox" name="zSpinBox"> <widget class="QDoubleSpinBox" name="zSpinBox">
<property name="toolTip"> <property name="toolTip">
<string>Position Z coordinate</string> <string>Position Z coordinate (negative)</string>
</property> </property>
<property name="suffix"> <property name="suffix">
<string> m</string> <string> m</string>
...@@ -313,9 +313,12 @@ QProgressBar::chunk#thrustBar { ...@@ -313,9 +313,12 @@ QProgressBar::chunk#thrustBar {
</item> </item>
<item> <item>
<widget class="QSpinBox" name="holdTimeSpinBox"> <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> <string>Time in milliseconds that the MAV has to stay inside the orbit before advancing</string>
</property> </property>
<property name="statusTip">
<string/>
</property>
<property name="suffix"> <property name="suffix">
<string> ms</string> <string> ms</string>
</property> </property>
......
This diff is collapsed.
/*=====================================================================
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 ...@@ -33,11 +33,8 @@ This file is part of the QGROUNDCONTROL project
#include <cmath> #include <cmath>
//#include <GL/gl.h>
//#include <GL/glu.h>
static const float KEY_ROTATE_AMOUNT = 5.0f; 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; static const float KEY_ZOOM_AMOUNT = 5.0f;
Q3DWidget::Q3DWidget(QWidget* parent) Q3DWidget::Q3DWidget(QWidget* parent)
...@@ -474,13 +471,13 @@ Q3DWidget::setDisplayMode3D() ...@@ -474,13 +471,13 @@ Q3DWidget::setDisplayMode3D()
} }
float float
Q3DWidget::r2d(float angle) Q3DWidget::r2d(float angle) const
{ {
return angle * 57.295779513082320876f; return angle * 57.295779513082320876f;
} }
float float
Q3DWidget::d2r(float angle) Q3DWidget::d2r(float angle) const
{ {
return angle * 0.0174532925199432957692f; return angle * 0.0174532925199432957692f;
} }
...@@ -866,10 +863,12 @@ Q3DWidget::closeEvent(QCloseEvent *) ...@@ -866,10 +863,12 @@ Q3DWidget::closeEvent(QCloseEvent *)
// exit application // 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 // Make sure quad object exists
if(!quadObj) quadObj = gluNewQuadric(); if (!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_LINE); gluQuadricDrawStyle(quadObj, GLU_LINE);
gluQuadricNormals(quadObj, GLU_SMOOTH); gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state /* If we ever changed/used the texture or orientation state
...@@ -878,10 +877,12 @@ void Q3DWidget::wireSphere(double radius, int slices, int stacks) ...@@ -878,10 +877,12 @@ void Q3DWidget::wireSphere(double radius, int slices, int stacks)
gluSphere(quadObj, radius, slices, stacks); 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 // Make sure quad object exists
if(!quadObj) quadObj = gluNewQuadric(); if (!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_FILL); gluQuadricDrawStyle(quadObj, GLU_FILL);
gluQuadricNormals(quadObj, GLU_SMOOTH); gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state /* If we ever changed/used the texture or orientation state
...@@ -890,10 +891,12 @@ void Q3DWidget::solidSphere(double radius, int slices, int stacks) ...@@ -890,10 +891,12 @@ void Q3DWidget::solidSphere(double radius, int slices, int stacks)
gluSphere(quadObj, radius, slices, stacks); 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 // Make sure quad object exists
if(!quadObj) quadObj = gluNewQuadric(); if (!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_LINE); gluQuadricDrawStyle(quadObj, GLU_LINE);
gluQuadricNormals(quadObj, GLU_SMOOTH); gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state /* If we ever changed/used the texture or orientation state
...@@ -902,10 +905,12 @@ void Q3DWidget::wireCone(double base, double height, int slices, int stacks) ...@@ -902,10 +905,12 @@ void Q3DWidget::wireCone(double base, double height, int slices, int stacks)
gluCylinder(quadObj, base, 0.0, height, slices, stacks); 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 // Make sure quad object exists
if(!quadObj) quadObj = gluNewQuadric(); if (!quadObj) quadObj = gluNewQuadric();
gluQuadricDrawStyle(quadObj, GLU_FILL); gluQuadricDrawStyle(quadObj, GLU_FILL);
gluQuadricNormals(quadObj, GLU_SMOOTH); gluQuadricNormals(quadObj, GLU_SMOOTH);
/* If we ever changed/used the texture or orientation state /* If we ever changed/used the texture or orientation state
...@@ -914,7 +919,8 @@ void Q3DWidget::solidCone(double base, double height, int slices, int stacks) ...@@ -914,7 +919,8 @@ void Q3DWidget::solidCone(double base, double height, int slices, int stacks)
gluCylinder(quadObj, base, 0.0, height, slices, stacks); gluCylinder(quadObj, base, 0.0, height, slices, stacks);
} }
void Q3DWidget::drawBox(float size, GLenum type) void
Q3DWidget::drawBox(float size, GLenum type) const
{ {
static GLfloat n[6][3] = static GLfloat n[6][3] =
{ {
...@@ -944,7 +950,8 @@ void Q3DWidget::drawBox(float size, GLenum type) ...@@ -944,7 +950,8 @@ void Q3DWidget::drawBox(float size, GLenum type)
v[0][2] = v[3][2] = v[4][2] = v[7][2] = -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; v[1][2] = v[2][2] = v[5][2] = v[6][2] = size / 2;
for (i = 5; i >= 0; i--) { for (i = 5; i >= 0; i--)
{
glBegin(type); glBegin(type);
glNormal3fv(&n[i][0]); glNormal3fv(&n[i][0]);
glVertex3fv(&v[faces[i][0]][0]); glVertex3fv(&v[faces[i][0]][0]);
...@@ -955,17 +962,20 @@ void Q3DWidget::drawBox(float size, GLenum type) ...@@ -955,17 +962,20 @@ void Q3DWidget::drawBox(float size, GLenum type)
} }
} }
void Q3DWidget::wireCube(double size) void
Q3DWidget::wireCube(double size) const
{ {
drawBox(size, GL_LINE_LOOP); drawBox(size, GL_LINE_LOOP);
} }
void Q3DWidget::solidCube(double size) void
Q3DWidget::solidCube(double size) const
{ {
drawBox(size, GL_QUADS); drawBox(size, GL_QUADS);
} }
void Q3DWidget::doughnut(float r, float R, int nsides, int rings) void
Q3DWidget::doughnut(float r, float R, int nsides, int rings) const
{ {
int i, j; int i, j;
GLfloat theta, phi, theta1; GLfloat theta, phi, theta1;
...@@ -979,13 +989,15 @@ void Q3DWidget::doughnut(float r, float R, int nsides, int rings) ...@@ -979,13 +989,15 @@ void Q3DWidget::doughnut(float r, float R, int nsides, int rings)
theta = 0.0; theta = 0.0;
cosTheta = 1.0; cosTheta = 1.0;
sinTheta = 0.0; sinTheta = 0.0;
for (i = rings - 1; i >= 0; i--) { for (i = rings - 1; i >= 0; i--)
{
theta1 = theta + ringDelta; theta1 = theta + ringDelta;
cosTheta1 = cos(theta1); cosTheta1 = cos(theta1);
sinTheta1 = sin(theta1); sinTheta1 = sin(theta1);
glBegin(GL_QUAD_STRIP); glBegin(GL_QUAD_STRIP);
phi = 0.0; phi = 0.0;
for (j = nsides; j >= 0; j--) { for (j = nsides; j >= 0; j--)
{
GLfloat cosPhi, sinPhi, dist; GLfloat cosPhi, sinPhi, dist;
phi += sideDelta; phi += sideDelta;
...@@ -1005,8 +1017,9 @@ void Q3DWidget::doughnut(float r, float R, int nsides, int rings) ...@@ -1005,8 +1017,9 @@ void Q3DWidget::doughnut(float r, float R, int nsides, int rings)
} }
} }
void Q3DWidget::wireTorus(double innerRadius, double outerRadius, void
int nsides, int rings) Q3DWidget::wireTorus(double innerRadius, double outerRadius,
int nsides, int rings) const
{ {
glPushAttrib(GL_POLYGON_BIT); glPushAttrib(GL_POLYGON_BIT);
glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); glPolygonMode(GL_FRONT_AND_BACK, GL_LINE);
...@@ -1014,8 +1027,9 @@ void Q3DWidget::wireTorus(double innerRadius, double outerRadius, ...@@ -1014,8 +1027,9 @@ void Q3DWidget::wireTorus(double innerRadius, double outerRadius,
glPopAttrib(); glPopAttrib();
} }
void Q3DWidget::solidTorus(double innerRadius, double outerRadius, void
int nsides, int rings) 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: ...@@ -162,23 +162,24 @@ protected:
void switchTo3DMode(void); void switchTo3DMode(void);
void setDisplayMode3D(void); void setDisplayMode3D(void);
float r2d(float angle); float r2d(float angle) const;
float d2r(float angle); float d2r(float angle) const;
void wireSphere(double radius, int slices, int stacks); void wireSphere(double radius, int slices, int stacks) const;
void solidSphere(double radius, int slices, int stacks); void solidSphere(double radius, int slices, int stacks) const;
void wireCone(double base, double height, int slices, int stacks); void wireCone(double base, double height, int slices, int stacks) const;
void solidCone(double base, double height, int slices, int stacks); void solidCone(double base, double height, int slices, int stacks) const;
void drawBox(float size, GLenum type); void drawBox(float size, GLenum type) const;
void wireCube(double size); void wireCube(double size) const;
void solidCube(double size); void solidCube(double size) const;
void doughnut(float r, float R, int nsides, int rings); void doughnut(float r, float R, int nsides, int rings) const;
void wireTorus(double innerRadius, double outerRadius, int nsides, int rings); void wireTorus(double innerRadius, double outerRadius,
void solidTorus(double innerRadius, double outerRadius, int nsides, int rings); int nsides, int rings) const;
void solidTorus(double innerRadius, double outerRadius,
int nsides, int rings) const;
GLUquadricObj* quadObj; GLUquadricObj* quadObj;
private:
// QGLWidget events // QGLWidget events
void initializeGL(void); void initializeGL(void);
void paintGL(void); void paintGL(void);
......
This diff is collapsed.
...@@ -34,6 +34,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -34,6 +34,7 @@ This file is part of the QGROUNDCONTROL project
#include <QLabel> #include <QLabel>
#include "Imagery.h"
#include "Q3DWidget.h" #include "Q3DWidget.h"
class CheetahModel; class CheetahModel;
...@@ -54,6 +55,7 @@ public: ...@@ -54,6 +55,7 @@ public:
static void display(void* clientData); static void display(void* clientData);
void displayHandler(void); void displayHandler(void);
// void paintEvent(QPaintEvent *event);
static void mouse(Qt::MouseButton button, MouseState state, static void mouse(Qt::MouseButton button, MouseState state,
int32_t x, int32_t y, void* clientData); int32_t x, int32_t y, void* clientData);
...@@ -72,22 +74,30 @@ public slots: ...@@ -72,22 +74,30 @@ public slots:
private slots: private slots:
void showGrid(int state); void showGrid(int state);
void showTrail(int state); void showTrail(int state);
void showImagery(const QString& text);
void recenterCamera(void); void recenterCamera(void);
void toggleLockCamera(int state); void toggleLockCamera(int state);
protected: protected:
UASInterface* uas; 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: private:
void drawPlatform(float roll, float pitch, float yaw); void drawPlatform(float roll, float pitch, float yaw) const;
void drawGrid(void); 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 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; double lastRedrawTime;
bool displayGrid; bool displayGrid;
bool displayImagery;
bool displayTrail; bool displayTrail;
typedef struct typedef struct
...@@ -105,9 +115,13 @@ private: ...@@ -105,9 +115,13 @@ private:
QVarLengthArray<Pose3D, 10000> trail; QVarLengthArray<Pose3D, 10000> trail;
bool displayTarget; bool displayTarget;
bool displayWaypoints;
Pose3D targetPosition; Pose3D targetPosition;
QScopedPointer<CheetahModel> cheetahModel; QScopedPointer<CheetahModel> cheetahModel;
QScopedPointer<Imagery> imagery;
QComboBox* imageryComboBox;
}; };
#endif // QMAP3DWIDGET_H #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 ...@@ -41,7 +41,6 @@ This file is part of the PIXHAWK project
#include "UASControlWidget.h" #include "UASControlWidget.h"
#include <UASManager.h> #include <UASManager.h>
#include <UAS.h> #include <UAS.h>
//#include <mavlink.h>
#define CONTROL_MODE_LOCKED "MODE LOCKED" #define CONTROL_MODE_LOCKED "MODE LOCKED"
#define CONTROL_MODE_MANUAL "MODE MANUAL" #define CONTROL_MODE_MANUAL "MODE MANUAL"
...@@ -104,6 +103,24 @@ void UASControlWidget::setUAS(UASInterface* uas) ...@@ -104,6 +103,24 @@ void UASControlWidget::setUAS(UASInterface* uas)
ui.controlStatusLabel->setText(tr("Connected to ") + uas->getUASName()); 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(); this->uas = uas->getUASID();
setBackgroundColor(uas->getColor()); setBackgroundColor(uas->getColor());
} }
......
...@@ -335,7 +335,7 @@ void UASView::refresh() ...@@ -335,7 +335,7 @@ void UASView::refresh()
//repaint(); //repaint();
static quint64 lastupdate = 0; static quint64 lastupdate = 0;
qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate; //qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
lastupdate = MG::TIME::getGroundTimeNow(); lastupdate = MG::TIME::getGroundTimeNow();
// FIXME // FIXME
...@@ -344,7 +344,7 @@ void UASView::refresh() ...@@ -344,7 +344,7 @@ void UASView::refresh()
if (generalUpdateCount == 4) if (generalUpdateCount == 4)
{ {
generalUpdateCount = 0; generalUpdateCount = 0;
qDebug() << "UPDATING EVERYTHING"; //qDebug() << "UPDATING EVERYTHING";
// State // State
m_ui->stateLabel->setText(state); m_ui->stateLabel->setText(state);
m_ui->statusTextLabel->setText(stateDesc); m_ui->statusTextLabel->setText(stateDesc);
...@@ -431,7 +431,7 @@ void UASView::refresh() ...@@ -431,7 +431,7 @@ void UASView::refresh()
// Fade heartbeat icon // Fade heartbeat icon
// Make color darker // Make color darker
heartbeatColor = heartbeatColor.darker(110); heartbeatColor = heartbeatColor.darker(150);
QString colorstyle; QString colorstyle;
colorstyle = colorstyle.sprintf("QGroupBox { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}", 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