mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-11-29 07:24:13 +01:00
LP-29 osgearth integration : added osgearth library (provides Qml items)
This commit is contained in:
parent
7b97bfdc28
commit
727924ea85
@ -106,6 +106,7 @@
|
||||
#include <QtWidgets/QApplication>
|
||||
#include <QMainWindow>
|
||||
#include <QSplashScreen>
|
||||
#include <QSurfaceFormat>
|
||||
|
||||
namespace {
|
||||
typedef QList<ExtensionSystem::PluginSpec *> PluginSpecSet;
|
||||
@ -252,11 +253,22 @@ void systemInit()
|
||||
getrlimit(RLIMIT_NOFILE, &rl);
|
||||
rl.rlim_cur = rl.rlim_max;
|
||||
setrlimit(RLIMIT_NOFILE, &rl);
|
||||
QApplication::setAttribute(Qt::AA_DontCreateNativeWidgetSiblings, true);
|
||||
#endif
|
||||
#ifdef Q_OS_LINUX
|
||||
|
||||
QApplication::setAttribute(Qt::AA_X11InitThreads, true);
|
||||
#endif
|
||||
|
||||
// protect QQuickWidget from native widgets like GLC ModelView
|
||||
// TODO revisit this...
|
||||
QApplication::setAttribute(Qt::AA_DontCreateNativeWidgetSiblings, true);
|
||||
|
||||
// Force "basic" render loop
|
||||
// Only Mac uses "threaded" by default and that mode currently does not work well with OSGViewport
|
||||
qputenv("QSG_RENDER_LOOP", "basic");
|
||||
|
||||
// disable vsync
|
||||
QSurfaceFormat format = QSurfaceFormat::defaultFormat();
|
||||
format.setSwapInterval(0);
|
||||
QSurfaceFormat::setDefaultFormat(format);
|
||||
}
|
||||
|
||||
static QTextStream *logStream;
|
||||
|
@ -1,7 +1,7 @@
|
||||
TEMPLATE = subdirs
|
||||
CONFIG += ordered
|
||||
TEMPLATE = subdirs
|
||||
CONFIG += ordered
|
||||
|
||||
SUBDIRS = \
|
||||
SUBDIRS = \
|
||||
version_info \
|
||||
qscispinbox\
|
||||
qtconcurrent \
|
||||
@ -13,4 +13,6 @@ SUBDIRS = \
|
||||
qwt \
|
||||
sdlgamepad
|
||||
|
||||
SUBDIRS +=
|
||||
exists( $(OSG_SDK_DIR) ) {
|
||||
SUBDIRS += osgearth
|
||||
}
|
||||
|
206
ground/openpilotgcs/src/libs/osgearth/copydata.pro
Normal file
206
ground/openpilotgcs/src/libs/osgearth/copydata.pro
Normal file
@ -0,0 +1,206 @@
|
||||
#
|
||||
# copy osg and osgearth libraries and data to build dir
|
||||
#
|
||||
equals(copydata, 1) {
|
||||
|
||||
OSG_VERSION = 3.3.8
|
||||
|
||||
linux {
|
||||
# copy osg libraries
|
||||
exists($(OSG_SDK_DIR)/lib64) {
|
||||
#addCopyDirFilesTargets($${OSG_SDK_DIR}/lib64,$${GCS_LIBRARY_PATH}/osg)
|
||||
} else {
|
||||
#addCopyDirFilesTargets($${OSG_SDK_DIR}/lib,$${GCS_LIBRARY_PATH}/osg)
|
||||
}
|
||||
}
|
||||
|
||||
macx {
|
||||
|
||||
isEmpty(PROVIDER) {
|
||||
PROVIDER = OpenPilot
|
||||
}
|
||||
|
||||
data_copy.commands += $(COPY_DIR) $$targetPath(\"$$OSG_SDK_DIR/lib/\"*) $$targetPath(\"$$GCS_LIBRARY_PATH\") $$addNewline()
|
||||
|
||||
# add make target
|
||||
POST_TARGETDEPS += copydata
|
||||
|
||||
data_copy.target = copydata
|
||||
QMAKE_EXTRA_TARGETS += data_copy
|
||||
}
|
||||
|
||||
win32 {
|
||||
# set debug suffix if needed
|
||||
CONFIG(debug, debug|release):DS = "d"
|
||||
|
||||
# copy osg libraries
|
||||
OSG_LIBS = \
|
||||
libcurl-4.dll \
|
||||
libfreetype-6.dll \
|
||||
libgdal.dll \
|
||||
libgeos-3-3-8.dll \
|
||||
libgeos_c-1.dll \
|
||||
libjpeg-9.dll \
|
||||
libpng16-16.dll \
|
||||
libproj-0.dll \
|
||||
libtiff-5.dll \
|
||||
libtiffxx-5.dll \
|
||||
zlib1.dll \
|
||||
libOpenThreads$${DS}.dll \
|
||||
libosg$${DS}.dll \
|
||||
libosgAnimation$${DS}.dll \
|
||||
libosgDB$${DS}.dll \
|
||||
libosgEarth$${DS}.dll \
|
||||
libosgEarthAnnotation$${DS}.dll \
|
||||
libosgEarthFeatures$${DS}.dll \
|
||||
libosgEarthQt$${DS}.dll \
|
||||
libosgEarthSymbology$${DS}.dll \
|
||||
libosgEarthUtil$${DS}.dll \
|
||||
libosgFX$${DS}.dll \
|
||||
libosgGA$${DS}.dll \
|
||||
libosgManipulator$${DS}.dll \
|
||||
libosgParticle$${DS}.dll \
|
||||
libosgPresentation$${DS}.dll \
|
||||
libosgQt$${DS}.dll \
|
||||
libosgShadow$${DS}.dll \
|
||||
libosgSim$${DS}.dll \
|
||||
libosgTerrain$${DS}.dll \
|
||||
libosgText$${DS}.dll \
|
||||
libosgUtil$${DS}.dll \
|
||||
libosgViewer$${DS}.dll \
|
||||
libosgVolume$${DS}.dll \
|
||||
libosgWidget$${DS}.dll
|
||||
for(lib, OSG_LIBS) {
|
||||
addCopyFileTarget($${lib},$${OSG_SDK_DIR}/bin,$${GCS_APP_PATH})
|
||||
}
|
||||
|
||||
OSG_PLUGINS = \
|
||||
mingw_osgdb_3dc$${DS}.dll \
|
||||
mingw_osgdb_3ds$${DS}.dll \
|
||||
mingw_osgdb_ac$${DS}.dll \
|
||||
mingw_osgdb_bmp$${DS}.dll \
|
||||
mingw_osgdb_bsp$${DS}.dll \
|
||||
mingw_osgdb_bvh$${DS}.dll \
|
||||
mingw_osgdb_cfg$${DS}.dll \
|
||||
mingw_osgdb_curl$${DS}.dll \
|
||||
mingw_osgdb_dds$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osg$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osganimationd$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osgfx$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osgparticle$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osgshadow$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osgsim$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osgterrain$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osgtext$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osgviewer$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osgvolume$${DS}.dll \
|
||||
#mingw_osgdb_deprecated_osgwidget$${DS}.dll \
|
||||
mingw_osgdb_dot$${DS}.dll \
|
||||
mingw_osgdb_dw$${DS}.dll \
|
||||
mingw_osgdb_dxf$${DS}.dll \
|
||||
mingw_osgdb_earth$${DS}.dll \
|
||||
mingw_osgdb_gdal$${DS}.dll \
|
||||
mingw_osgdb_glsl$${DS}.dll \
|
||||
mingw_osgdb_gz$${DS}.dll \
|
||||
mingw_osgdb_hdr$${DS}.dll \
|
||||
mingw_osgdb_ive$${DS}.dll \
|
||||
mingw_osgdb_jpeg$${DS}.dll \
|
||||
mingw_osgdb_kml$${DS}.dll \
|
||||
mingw_osgdb_ktx$${DS}.dll \
|
||||
mingw_osgdb_logo$${DS}.dll \
|
||||
mingw_osgdb_lwo$${DS}.dll \
|
||||
mingw_osgdb_lws$${DS}.dll \
|
||||
mingw_osgdb_md2$${DS}.dll \
|
||||
mingw_osgdb_mdl$${DS}.dll \
|
||||
mingw_osgdb_normals$${DS}.dll \
|
||||
mingw_osgdb_obj$${DS}.dll \
|
||||
mingw_osgdb_ogr$${DS}.dll \
|
||||
mingw_osgdb_openflight$${DS}.dll \
|
||||
mingw_osgdb_osc$${DS}.dll \
|
||||
mingw_osgdb_osg$${DS}.dll \
|
||||
mingw_osgdb_osga$${DS}.dll \
|
||||
mingw_osgdb_osgearth_agglite$${DS}.dll \
|
||||
mingw_osgdb_osgearth_arcgis$${DS}.dll \
|
||||
mingw_osgdb_osgearth_arcgis_map_cache$${DS}.dll \
|
||||
mingw_osgdb_osgearth_bing$${DS}.dll \
|
||||
mingw_osgdb_osgearth_cache_filesystem$${DS}.dll \
|
||||
mingw_osgdb_osgearth_colorramp$${DS}.dll \
|
||||
mingw_osgdb_osgearth_debug$${DS}.dll \
|
||||
mingw_osgdb_osgearth_engine_byo$${DS}.dll \
|
||||
mingw_osgdb_osgearth_engine_mp$${DS}.dll \
|
||||
mingw_osgdb_osgearth_feature_ogr$${DS}.dll \
|
||||
mingw_osgdb_osgearth_feature_tfs$${DS}.dll \
|
||||
mingw_osgdb_osgearth_feature_wfs$${DS}.dll \
|
||||
mingw_osgdb_osgearth_gdal$${DS}.dll \
|
||||
mingw_osgdb_osgearth_label_annotation$${DS}.dll \
|
||||
mingw_osgdb_osgearth_mask_feature$${DS}.dll \
|
||||
mingw_osgdb_osgearth_model_feature_geom$${DS}.dll \
|
||||
mingw_osgdb_osgearth_model_feature_stencil$${DS}.dll \
|
||||
mingw_osgdb_osgearth_model_simple$${DS}.dll \
|
||||
mingw_osgdb_osgearth_noise$${DS}.dll \
|
||||
mingw_osgdb_osgearth_ocean_simple$${DS}.dll \
|
||||
mingw_osgdb_osgearth_osg$${DS}.dll \
|
||||
mingw_osgdb_osgearth_refresh$${DS}.dll \
|
||||
mingw_osgdb_osgearth_scriptengine_javascript$${DS}.dll \
|
||||
mingw_osgdb_osgearth_sky_gl$${DS}.dll \
|
||||
mingw_osgdb_osgearth_sky_simple$${DS}.dll \
|
||||
mingw_osgdb_osgearth_splat_mask$${DS}.dll \
|
||||
mingw_osgdb_osgearth_template_matclass$${DS}.dll \
|
||||
mingw_osgdb_osgearth_tilecache$${DS}.dll \
|
||||
mingw_osgdb_osgearth_tileindex$${DS}.dll \
|
||||
mingw_osgdb_osgearth_tileservice$${DS}.dll \
|
||||
mingw_osgdb_osgearth_tms$${DS}.dll \
|
||||
mingw_osgdb_osgearth_vdatum_egm2008$${DS}.dll \
|
||||
mingw_osgdb_osgearth_vdatum_egm84$${DS}.dll \
|
||||
mingw_osgdb_osgearth_vdatum_egm96$${DS}.dll \
|
||||
mingw_osgdb_osgearth_vpb$${DS}.dll \
|
||||
mingw_osgdb_osgearth_wcs$${DS}.dll \
|
||||
mingw_osgdb_osgearth_wms$${DS}.dll \
|
||||
mingw_osgdb_osgearth_xyz$${DS}.dll \
|
||||
mingw_osgdb_osgearth_yahoo$${DS}.dll \
|
||||
mingw_osgdb_osgshadow$${DS}.dll \
|
||||
mingw_osgdb_osgterrain$${DS}.dll \
|
||||
mingw_osgdb_osgtgz$${DS}.dll \
|
||||
mingw_osgdb_osgviewer$${DS}.dll \
|
||||
mingw_osgdb_p3d$${DS}.dll \
|
||||
mingw_osgdb_pic$${DS}.dll \
|
||||
mingw_osgdb_ply$${DS}.dll \
|
||||
mingw_osgdb_png$${DS}.dll \
|
||||
mingw_osgdb_pnm$${DS}.dll \
|
||||
mingw_osgdb_pov$${DS}.dll \
|
||||
mingw_osgdb_pvr$${DS}.dll \
|
||||
mingw_osgdb_revisions$${DS}.dll \
|
||||
mingw_osgdb_rgb$${DS}.dll \
|
||||
mingw_osgdb_rot$${DS}.dll \
|
||||
mingw_osgdb_scale$${DS}.dll \
|
||||
mingw_osgdb_serializers_osg$${DS}.dll \
|
||||
mingw_osgdb_serializers_osganimation$${DS}.dll \
|
||||
mingw_osgdb_serializers_osgfx$${DS}.dll \
|
||||
mingw_osgdb_serializers_osgga$${DS}.dll \
|
||||
mingw_osgdb_serializers_osgmanipulator$${DS}.dll \
|
||||
mingw_osgdb_serializers_osgparticle$${DS}.dll \
|
||||
mingw_osgdb_serializers_osgshadow$${DS}.dll \
|
||||
mingw_osgdb_serializers_osgsim$${DS}.dll \
|
||||
mingw_osgdb_serializers_osgterrain$${DS}.dll \
|
||||
mingw_osgdb_serializers_osgtext$${DS}.dll \
|
||||
mingw_osgdb_serializers_osgviewer$${DS}.dll \
|
||||
mingw_osgdb_serializers_osgvolume$${DS}.dll \
|
||||
mingw_osgdb_shp$${DS}.dll \
|
||||
mingw_osgdb_stl$${DS}.dll \
|
||||
mingw_osgdb_tga$${DS}.dll \
|
||||
mingw_osgdb_tgz$${DS}.dll \
|
||||
mingw_osgdb_tiff$${DS}.dll \
|
||||
mingw_osgdb_trans$${DS}.dll \
|
||||
mingw_osgdb_trk$${DS}.dll \
|
||||
mingw_osgdb_txf$${DS}.dll \
|
||||
mingw_osgdb_txp$${DS}.dll \
|
||||
mingw_osgdb_vtf$${DS}.dll \
|
||||
mingw_osgdb_x$${DS}.dll \
|
||||
mingw_osgdb_zip$${DS}.dll
|
||||
# copy osg plugins
|
||||
for(lib, OSG_PLUGINS) {
|
||||
addCopyFileTarget($${lib},$${OSG_SDK_DIR}/bin/osgPlugins-$${OSG_VERSION},$${GCS_LIBRARY_PATH}/osg/osgPlugins-$${OSG_VERSION})
|
||||
}
|
||||
}
|
||||
|
||||
}
|
29
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/Export.hpp
Normal file
29
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/Export.hpp
Normal file
@ -0,0 +1,29 @@
|
||||
#ifndef _H_OSGQTQUICK_EXPORT_H_
|
||||
#define _H_OSGQTQUICK_EXPORT_H_ 1
|
||||
|
||||
#include <osg/Config>
|
||||
|
||||
#if defined(_MSC_VER) && defined(OSG_DISABLE_MSVC_WARNINGS)
|
||||
#pragma warning( disable : 4244 )
|
||||
#pragma warning( disable : 4251 )
|
||||
#pragma warning( disable : 4267 )
|
||||
#pragma warning( disable : 4275 )
|
||||
#pragma warning( disable : 4290 )
|
||||
#pragma warning( disable : 4786 )
|
||||
#pragma warning( disable : 4305 )
|
||||
#pragma warning( disable : 4996 )
|
||||
#endif
|
||||
|
||||
#if defined(_MSC_VER) || defined(__CYGWIN__) || defined(__MINGW32__) || defined(__BCPLUSPLUS__) || defined(__MWERKS__)
|
||||
# if defined(OSGEARTH_LIBRARY_STATIC)
|
||||
# define OSGQTQUICK_EXPORT
|
||||
# elif defined(OSGEARTH_LIBRARY)
|
||||
# define OSGQTQUICK_EXPORT __declspec(dllexport)
|
||||
# else
|
||||
# define OSGQTQUICK_EXPORT __declspec(dllimport)
|
||||
#endif
|
||||
#else
|
||||
#define OSGQTQUICK_EXPORT
|
||||
#endif
|
||||
|
||||
#endif // _H_OSGQTQUICK_EXPORT_H_
|
@ -0,0 +1,92 @@
|
||||
#include "OSGBackgroundNode.hpp"
|
||||
|
||||
#include <osg/Depth>
|
||||
#include <osg/Texture2D>
|
||||
#include <osgDB/ReadFile>
|
||||
|
||||
#include <QUrl>
|
||||
#include <QDebug>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGBackgroundNode::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
Hidden(OSGBackgroundNode *parent) : QObject(parent), self(parent), url() {}
|
||||
|
||||
bool acceptImageFile(QUrl url)
|
||||
{
|
||||
// qDebug() << "OSGBackgroundNode::acceptImageFile" << url;
|
||||
if (this->url == url) {
|
||||
return false;
|
||||
}
|
||||
|
||||
this->url = url;
|
||||
|
||||
realize();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void realize()
|
||||
{
|
||||
qDebug() << "OSGBackgroundNode::realize";
|
||||
|
||||
// qDebug() << "OSGBackgroundNode::realize - reading image file" << h->url.path();
|
||||
osg::ref_ptr<osg::Texture2D> texture = new osg::Texture2D;
|
||||
osg::ref_ptr<osg::Image> image = osgDB::readImageFile(url.path().toStdString());
|
||||
texture->setImage(image.get());
|
||||
|
||||
osg::ref_ptr<osg::Drawable> quad = osg::createTexturedQuadGeometry(
|
||||
osg::Vec3(), osg::Vec3(1.0f, 0.0f, 0.0f), osg::Vec3(0.0f, 1.0f, 0.0f));
|
||||
quad->getOrCreateStateSet()->setTextureAttributeAndModes(0, texture.get());
|
||||
|
||||
osg::ref_ptr<osg::Geode> geode = new osg::Geode;
|
||||
geode->addDrawable(quad.get());
|
||||
|
||||
osg::Camera *camera = new osg::Camera;
|
||||
camera->setClearMask(0);
|
||||
camera->setCullingActive(false);
|
||||
camera->setAllowEventFocus(false);
|
||||
camera->setReferenceFrame(osg::Transform::ABSOLUTE_RF);
|
||||
camera->setRenderOrder(osg::Camera::POST_RENDER);
|
||||
camera->setProjectionMatrix(osg::Matrix::ortho2D(0.0, 1.0, 0.0, 1.0));
|
||||
camera->addChild(geode.get());
|
||||
|
||||
osg::StateSet *ss = camera->getOrCreateStateSet();
|
||||
ss->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
|
||||
ss->setAttributeAndModes(new osg::Depth(osg::Depth::LEQUAL, 1.0, 1.0));
|
||||
|
||||
self->setNode(camera);
|
||||
}
|
||||
|
||||
OSGBackgroundNode *const self;
|
||||
|
||||
QUrl url;
|
||||
};
|
||||
|
||||
OSGBackgroundNode::OSGBackgroundNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
|
||||
{
|
||||
// qDebug() << "OSGBackgroundNode::OSGBackgroundNode";
|
||||
}
|
||||
|
||||
OSGBackgroundNode::~OSGBackgroundNode()
|
||||
{
|
||||
// qDebug() << "OSGBackgroundNode::~OSGBackgroundNode";
|
||||
}
|
||||
|
||||
const QUrl OSGBackgroundNode::imageFile() const
|
||||
{
|
||||
return h->url;
|
||||
}
|
||||
|
||||
void OSGBackgroundNode::setImageFile(const QUrl &url)
|
||||
{
|
||||
// qDebug() << "OSGBackgroundNode::setImageFile" << url;
|
||||
if (h->acceptImageFile(url)) {
|
||||
emit imageFileChanged(imageFile());
|
||||
}
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGBackgroundNode.moc"
|
@ -0,0 +1,32 @@
|
||||
#ifndef _H_OSGQTQUICK_BACKGROUNDNODE_H_
|
||||
#define _H_OSGQTQUICK_BACKGROUNDNODE_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
#include <QUrl>
|
||||
QT_BEGIN_NAMESPACE
|
||||
class QUrl;
|
||||
QT_END_NAMESPACE
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGQTQUICK_EXPORT OSGBackgroundNode : public OSGNode {
|
||||
Q_OBJECT Q_PROPERTY(QUrl imageFile READ imageFile WRITE setImageFile NOTIFY imageFileChanged)
|
||||
|
||||
public:
|
||||
OSGBackgroundNode(QObject *parent = 0);
|
||||
virtual ~OSGBackgroundNode();
|
||||
|
||||
const QUrl imageFile() const;
|
||||
void setImageFile(const QUrl &url);
|
||||
|
||||
signals:
|
||||
void imageFileChanged(const QUrl &url);
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_BACKGROUNDNODE_H_
|
621
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGCamera.cpp
Normal file
621
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGCamera.cpp
Normal file
@ -0,0 +1,621 @@
|
||||
#include "OSGCamera.hpp"
|
||||
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
#include "../utility.h"
|
||||
|
||||
#include <osg/Camera>
|
||||
#include <osg/Matrix>
|
||||
#include <osg/Node>
|
||||
#include <osg/Vec3d>
|
||||
|
||||
#include <osgGA/NodeTrackerManipulator>
|
||||
#include <osgGA/TrackballManipulator>
|
||||
|
||||
#include <osgViewer/View>
|
||||
|
||||
#include <osgEarth/GeoData>
|
||||
#include <osgEarth/SpatialReference>
|
||||
#include <osgEarthUtil/EarthManipulator>
|
||||
#include <osgEarthUtil/LogarithmicDepthBuffer>
|
||||
|
||||
#include <QDebug>
|
||||
#include <QThread>
|
||||
#include <QApplication>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGCamera::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
struct CameraUpdateCallback : public osg::NodeCallback {
|
||||
public:
|
||||
CameraUpdateCallback(Hidden *h) : h(h) {}
|
||||
|
||||
void operator()(osg::Node *node, osg::NodeVisitor *nv);
|
||||
|
||||
mutable Hidden *h;
|
||||
};
|
||||
friend class CameraUpdateCallback;
|
||||
|
||||
public:
|
||||
|
||||
Hidden(OSGCamera *parent) :
|
||||
QObject(parent), sceneData(NULL), manipulatorMode(Default), node(NULL),
|
||||
trackerMode(NodeCenterAndAzim), trackNode(NULL),
|
||||
logDepthBufferEnabled(false), logDepthBuffer(NULL), clampToTerrain(false)
|
||||
{
|
||||
fieldOfView = 90.0;
|
||||
|
||||
first = true;
|
||||
|
||||
dirty = false;
|
||||
|
||||
sizeDirty = false;
|
||||
x = 0;
|
||||
y = 0;
|
||||
width = 0;
|
||||
height = 0;
|
||||
}
|
||||
|
||||
~Hidden()
|
||||
{
|
||||
if (logDepthBuffer) {
|
||||
delete logDepthBuffer;
|
||||
logDepthBuffer = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
bool acceptSceneData(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGCamera::acceptSceneData" << node;
|
||||
if (sceneData == node) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if (sceneData) {
|
||||
disconnect(sceneData);
|
||||
}
|
||||
|
||||
sceneData = node;
|
||||
|
||||
if (sceneData) {
|
||||
//connect(sceneData, &OSGNode::nodeChanged, this, &Hidden::onSceneDataChanged);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptManipulatorMode(ManipulatorMode mode)
|
||||
{
|
||||
// qDebug() << "OSGCamera::acceptManipulatorMode" << mode;
|
||||
if (manipulatorMode == mode) {
|
||||
return false;
|
||||
}
|
||||
|
||||
manipulatorMode = mode;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptNode(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGCamera::acceptNode" << node;
|
||||
if (this->node == node) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (this->node) {
|
||||
disconnect(this->node);
|
||||
}
|
||||
|
||||
this->node = node;
|
||||
|
||||
if (this->node) {
|
||||
connect(this->node, SIGNAL(nodeChanged(osg::Node *)), this, SLOT(onNodeChanged(osg::Node *)));
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptTrackNode(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGCamera::acceptTrackNode" << node;
|
||||
if (trackNode == node) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (trackNode) {
|
||||
disconnect(trackNode);
|
||||
}
|
||||
|
||||
trackNode = node;
|
||||
|
||||
if (trackNode) {
|
||||
connect(trackNode, SIGNAL(nodeChanged(osg::Node *)), this, SLOT(onTrackNodeChanged(osg::Node *)));
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool attach(osgViewer::View *view)
|
||||
{
|
||||
attachCamera(view->getCamera());
|
||||
attachManipulator(view);
|
||||
return true;
|
||||
}
|
||||
|
||||
bool detach(osgViewer::View *view)
|
||||
{
|
||||
detachManipulator(view);
|
||||
detachCamera(view->getCamera());
|
||||
return true;
|
||||
}
|
||||
|
||||
void attachCamera(osg::Camera *camera)
|
||||
{
|
||||
qDebug() << "OSGCamera::attach" << camera;
|
||||
|
||||
this->camera = camera;
|
||||
|
||||
cameraUpdateCallback = new CameraUpdateCallback(this);
|
||||
camera->addUpdateCallback(cameraUpdateCallback);
|
||||
|
||||
// install log depth buffer if requested
|
||||
if (logDepthBufferEnabled) {
|
||||
qDebug() << "OSGCamera::attach - install logarithmic depth buffer";
|
||||
logDepthBuffer = new osgEarth::Util::LogarithmicDepthBuffer();
|
||||
//logDepthBuffer->setUseFragDepth(true);
|
||||
logDepthBuffer->install(camera);
|
||||
}
|
||||
|
||||
dirty = true;
|
||||
sizeDirty = true;
|
||||
updateCamera();
|
||||
}
|
||||
|
||||
void detachCamera(osg::Camera *camera)
|
||||
{
|
||||
qDebug() << "OSGCamera::detach" << camera;
|
||||
|
||||
if (camera != this->camera) {
|
||||
qWarning() << "OSGCamera::detach - camera not attached" << camera;
|
||||
return;
|
||||
}
|
||||
this->camera = NULL;
|
||||
|
||||
if (cameraUpdateCallback.valid()) {
|
||||
camera->removeUpdateCallback(cameraUpdateCallback);
|
||||
cameraUpdateCallback = NULL;
|
||||
}
|
||||
|
||||
if (logDepthBuffer) {
|
||||
logDepthBuffer->uninstall(camera);
|
||||
delete logDepthBuffer;
|
||||
logDepthBuffer = NULL;
|
||||
}
|
||||
|
||||
// reset viewport
|
||||
x = y = width = height = 0;
|
||||
}
|
||||
|
||||
void attachManipulator(osgViewer::View *view)
|
||||
{
|
||||
qDebug() << "OSGCamera::attachManipulator" << view;
|
||||
|
||||
osgGA::CameraManipulator *cm = NULL;
|
||||
|
||||
switch (manipulatorMode) {
|
||||
case OSGCamera::Default:
|
||||
{
|
||||
qDebug() << "OSGCamera::attachManipulator - use TrackballManipulator";
|
||||
osgGA::TrackballManipulator *tm = new osgGA::TrackballManipulator();
|
||||
// Set the minimum distance of the eye point from the center before the center is pushed forward.
|
||||
// tm->setMinimumDistance(1, true);
|
||||
cm = tm;
|
||||
break;
|
||||
}
|
||||
case OSGCamera::User:
|
||||
qDebug() << "OSGCamera::attachManipulator - no camera manipulator";
|
||||
// disable any installed camera manipulator
|
||||
cm = NULL;
|
||||
break;
|
||||
case OSGCamera::Earth:
|
||||
{
|
||||
qDebug() << "OSGCamera::attachManipulator - use EarthManipulator";
|
||||
osgEarth::Util::EarthManipulator *em = new osgEarth::Util::EarthManipulator();
|
||||
em->getSettings()->setThrowingEnabled(true);
|
||||
cm = em;
|
||||
break;
|
||||
}
|
||||
case OSGCamera::Track:
|
||||
qDebug() << "OSGCamera::attachManipulator - use NodeTrackerManipulator";
|
||||
if (trackNode && trackNode->node()) {
|
||||
// setup tracking camera
|
||||
// TODO when camera is thrown, then changing attitude has jitter (could be due to different frequency between refresh and animation)
|
||||
// TODO who takes ownership?
|
||||
osgGA::NodeTrackerManipulator *ntm = new osgGA::NodeTrackerManipulator(
|
||||
/*osgGA::StandardManipulator::COMPUTE_HOME_USING_BBOX | osgGA::StandardManipulator::DEFAULT_SETTINGS*/);
|
||||
switch (trackerMode) {
|
||||
case NodeCenter:
|
||||
ntm->setTrackerMode(osgGA::NodeTrackerManipulator::NODE_CENTER);
|
||||
break;
|
||||
case NodeCenterAndAzim:
|
||||
ntm->setTrackerMode(osgGA::NodeTrackerManipulator::NODE_CENTER_AND_AZIM);
|
||||
break;
|
||||
case NodeCenterAndRotation:
|
||||
ntm->setTrackerMode(osgGA::NodeTrackerManipulator::NODE_CENTER_AND_ROTATION);
|
||||
break;
|
||||
}
|
||||
ntm->setTrackNode(trackNode->node());
|
||||
// ntm->setRotationMode(trackRotationMode)
|
||||
// ntm->setMinimumDistance(2, false);
|
||||
ntm->setVerticalAxisFixed(false);
|
||||
// ntm->setAutoComputeHomePosition(true);
|
||||
// ntm->setDistance(100);
|
||||
cm = ntm;
|
||||
} else {
|
||||
qWarning() << "OSGCamera::attachManipulator - no track node provided.";
|
||||
cm = NULL;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
qWarning() << "OSGCamera::attachManipulator - should not reach here!";
|
||||
break;
|
||||
}
|
||||
|
||||
view->setCameraManipulator(cm, false);
|
||||
if (cm && node && node->node()) {
|
||||
qDebug() << "OSGCamera::attachManipulator - camera node" << node;
|
||||
// set node used to auto compute home position
|
||||
// needs to be done after setting the manipulator on the view as the view will set its scene as the node
|
||||
cm->setNode(node->node());
|
||||
}
|
||||
if (cm) {
|
||||
view->home();
|
||||
}
|
||||
}
|
||||
|
||||
void detachManipulator(osgViewer::View *view)
|
||||
{
|
||||
qDebug() << "OSGCamera::detachManipulator" << view;
|
||||
|
||||
view->setCameraManipulator(NULL, false);
|
||||
}
|
||||
|
||||
void updateCamera()
|
||||
{
|
||||
if (first) {
|
||||
first = false;
|
||||
updateCameraFOV();
|
||||
}
|
||||
updateCameraSize();
|
||||
if (manipulatorMode == User) {
|
||||
updateCameraPosition();
|
||||
}
|
||||
}
|
||||
|
||||
void updateCameraSize()
|
||||
{
|
||||
if (!sizeDirty || !camera.valid()) {
|
||||
return;
|
||||
}
|
||||
sizeDirty = false;
|
||||
|
||||
// qDebug() << "OSGCamera::updateCamera size" << x << y << width << height << fieldOfView;
|
||||
camera->getGraphicsContext()->resized(x, y, width, height);
|
||||
camera->setViewport(x, y, width, height);
|
||||
updateAspectRatio();
|
||||
}
|
||||
|
||||
void updateCameraFOV()
|
||||
{
|
||||
// qDebug() << "OSGCamera::updateCameraFOV";
|
||||
double fovy, ar, zn, zf;
|
||||
camera->getProjectionMatrixAsPerspective(fovy, ar, zn ,zf);
|
||||
|
||||
fovy = fieldOfView;
|
||||
camera->setProjectionMatrixAsPerspective(fovy, ar, zn, zf);
|
||||
}
|
||||
|
||||
void updateAspectRatio()
|
||||
{
|
||||
double fovy, ar, zn, zf;
|
||||
camera->getProjectionMatrixAsPerspective(fovy, ar, zn ,zf);
|
||||
|
||||
ar = static_cast<double>(width) / static_cast<double>(height);
|
||||
camera->setProjectionMatrixAsPerspective(fovy, ar, zn, zf);
|
||||
}
|
||||
|
||||
void updateCameraPosition()
|
||||
{
|
||||
if (!dirty || !camera.valid()) {
|
||||
return;
|
||||
}
|
||||
dirty = false;
|
||||
|
||||
// Altitude mode is absolute (absolute height above MSL/HAE)
|
||||
// HAE : Height above ellipsoid. This is the default.
|
||||
// MSL : Height above Mean Sea Level (MSL) if a geoid separation value is specified.
|
||||
// TODO handle the case where the terrain SRS is not "wgs84"
|
||||
// TODO check if position is not below terrain?
|
||||
// TODO compensate antenna height when source of position is GPS (i.e. subtract antenna height from altitude) ;)
|
||||
|
||||
// Camera position
|
||||
osgEarth::GeoPoint geoPoint = osgQtQuick::toGeoPoint(position);
|
||||
if (clampToTerrain) {
|
||||
if (sceneData) {
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneData->node());
|
||||
if (mapNode) {
|
||||
intoTerrain = clampGeoPoint(geoPoint, 0.5f, mapNode);
|
||||
} else {
|
||||
qWarning() << "OSGCamera::updateNode - scene data does not contain a map node";
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
osg::Matrix cameraPosition;
|
||||
geoPoint.createLocalToWorld(cameraPosition);
|
||||
|
||||
// Camera orientation
|
||||
// By default the camera looks toward -Z, we must rotate it so it looks toward Y
|
||||
osg::Matrix cameraRotation;
|
||||
cameraRotation.makeRotate(osg::DegreesToRadians(90.0), osg::Vec3(1.0, 0.0, 0.0),
|
||||
osg::DegreesToRadians(0.0), osg::Vec3(0.0, 1.0, 0.0),
|
||||
osg::DegreesToRadians(0.0), osg::Vec3(0.0, 0.0, 1.0));
|
||||
|
||||
// Final camera matrix
|
||||
osg::Matrix cameraMatrix = cameraRotation
|
||||
* osg::Matrix::rotate(osg::DegreesToRadians(attitude.x()), osg::Vec3(1.0, 0.0, 0.0))
|
||||
* osg::Matrix::rotate(osg::DegreesToRadians(attitude.y()), osg::Vec3(0.0, 1.0, 0.0))
|
||||
* osg::Matrix::rotate(osg::DegreesToRadians(attitude.z()), osg::Vec3(0.0, 0.0, 1.0)) * cameraPosition;
|
||||
|
||||
// Inverse the camera's position and orientation matrix to obtain the view matrix
|
||||
cameraMatrix = osg::Matrix::inverse(cameraMatrix);
|
||||
camera->setViewMatrix(cameraMatrix);
|
||||
}
|
||||
|
||||
qreal fieldOfView;
|
||||
|
||||
OSGNode *sceneData;
|
||||
|
||||
ManipulatorMode manipulatorMode;
|
||||
|
||||
// to compute home position
|
||||
OSGNode *node;
|
||||
|
||||
// for NodeTrackerManipulator
|
||||
TrackerMode trackerMode;
|
||||
OSGNode *trackNode;
|
||||
|
||||
bool logDepthBufferEnabled;
|
||||
osgEarth::Util::LogarithmicDepthBuffer *logDepthBuffer;
|
||||
|
||||
bool first;
|
||||
|
||||
// for User manipulator
|
||||
bool dirty;
|
||||
|
||||
bool clampToTerrain;
|
||||
bool intoTerrain;
|
||||
|
||||
QVector3D attitude;
|
||||
QVector3D position;
|
||||
|
||||
bool sizeDirty;
|
||||
int x;
|
||||
int y;
|
||||
int width;
|
||||
int height;
|
||||
|
||||
osg::ref_ptr<osg::Camera> camera;
|
||||
osg::ref_ptr<CameraUpdateCallback> cameraUpdateCallback;
|
||||
|
||||
private slots:
|
||||
void onNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGCamera::onNodeChanged" << node;
|
||||
qWarning() << "OSGCamera::onNodeChanged - needs to be implemented";
|
||||
}
|
||||
|
||||
void onTrackNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGCamera::onTrackNodeChanged" << node;
|
||||
qWarning() << "OSGCamera::onTrackNodeChanged - needs to be implemented";
|
||||
}
|
||||
};
|
||||
|
||||
/* struct Hidden::CameraUpdateCallback */
|
||||
|
||||
void OSGCamera::Hidden::CameraUpdateCallback::operator()(osg::Node *node, osg::NodeVisitor *nv)
|
||||
{
|
||||
h->updateCamera();
|
||||
//traverse(node, nv);
|
||||
}
|
||||
|
||||
/* class OSGCamera */
|
||||
|
||||
OSGCamera::OSGCamera(QObject *parent) : QObject(parent), h(new Hidden(this))
|
||||
{
|
||||
qDebug() << "OSGCamera::OSGCamera";
|
||||
}
|
||||
|
||||
OSGCamera::~OSGCamera()
|
||||
{
|
||||
qDebug() << "OSGCamera::~OSGCamera";
|
||||
}
|
||||
|
||||
qreal OSGCamera::fieldOfView() const
|
||||
{
|
||||
return h->fieldOfView;
|
||||
}
|
||||
|
||||
// ! Camera vertical field of view in degrees
|
||||
void OSGCamera::setFieldOfView(qreal arg)
|
||||
{
|
||||
if (h->fieldOfView != arg) {
|
||||
h->fieldOfView = arg;
|
||||
h->sizeDirty = true;
|
||||
emit fieldOfViewChanged(fieldOfView());
|
||||
|
||||
// it should be a queued call to OSGCameraRenderer instead
|
||||
/*if (h->viewer.get()) {
|
||||
h->viewer->getCamera()->setProjectionMatrixAsPerspective(
|
||||
h->fieldOfView,
|
||||
qreal(h->currentSize.width())/h->currentSize.height(),
|
||||
1.0f, 10000.0f);
|
||||
}*/
|
||||
|
||||
// updateFrame();
|
||||
}
|
||||
}
|
||||
|
||||
OSGNode *OSGCamera::sceneData()
|
||||
{
|
||||
return h->sceneData;
|
||||
}
|
||||
|
||||
void OSGCamera::setSceneData(OSGNode *node)
|
||||
{
|
||||
if (h->acceptSceneData(node)) {
|
||||
emit sceneDataChanged(node);
|
||||
}
|
||||
}
|
||||
|
||||
OSGCamera::ManipulatorMode OSGCamera::manipulatorMode() const
|
||||
{
|
||||
return h->manipulatorMode;
|
||||
}
|
||||
|
||||
void OSGCamera::setManipulatorMode(ManipulatorMode mode)
|
||||
{
|
||||
if (h->acceptManipulatorMode(mode)) {
|
||||
emit manipulatorModeChanged(manipulatorMode());
|
||||
}
|
||||
}
|
||||
|
||||
OSGNode *OSGCamera::node() const
|
||||
{
|
||||
return h->node;
|
||||
}
|
||||
|
||||
void OSGCamera::setNode(OSGNode *node)
|
||||
{
|
||||
if (h->acceptNode(node)) {
|
||||
emit nodeChanged(node);
|
||||
}
|
||||
}
|
||||
|
||||
OSGNode *OSGCamera::trackNode() const
|
||||
{
|
||||
return h->trackNode;
|
||||
}
|
||||
|
||||
void OSGCamera::setTrackNode(OSGNode *node)
|
||||
{
|
||||
if (h->acceptTrackNode(node)) {
|
||||
emit trackNodeChanged(node);
|
||||
}
|
||||
}
|
||||
|
||||
OSGCamera::TrackerMode OSGCamera::trackerMode() const
|
||||
{
|
||||
return h->trackerMode;
|
||||
}
|
||||
|
||||
void OSGCamera::setTrackerMode(TrackerMode mode)
|
||||
{
|
||||
if (h->trackerMode != mode) {
|
||||
h->trackerMode = mode;
|
||||
emit trackerModeChanged(trackerMode());
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGCamera::clampToTerrain() const
|
||||
{
|
||||
return h->clampToTerrain;
|
||||
}
|
||||
|
||||
void OSGCamera::setClampToTerrain(bool arg)
|
||||
{
|
||||
if (h->clampToTerrain != arg) {
|
||||
h->clampToTerrain = arg;
|
||||
h->dirty = true;
|
||||
emit clampToTerrainChanged(clampToTerrain());
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGCamera::intoTerrain() const
|
||||
{
|
||||
return h->intoTerrain;
|
||||
}
|
||||
|
||||
QVector3D OSGCamera::attitude() const
|
||||
{
|
||||
return h->attitude;
|
||||
}
|
||||
|
||||
void OSGCamera::setAttitude(QVector3D arg)
|
||||
{
|
||||
if (h->attitude != arg) {
|
||||
h->attitude = arg;
|
||||
h->dirty = true;
|
||||
emit attitudeChanged(attitude());
|
||||
}
|
||||
}
|
||||
|
||||
QVector3D OSGCamera::position() const
|
||||
{
|
||||
return h->position;
|
||||
}
|
||||
|
||||
void OSGCamera::setPosition(QVector3D arg)
|
||||
{
|
||||
if (h->position != arg) {
|
||||
h->position = arg;
|
||||
h->dirty = true;
|
||||
emit positionChanged(position());
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGCamera::logarithmicDepthBuffer()
|
||||
{
|
||||
return h->logDepthBufferEnabled;
|
||||
}
|
||||
|
||||
void OSGCamera::setLogarithmicDepthBuffer(bool enabled)
|
||||
{
|
||||
if (h->logDepthBufferEnabled != enabled) {
|
||||
h->logDepthBufferEnabled = enabled;
|
||||
emit logarithmicDepthBufferChanged(logarithmicDepthBuffer());
|
||||
}
|
||||
}
|
||||
|
||||
void OSGCamera::setViewport(int x, int y, int width, int height)
|
||||
{
|
||||
// qDebug() << "OSGCamera::setViewport" << x << y << width << "x" << heigth;
|
||||
if (width <= 0 || height <= 0) {
|
||||
qWarning() << "OSGCamera::setViewport - invalid size" << width << "x" << height;
|
||||
return;
|
||||
}
|
||||
if (h->x != x || h->y != y || h->width != width || h->height != height) {
|
||||
qWarning() << "OSGCamera::setViewport" << width << "x" << height;
|
||||
h->x = x;
|
||||
h->y = y;
|
||||
h->width = width;
|
||||
h->height = height;
|
||||
h->sizeDirty = true;
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGCamera::attach(osgViewer::View *view)
|
||||
{
|
||||
return h->attach(view);
|
||||
}
|
||||
|
||||
bool OSGCamera::detach(osgViewer::View *view)
|
||||
{
|
||||
return h->detach(view);
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGCamera.moc"
|
124
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGCamera.hpp
Normal file
124
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGCamera.hpp
Normal file
@ -0,0 +1,124 @@
|
||||
#ifndef _H_OSGQTQUICK_OSGCAMERA_H_
|
||||
#define _H_OSGQTQUICK_OSGCAMERA_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
|
||||
#include <QObject>
|
||||
#include <QVector3D>
|
||||
|
||||
namespace osgViewer {
|
||||
class View;
|
||||
}
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGNode;
|
||||
|
||||
// This class does too much:
|
||||
// - tracking a geo point and attitude
|
||||
// - tracking another node
|
||||
// camera should be simpler and provide only tracking
|
||||
// - tracking of a modelnode (for ModelView)
|
||||
// - tracking of a virtual node (for PFD with Terrain)
|
||||
//
|
||||
// TODO
|
||||
// - expose track mode
|
||||
// - provide good default distance and attitude for tracker camera
|
||||
class OSGQTQUICK_EXPORT OSGCamera : public QObject {
|
||||
Q_OBJECT Q_PROPERTY(qreal fieldOfView READ fieldOfView WRITE setFieldOfView NOTIFY fieldOfViewChanged)
|
||||
|
||||
Q_PROPERTY(osgQtQuick::OSGNode * sceneData READ sceneData WRITE setSceneData NOTIFY sceneDataChanged)
|
||||
|
||||
Q_PROPERTY(ManipulatorMode manipulatorMode READ manipulatorMode WRITE setManipulatorMode NOTIFY manipulatorModeChanged)
|
||||
|
||||
Q_PROPERTY(osgQtQuick::OSGNode * node READ node WRITE setNode NOTIFY nodeChanged)
|
||||
|
||||
Q_PROPERTY(osgQtQuick::OSGNode * trackNode READ trackNode WRITE setTrackNode NOTIFY trackNodeChanged)
|
||||
Q_PROPERTY(TrackerMode trackerMode READ trackerMode WRITE setTrackerMode NOTIFY trackerModeChanged)
|
||||
|
||||
Q_PROPERTY(bool clampToTerrain READ clampToTerrain WRITE setClampToTerrain NOTIFY clampToTerrainChanged)
|
||||
Q_PROPERTY(bool intoTerrain READ intoTerrain NOTIFY intoTerrainChanged)
|
||||
|
||||
Q_PROPERTY(QVector3D attitude READ attitude WRITE setAttitude NOTIFY attitudeChanged)
|
||||
Q_PROPERTY(QVector3D position READ position WRITE setPosition NOTIFY positionChanged)
|
||||
|
||||
Q_PROPERTY(bool logarithmicDepthBuffer READ logarithmicDepthBuffer WRITE setLogarithmicDepthBuffer NOTIFY logarithmicDepthBufferChanged)
|
||||
|
||||
Q_ENUMS(ManipulatorMode)
|
||||
Q_ENUMS(TrackerMode)
|
||||
|
||||
public:
|
||||
enum ManipulatorMode { Default, Earth, Track, User };
|
||||
|
||||
enum TrackerMode { NodeCenter, NodeCenterAndAzim, NodeCenterAndRotation };
|
||||
|
||||
explicit OSGCamera(QObject *parent = 0);
|
||||
virtual ~OSGCamera();
|
||||
|
||||
// fov depends on the scenery space (probaby distance)
|
||||
// here are some value: 75°, 60°, 45° many gamers use
|
||||
// x-plane uses 45° for 4:3 and 60° for 16:9/16:10
|
||||
// flightgear uses 55° / 70°
|
||||
qreal fieldOfView() const;
|
||||
void setFieldOfView(qreal arg);
|
||||
|
||||
OSGNode *sceneData();
|
||||
void setSceneData(OSGNode *node);
|
||||
|
||||
ManipulatorMode manipulatorMode() const;
|
||||
void setManipulatorMode(ManipulatorMode);
|
||||
|
||||
OSGNode *node() const;
|
||||
void setNode(OSGNode *node);
|
||||
|
||||
OSGNode *trackNode() const;
|
||||
void setTrackNode(OSGNode *node);
|
||||
|
||||
TrackerMode trackerMode() const;
|
||||
void setTrackerMode(TrackerMode);
|
||||
|
||||
bool clampToTerrain() const;
|
||||
void setClampToTerrain(bool arg);
|
||||
|
||||
bool intoTerrain() const;
|
||||
|
||||
QVector3D attitude() const;
|
||||
void setAttitude(QVector3D arg);
|
||||
|
||||
QVector3D position() const;
|
||||
void setPosition(QVector3D arg);
|
||||
|
||||
bool logarithmicDepthBuffer();
|
||||
void setLogarithmicDepthBuffer(bool enabled);
|
||||
|
||||
void setViewport(int x, int y, int width, int height);
|
||||
|
||||
virtual bool attach(osgViewer::View *view);
|
||||
virtual bool detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void fieldOfViewChanged(qreal arg);
|
||||
|
||||
void sceneDataChanged(OSGNode *node);
|
||||
|
||||
void manipulatorModeChanged(ManipulatorMode);
|
||||
|
||||
void nodeChanged(OSGNode *node);
|
||||
|
||||
void trackNodeChanged(OSGNode *node);
|
||||
void trackerModeChanged(TrackerMode);
|
||||
|
||||
void clampToTerrainChanged(bool arg);
|
||||
void intoTerrainChanged(bool arg);
|
||||
|
||||
void attitudeChanged(QVector3D arg);
|
||||
void positionChanged(QVector3D arg);
|
||||
|
||||
void logarithmicDepthBufferChanged(bool enabled);
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_OSGCAMERA_H_
|
@ -0,0 +1,64 @@
|
||||
#include "OSGCubeNode.hpp"
|
||||
|
||||
#include <osg/Geode>
|
||||
#include <osg/Group>
|
||||
#include <osg/Shape>
|
||||
#include <osg/ShapeDrawable>
|
||||
|
||||
#include <QDebug>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGCubeNode::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
Hidden(OSGCubeNode *parent) : QObject(parent), self(parent) {}
|
||||
|
||||
void realize()
|
||||
{
|
||||
qDebug() << "OSGCubeNode::realize";
|
||||
|
||||
// Declare a group to act as root node of a scene:
|
||||
// osg::Group* root = new osg::Group();
|
||||
|
||||
// Declare a box class (derived from shape class) instance
|
||||
// This constructor takes an osg::Vec3 to define the center
|
||||
// and a float to define the height, width and depth.
|
||||
// (an overloaded constructor allows you to specify unique
|
||||
// height, width and height values.)
|
||||
osg::Box *unitCube = new osg::Box(osg::Vec3(0, 0, 0), 1.0f);
|
||||
|
||||
// Declare an instance of the shape drawable class and initialize
|
||||
// it with the unitCube shape we created above.
|
||||
// This class is derived from 'drawable' so instances of this
|
||||
// class can be added to Geode instances.
|
||||
osg::ShapeDrawable *unitCubeDrawable = new osg::ShapeDrawable(unitCube);
|
||||
|
||||
// Declare a instance of the geode class:
|
||||
osg::Geode *basicShapesGeode = new osg::Geode();
|
||||
|
||||
// Add the unit cube drawable to the geode:
|
||||
basicShapesGeode->addDrawable(unitCubeDrawable);
|
||||
|
||||
// Add the geode to the scene:
|
||||
self->setNode(basicShapesGeode);
|
||||
}
|
||||
|
||||
OSGCubeNode *self;
|
||||
};
|
||||
|
||||
// TODO turn into generic shape node...
|
||||
// see http://trac.openscenegraph.org/projects/osg//wiki/Support/Tutorials/TransformsAndStates
|
||||
OSGCubeNode::OSGCubeNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
|
||||
{
|
||||
qDebug() << "OSGCubeNode::OSGCubeNode";
|
||||
h->realize();
|
||||
}
|
||||
|
||||
OSGCubeNode::~OSGCubeNode()
|
||||
{
|
||||
qDebug() << "OSGCubeNode::~OSGCubeNode";
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGCubeNode.moc"
|
@ -0,0 +1,21 @@
|
||||
#ifndef _H_OSGQTQUICK_CUBENODE_H_
|
||||
#define _H_OSGQTQUICK_CUBENODE_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGQTQUICK_EXPORT OSGCubeNode : public OSGNode {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
OSGCubeNode(QObject *parent = 0);
|
||||
virtual ~OSGCubeNode();
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_CUBENODE_H_
|
178
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGFileNode.cpp
Normal file
178
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGFileNode.cpp
Normal file
@ -0,0 +1,178 @@
|
||||
#include "OSGFileNode.hpp"
|
||||
|
||||
#include <osgDB/ReadFile>
|
||||
#include <osgUtil/Optimizer>
|
||||
|
||||
#include <QUrl>
|
||||
#include <QOpenGLContext>
|
||||
#include <QThread>
|
||||
#include <QElapsedTimer>
|
||||
#include <QDebug>
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGFileLoader : public QThread {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
OSGFileLoader(const QUrl &url) : url(url) {}
|
||||
|
||||
void run()
|
||||
{
|
||||
load();
|
||||
}
|
||||
|
||||
void load()
|
||||
{
|
||||
QElapsedTimer t;
|
||||
|
||||
t.start();
|
||||
qDebug() << "OSGFileLoader::load - reading node file" << url.path();
|
||||
// qDebug() << "OSGFileLoader - load - currentContext" << QOpenGLContext::currentContext();
|
||||
osg::Node *node = osgDB::readNodeFile(url.path().toStdString());
|
||||
// qDebug() << "OSGFileLoader::load - reading node" << node << "took" << t.elapsed() << "ms";
|
||||
|
||||
emit loaded(url, node);
|
||||
}
|
||||
|
||||
signals:
|
||||
void loaded(const QUrl & url, osg::Node *node);
|
||||
|
||||
private:
|
||||
QUrl url;
|
||||
};
|
||||
|
||||
struct OSGFileNode::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
private:
|
||||
OSGFileNode * const self;
|
||||
|
||||
public:
|
||||
Hidden(OSGFileNode *parent) : QObject(parent), self(parent), url(), async(false), optimizeMode(None) {}
|
||||
|
||||
bool acceptSource(QUrl url)
|
||||
{
|
||||
// qDebug() << "OSGFileNode::acceptSource" << url;
|
||||
|
||||
if (this->url == url) {
|
||||
return false;
|
||||
}
|
||||
|
||||
this->url = url;
|
||||
|
||||
if (url.isValid()) {
|
||||
realize();
|
||||
} else {
|
||||
qWarning() << "OSGFileNode::acceptNode - invalid url" << url;
|
||||
self->setNode(NULL);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
QUrl url;
|
||||
bool async;
|
||||
OptimizeMode optimizeMode;
|
||||
|
||||
private:
|
||||
|
||||
void asyncLoad(const QUrl &url)
|
||||
{
|
||||
OSGFileLoader *loader = new OSGFileLoader(url);
|
||||
|
||||
connect(loader, &OSGFileLoader::loaded, this, &Hidden::onLoaded);
|
||||
connect(loader, &OSGFileLoader::finished, loader, &OSGFileLoader::deleteLater);
|
||||
loader->start();
|
||||
}
|
||||
|
||||
void syncLoad(const QUrl &url)
|
||||
{
|
||||
OSGFileLoader loader(url);
|
||||
|
||||
connect(&loader, &OSGFileLoader::loaded, this, &Hidden::onLoaded);
|
||||
loader.load();
|
||||
}
|
||||
|
||||
void realize()
|
||||
{
|
||||
qDebug() << "OSGFileNode::realize";
|
||||
if (async) {
|
||||
asyncLoad(url);
|
||||
} else {
|
||||
syncLoad(url);
|
||||
}
|
||||
}
|
||||
|
||||
bool acceptNode(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGFileNode::acceptNode" << node;
|
||||
if (node && optimizeMode != OSGFileNode::None) {
|
||||
// qDebug() << "OSGFileNode::acceptNode - optimize" << node << optimizeMode;
|
||||
osgUtil::Optimizer optimizer;
|
||||
optimizer.optimize(node, osgUtil::Optimizer::DEFAULT_OPTIMIZATIONS);
|
||||
}
|
||||
self->setNode(node);
|
||||
return true;
|
||||
}
|
||||
|
||||
private slots:
|
||||
void onLoaded(const QUrl &url, osg::Node *node)
|
||||
{
|
||||
acceptNode(node);
|
||||
}
|
||||
};
|
||||
|
||||
OSGFileNode::OSGFileNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
|
||||
{
|
||||
qDebug() << "OSGFileNode::OSGFileNode";
|
||||
}
|
||||
|
||||
OSGFileNode::~OSGFileNode()
|
||||
{
|
||||
qDebug() << "OSGFileNode::~OSGFileNode";
|
||||
}
|
||||
|
||||
const QUrl OSGFileNode::source() const
|
||||
{
|
||||
return h->url;
|
||||
}
|
||||
|
||||
void OSGFileNode::setSource(const QUrl &url)
|
||||
{
|
||||
qDebug() << "OSGFileNode::setSource" << url;
|
||||
if (h->acceptSource(url)) {
|
||||
emit sourceChanged(source());
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGFileNode::async() const
|
||||
{
|
||||
return h->async;
|
||||
}
|
||||
|
||||
void OSGFileNode::setAsync(const bool async)
|
||||
{
|
||||
// qDebug() << "OSGFileNode::setAsync" << async;
|
||||
if (h->async != async) {
|
||||
h->async = async;
|
||||
emit asyncChanged(async);
|
||||
}
|
||||
}
|
||||
|
||||
OSGFileNode::OptimizeMode OSGFileNode::optimizeMode() const
|
||||
{
|
||||
return h->optimizeMode;
|
||||
}
|
||||
|
||||
void OSGFileNode::setOptimizeMode(OptimizeMode mode)
|
||||
{
|
||||
// qDebug() << "OSGFileNode::setOptimizeMode" << mode;
|
||||
if (h->optimizeMode != mode) {
|
||||
h->optimizeMode = mode;
|
||||
emit optimizeModeChanged(optimizeMode());
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGFileNode.moc"
|
@ -0,0 +1,46 @@
|
||||
#ifndef _H_OSGQTQUICK_FILENODE_H_
|
||||
#define _H_OSGQTQUICK_FILENODE_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
#include <QUrl>
|
||||
QT_BEGIN_NAMESPACE
|
||||
class QUrl;
|
||||
QT_END_NAMESPACE
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGQTQUICK_EXPORT OSGFileNode : public OSGNode {
|
||||
Q_OBJECT Q_PROPERTY(QUrl source READ source WRITE setSource NOTIFY sourceChanged)
|
||||
Q_PROPERTY(bool async READ async WRITE setAsync NOTIFY asyncChanged)
|
||||
Q_PROPERTY(OptimizeMode optimizeMode READ optimizeMode WRITE setOptimizeMode NOTIFY optimizeModeChanged)
|
||||
|
||||
Q_ENUMS(OptimizeMode)
|
||||
|
||||
public:
|
||||
enum OptimizeMode { None, Optimize, OptimizeAndCheck };
|
||||
|
||||
OSGFileNode(QObject *parent = 0);
|
||||
virtual ~OSGFileNode();
|
||||
|
||||
const QUrl source() const;
|
||||
void setSource(const QUrl &url);
|
||||
|
||||
bool async() const;
|
||||
void setAsync(const bool async);
|
||||
|
||||
OptimizeMode optimizeMode() const;
|
||||
void setOptimizeMode(OptimizeMode);
|
||||
|
||||
signals:
|
||||
void sourceChanged(const QUrl &url);
|
||||
void asyncChanged(const bool async);
|
||||
void optimizeModeChanged(OptimizeMode);
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_FILENODE_H_
|
123
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGGroup.cpp
Normal file
123
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGGroup.cpp
Normal file
@ -0,0 +1,123 @@
|
||||
#include "OSGGroup.hpp"
|
||||
|
||||
#include <osg/Group>
|
||||
|
||||
#include <QQmlListProperty>
|
||||
#include <QDebug>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGGroup::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
Hidden(OSGGroup *parent) : QObject(parent), self(parent)
|
||||
{
|
||||
group = new osg::Group;
|
||||
}
|
||||
|
||||
OSGGroup *self;
|
||||
|
||||
osg::ref_ptr<osg::Group> group;
|
||||
|
||||
QList<OSGNode *> children;
|
||||
|
||||
QMap<OSGNode *, osg::Node *> cache;
|
||||
|
||||
static void append_child(QQmlListProperty<OSGNode> *list, OSGNode *child)
|
||||
{
|
||||
OSGGroup *group = qobject_cast<OSGGroup *>(list->object);
|
||||
|
||||
if (group && child) {
|
||||
group->h->cache[child] = child->node();
|
||||
group->h->children.append(child);
|
||||
if (child->node()) {
|
||||
group->h->group->addChild(child->node());
|
||||
emit group->nodeChanged(group->h->group);
|
||||
}
|
||||
QObject::connect(child, SIGNAL(nodeChanged(osg::Node *)), group->h, SLOT(onNodeChanged(osg::Node *)));
|
||||
}
|
||||
}
|
||||
|
||||
static int count_child(QQmlListProperty<OSGNode> *list)
|
||||
{
|
||||
OSGGroup *group = qobject_cast<OSGGroup *>(list->object);
|
||||
|
||||
if (group) {
|
||||
return group->h->children.size();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static OSGNode *at_child(QQmlListProperty<OSGNode> *list, int index)
|
||||
{
|
||||
OSGGroup *group = qobject_cast<OSGGroup *>(list->object);
|
||||
|
||||
if (group && index >= 0 && index < group->h->children.size()) {
|
||||
return group->h->children[index];
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void clear_child(QQmlListProperty<OSGNode> *list)
|
||||
{
|
||||
OSGGroup *group = qobject_cast<OSGGroup *>(list->object);
|
||||
|
||||
if (group) {
|
||||
while (!group->h->children.isEmpty()) {
|
||||
OSGNode *node = group->h->children.takeLast();
|
||||
if (node->parent() == group) {
|
||||
node->deleteLater();
|
||||
}
|
||||
if (!node->parent()) {
|
||||
node->deleteLater();
|
||||
}
|
||||
}
|
||||
group->h->group->removeChild(0, group->h->group->getNumChildren());
|
||||
group->h->cache.clear();
|
||||
}
|
||||
}
|
||||
|
||||
public slots:
|
||||
void onNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGGroup::nodeChanged" << node;
|
||||
OSGNode *obj = qobject_cast<OSGNode *>(sender());
|
||||
if (obj) {
|
||||
osg::Node *cacheNode = cache.value(obj, NULL);
|
||||
if (cacheNode) {
|
||||
group->removeChild(cacheNode);
|
||||
}
|
||||
if (node) {
|
||||
group->addChild(node);
|
||||
}
|
||||
cache[obj] = node;
|
||||
emit self->nodeChanged(group.get());
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
OSGGroup::OSGGroup(QObject *parent) :
|
||||
OSGNode(parent), h(new Hidden(this))
|
||||
{
|
||||
qDebug() << "OSGGroup::OSGGroup";
|
||||
setNode(h->group.get());
|
||||
}
|
||||
|
||||
OSGGroup::~OSGGroup()
|
||||
{
|
||||
qDebug() << "OSGGroup::~OSGGroup";
|
||||
}
|
||||
|
||||
QQmlListProperty<OSGNode> OSGGroup::children()
|
||||
{
|
||||
return QQmlListProperty<OSGNode>(this, 0,
|
||||
&Hidden::append_child,
|
||||
&Hidden::count_child,
|
||||
&Hidden::at_child,
|
||||
&Hidden::clear_child);
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGGroup.moc"
|
@ -0,0 +1,27 @@
|
||||
#ifndef _H_OSGQTQUICK_OSGGROUP_H_
|
||||
#define _H_OSGQTQUICK_OSGGROUP_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
#include <QQmlListProperty>
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGQTQUICK_EXPORT OSGGroup : public OSGNode {
|
||||
Q_OBJECT Q_PROPERTY(QQmlListProperty<osgQtQuick::OSGNode> children READ children)
|
||||
|
||||
Q_CLASSINFO("DefaultProperty", "children")
|
||||
|
||||
public:
|
||||
explicit OSGGroup(QObject *parent = 0);
|
||||
virtual ~OSGGroup();
|
||||
|
||||
QQmlListProperty<OSGNode> children();
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_OSGGROUP_H_
|
@ -0,0 +1,341 @@
|
||||
#include "OSGModelNode.hpp"
|
||||
|
||||
#include "../utility.h"
|
||||
|
||||
#include <osg/Quat>
|
||||
#include <osg/ComputeBoundsVisitor>
|
||||
#include <osgViewer/View>
|
||||
|
||||
#include <osgEarth/MapNode>
|
||||
#include <osgEarth/GeoData>
|
||||
|
||||
#include <osgEarthSymbology/Style>
|
||||
#include <osgEarthSymbology/ModelSymbol>
|
||||
|
||||
#include <osgEarthAnnotation/ModelNode>
|
||||
|
||||
#include <QDebug>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGModelNode::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
struct NodeUpdateCallback : public osg::NodeCallback {
|
||||
public:
|
||||
NodeUpdateCallback(Hidden *h) : h(h) {}
|
||||
|
||||
void operator()(osg::Node *node, osg::NodeVisitor *nv);
|
||||
|
||||
mutable Hidden *h;
|
||||
};
|
||||
friend class NodeUpdateCallback;
|
||||
|
||||
public:
|
||||
|
||||
Hidden(OSGModelNode *parent) : QObject(parent), self(parent), modelData(NULL), sceneData(NULL), offset(-1.0), clampToTerrain(false), dirty(false)
|
||||
{
|
||||
}
|
||||
|
||||
~Hidden()
|
||||
{}
|
||||
|
||||
bool acceptModelData(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGModelNode::acceptModelData" << node;
|
||||
if (modelData == node) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (modelData) {
|
||||
disconnect(modelData);
|
||||
}
|
||||
|
||||
modelData = node;
|
||||
|
||||
if (modelData) {
|
||||
acceptModelNode(modelData->node());
|
||||
connect(modelData, SIGNAL(nodeChanged(osg::Node *)), this, SLOT(onModelNodeChanged(osg::Node *)));
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptModelNode(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGModelNode::acceptModelNode" << node;
|
||||
if (!node) {
|
||||
qWarning() << "OSGModelNode::acceptModelNode - node is null";
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!sceneData || !sceneData->node()) {
|
||||
qWarning() << "OSGModelNode::acceptModelNode - no scene data";
|
||||
return false;
|
||||
}
|
||||
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneData->node());
|
||||
if (!mapNode) {
|
||||
qWarning() << "OSGModelNode::acceptModelNode - scene data does not contain a map node";
|
||||
return false;
|
||||
}
|
||||
|
||||
// establish the coordinate system we wish to use:
|
||||
// const osgEarth::SpatialReference* latLong = osgEarth::SpatialReference::get("wgs84");
|
||||
|
||||
osgEarth::Symbology::Style style;
|
||||
|
||||
// construct the symbology
|
||||
osgEarth::Symbology::ModelSymbol *modelSymbol = style.getOrCreate<osgEarth::Symbology::ModelSymbol>();
|
||||
modelSymbol->setModel(node);
|
||||
|
||||
// create ModelNode
|
||||
modelNode = new osgEarth::Annotation::ModelNode(mapNode, style);
|
||||
|
||||
// add update callback
|
||||
if (!nodeUpdateCallback.valid()) {
|
||||
nodeUpdateCallback = new NodeUpdateCallback(this);
|
||||
}
|
||||
modelNode->addUpdateCallback(nodeUpdateCallback.get());
|
||||
|
||||
// get "size" of model
|
||||
osg::ComputeBoundsVisitor cbv;
|
||||
modelNode->accept(cbv);
|
||||
const osg::BoundingBox& bbox = cbv.getBoundingBox();
|
||||
offset = bbox.radius();
|
||||
|
||||
self->setNode(modelNode);
|
||||
|
||||
dirty = true;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool attach(osgViewer::View *view)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
bool detach(osgViewer::View *view)
|
||||
{
|
||||
qWarning() << "OSGModelNode::detach - not implemented";
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptSceneData(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGModelNode::acceptSceneData" << node;
|
||||
if (sceneData == node) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (sceneData) {
|
||||
disconnect(sceneData);
|
||||
}
|
||||
|
||||
sceneData = node;
|
||||
|
||||
if (sceneData) {
|
||||
// TODO find a better way
|
||||
if (modelData && modelData->node()) {
|
||||
acceptModelNode(modelData->node());
|
||||
}
|
||||
connect(sceneData, SIGNAL(nodeChanged(osg::Node *)), this, SLOT(onSceneNodeChanged(osg::Node *)));
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// TODO model update gets jitter if camera is thrown (i.e animated)
|
||||
void updateNode()
|
||||
{
|
||||
if (!dirty || !modelNode.valid()) {
|
||||
return;
|
||||
}
|
||||
dirty = false;
|
||||
|
||||
osgEarth::GeoPoint geoPoint = osgQtQuick::toGeoPoint(position);
|
||||
if (clampToTerrain) {
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneData->node());
|
||||
if (mapNode) {
|
||||
intoTerrain = clampGeoPoint(geoPoint, offset, mapNode);
|
||||
} else {
|
||||
qWarning() << "OSGModelNode::updateNode - scene data does not contain a map node";
|
||||
}
|
||||
}
|
||||
modelNode->setPosition(geoPoint);
|
||||
modelNode->setLocalRotation(localRotation());
|
||||
}
|
||||
|
||||
osg::Quat localRotation()
|
||||
{
|
||||
osg::Quat q = osg::Quat(
|
||||
osg::DegreesToRadians(attitude.x()), osg::Vec3d(1, 0, 0),
|
||||
osg::DegreesToRadians(attitude.y()), osg::Vec3d(0, 1, 0),
|
||||
osg::DegreesToRadians(attitude.z()), osg::Vec3d(0, 0, 1));
|
||||
|
||||
return q;
|
||||
}
|
||||
|
||||
OSGModelNode *const self;
|
||||
|
||||
OSGNode *modelData;
|
||||
OSGNode *sceneData;
|
||||
|
||||
osg::ref_ptr<osgEarth::Annotation::ModelNode> modelNode;
|
||||
|
||||
float offset;
|
||||
|
||||
bool clampToTerrain;
|
||||
bool intoTerrain;
|
||||
|
||||
QVector3D attitude;
|
||||
QVector3D position;
|
||||
|
||||
// handle attitude/position/etc independently
|
||||
bool dirty;
|
||||
|
||||
osg::observer_ptr<NodeUpdateCallback> nodeUpdateCallback;
|
||||
|
||||
private slots:
|
||||
|
||||
void onModelNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGModelNode::onModelNodeChanged" << node;
|
||||
if (modelData) {
|
||||
if (modelNode.valid()) {
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneData->node());
|
||||
if (mapNode) {
|
||||
mapNode->removeChild(modelNode);
|
||||
}
|
||||
if (nodeUpdateCallback.valid()) {
|
||||
modelNode->removeUpdateCallback(nodeUpdateCallback.get());
|
||||
}
|
||||
}
|
||||
if (node) {
|
||||
acceptModelNode(node);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void onSceneNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGModelNode::onSceneNodeChanged" << node;
|
||||
// TODO needs to be improved...
|
||||
if (modelData) {
|
||||
if (modelNode.valid()) {
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneData->node());
|
||||
if (mapNode) {
|
||||
mapNode->removeChild(modelNode);
|
||||
}
|
||||
if (nodeUpdateCallback.valid()) {
|
||||
modelNode->removeUpdateCallback(nodeUpdateCallback.get());
|
||||
}
|
||||
}
|
||||
if (modelData->node()) {
|
||||
acceptModelNode(modelData->node());
|
||||
}
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
/* struct Hidden::NodeUpdateCallback */
|
||||
|
||||
void OSGModelNode::Hidden::NodeUpdateCallback::operator()(osg::Node *node, osg::NodeVisitor *nv)
|
||||
{
|
||||
h->updateNode();
|
||||
traverse(node, nv);
|
||||
}
|
||||
|
||||
OSGModelNode::OSGModelNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
|
||||
{
|
||||
qDebug() << "OSGModelNode::OSGModelNode";
|
||||
}
|
||||
|
||||
OSGModelNode::~OSGModelNode()
|
||||
{
|
||||
qDebug() << "OSGModelNode::~OSGModelNode";
|
||||
}
|
||||
|
||||
OSGNode *OSGModelNode::modelData()
|
||||
{
|
||||
return h->modelData;
|
||||
}
|
||||
|
||||
void OSGModelNode::setModelData(OSGNode *node)
|
||||
{
|
||||
if (h->acceptModelData(node)) {
|
||||
emit modelDataChanged(node);
|
||||
}
|
||||
}
|
||||
|
||||
OSGNode *OSGModelNode::sceneData()
|
||||
{
|
||||
return h->sceneData;
|
||||
}
|
||||
|
||||
void OSGModelNode::setSceneData(OSGNode *node)
|
||||
{
|
||||
if (h->acceptSceneData(node)) {
|
||||
emit sceneDataChanged(node);
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGModelNode::clampToTerrain() const
|
||||
{
|
||||
return h->clampToTerrain;
|
||||
}
|
||||
|
||||
void OSGModelNode::setClampToTerrain(bool arg)
|
||||
{
|
||||
if (h->clampToTerrain != arg) {
|
||||
h->clampToTerrain = arg;
|
||||
h->dirty = true;
|
||||
emit clampToTerrainChanged(clampToTerrain());
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGModelNode::intoTerrain() const
|
||||
{
|
||||
return h->intoTerrain;
|
||||
}
|
||||
|
||||
QVector3D OSGModelNode::attitude() const
|
||||
{
|
||||
return h->attitude;
|
||||
}
|
||||
|
||||
void OSGModelNode::setAttitude(QVector3D arg)
|
||||
{
|
||||
if (h->attitude != arg) {
|
||||
h->attitude = arg;
|
||||
h->dirty = true;
|
||||
emit attitudeChanged(attitude());
|
||||
}
|
||||
}
|
||||
|
||||
QVector3D OSGModelNode::position() const
|
||||
{
|
||||
return h->position;
|
||||
}
|
||||
|
||||
void OSGModelNode::setPosition(QVector3D arg)
|
||||
{
|
||||
if (h->position != arg) {
|
||||
h->position = arg;
|
||||
h->dirty = true;
|
||||
emit positionChanged(position());
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGModelNode::attach(osgViewer::View *view)
|
||||
{
|
||||
return h->attach(view);
|
||||
}
|
||||
|
||||
bool OSGModelNode::detach(osgViewer::View *view)
|
||||
{
|
||||
return h->detach(view);
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGModelNode.moc"
|
@ -0,0 +1,67 @@
|
||||
#ifndef _H_OSGQTQUICK_MODELNODE_H_
|
||||
#define _H_OSGQTQUICK_MODELNODE_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
#include <QVector3D>
|
||||
#include <QUrl>
|
||||
|
||||
namespace osgViewer {
|
||||
class View;
|
||||
}
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGQTQUICK_EXPORT OSGModelNode : public OSGNode {
|
||||
Q_OBJECT
|
||||
// TODO rename to parentNode and modelNode
|
||||
Q_PROPERTY(osgQtQuick::OSGNode *modelData READ modelData WRITE setModelData NOTIFY modelDataChanged)
|
||||
Q_PROPERTY(osgQtQuick::OSGNode * sceneData READ sceneData WRITE setSceneData NOTIFY sceneDataChanged)
|
||||
|
||||
Q_PROPERTY(bool clampToTerrain READ clampToTerrain WRITE setClampToTerrain NOTIFY clampToTerrainChanged)
|
||||
Q_PROPERTY(bool intoTerrain READ intoTerrain NOTIFY intoTerrainChanged)
|
||||
|
||||
Q_PROPERTY(QVector3D attitude READ attitude WRITE setAttitude NOTIFY attitudeChanged)
|
||||
Q_PROPERTY(QVector3D position READ position WRITE setPosition NOTIFY positionChanged)
|
||||
|
||||
public:
|
||||
OSGModelNode(QObject *parent = 0);
|
||||
virtual ~OSGModelNode();
|
||||
|
||||
OSGNode *modelData();
|
||||
void setModelData(OSGNode *node);
|
||||
|
||||
OSGNode *sceneData();
|
||||
void setSceneData(OSGNode *node);
|
||||
|
||||
bool clampToTerrain() const;
|
||||
void setClampToTerrain(bool arg);
|
||||
|
||||
bool intoTerrain() const;
|
||||
|
||||
QVector3D attitude() const;
|
||||
void setAttitude(QVector3D arg);
|
||||
|
||||
QVector3D position() const;
|
||||
void setPosition(QVector3D arg);
|
||||
|
||||
virtual bool attach(osgViewer::View *view);
|
||||
virtual bool detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void modelDataChanged(OSGNode *node);
|
||||
void sceneDataChanged(OSGNode *node);
|
||||
|
||||
void clampToTerrainChanged(bool arg);
|
||||
void intoTerrainChanged(bool arg);
|
||||
|
||||
void attitudeChanged(QVector3D arg);
|
||||
void positionChanged(QVector3D arg);
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_MODELNODE_H_
|
56
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGNode.cpp
Normal file
56
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGNode.cpp
Normal file
@ -0,0 +1,56 @@
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
#include <osg/Node>
|
||||
|
||||
#include <QListIterator>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGNode::Hidden {
|
||||
osg::ref_ptr<osg::Node> node;
|
||||
};
|
||||
|
||||
OSGNode::OSGNode(QObject *parent) : QObject(parent), h(new Hidden)
|
||||
{}
|
||||
|
||||
OSGNode::~OSGNode()
|
||||
{
|
||||
delete h;
|
||||
}
|
||||
|
||||
osg::Node *OSGNode::node() const
|
||||
{
|
||||
return h->node.get();
|
||||
}
|
||||
|
||||
void OSGNode::setNode(osg::Node *node)
|
||||
{
|
||||
if (h->node.get() != node) {
|
||||
h->node = node;
|
||||
emit nodeChanged(node);
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGNode::attach(osgViewer::View *view)
|
||||
{
|
||||
QListIterator<QObject *> i(children());
|
||||
while (i.hasNext()) {
|
||||
OSGNode *node = qobject_cast<OSGNode *>(i.next());
|
||||
if (node) {
|
||||
node->attach(view);
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool OSGNode::detach(osgViewer::View *view)
|
||||
{
|
||||
QListIterator<QObject *> i(children());
|
||||
while (i.hasNext()) {
|
||||
OSGNode *node = qobject_cast<OSGNode *>(i.next());
|
||||
if (node) {
|
||||
node->detach(view);
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
} // namespace osgQtQuick
|
39
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGNode.hpp
Normal file
39
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGNode.hpp
Normal file
@ -0,0 +1,39 @@
|
||||
#ifndef _H_OSGQTQUICK_OSGNODE_H_
|
||||
#define _H_OSGQTQUICK_OSGNODE_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
|
||||
#include <QObject>
|
||||
|
||||
namespace osg {
|
||||
class Node;
|
||||
} // namespace osg
|
||||
|
||||
namespace osgViewer {
|
||||
class View;
|
||||
} // namespace osgViewer
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGQTQUICK_EXPORT OSGNode : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit OSGNode(QObject *parent = 0);
|
||||
virtual ~OSGNode();
|
||||
|
||||
osg::Node *node() const;
|
||||
void setNode(osg::Node *node);
|
||||
|
||||
virtual bool attach(osgViewer::View *view);
|
||||
virtual bool detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void nodeChanged(osg::Node *node) const;
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_OSGNODE_H_
|
259
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGSkyNode.cpp
Normal file
259
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGSkyNode.cpp
Normal file
@ -0,0 +1,259 @@
|
||||
#include "OSGSkyNode.hpp"
|
||||
|
||||
#include <osgViewer/View>
|
||||
|
||||
#include <osgEarth/Config>
|
||||
#include <osgEarth/DateTime>
|
||||
#include <osgEarth/MapNode>
|
||||
#include <osgEarthUtil/Sky>
|
||||
|
||||
// #include <osgEarthDrivers/sky_silverlining/SilverLiningOptions>
|
||||
|
||||
#include <QDebug>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGSkyNode::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
Hidden(OSGSkyNode *parent) : QObject(parent), self(parent), sceneData(NULL), sunLightEnabled(true), dateTime(), minimumAmbientLight(0.03)
|
||||
{}
|
||||
|
||||
~Hidden()
|
||||
{}
|
||||
|
||||
bool acceptSceneNode(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGSkyNode::acceptSceneNode" << node;
|
||||
if (sceneData == node) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (sceneData) {
|
||||
disconnect(sceneData);
|
||||
}
|
||||
|
||||
sceneData = node;
|
||||
|
||||
if (sceneData) {
|
||||
acceptNode(sceneData->node());
|
||||
connect(sceneData, SIGNAL(nodeChanged(osg::Node *)), this, SLOT(onNodeChanged(osg::Node *)));
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptNode(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGSkyNode::acceptNode" << node;
|
||||
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(node);
|
||||
if (!mapNode) {
|
||||
qWarning() << "OSGSkyNode::acceptNode - scene data does not contain a map node";
|
||||
return false;
|
||||
}
|
||||
if (!mapNode->getMap()->isGeocentric()) {
|
||||
qWarning() << "OSGSkyNode::acceptNode - map node is not geocentric";
|
||||
return false;
|
||||
}
|
||||
|
||||
// create sky node
|
||||
skyNode = createSimpleSky(mapNode);
|
||||
// skyNode = createSilverLiningSky(mapNode);
|
||||
|
||||
acceptSunLightEnabled(sunLightEnabled);
|
||||
acceptDateTime(dateTime);
|
||||
acceptMinimumAmbientLight(minimumAmbientLight);
|
||||
|
||||
// skyNode->setStarsVisible(false);
|
||||
|
||||
// Ocean
|
||||
// const osgEarth::Config & externals = mapNode->externalConfig();
|
||||
// if (externals.hasChild("ocean")) {
|
||||
// s_ocean = osgEarth::Util::OceanNode::create(osgEarth::Util::OceanOptions(externals.child("ocean")), mapNode);
|
||||
// if (s_ocean) root->addChild(s_ocean);
|
||||
|
||||
skyNode->addChild(node);
|
||||
|
||||
self->setNode(skyNode);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
osgEarth::Util::SkyNode *createSimpleSky(osgEarth::MapNode *mapNode)
|
||||
{
|
||||
return osgEarth::Util::SkyNode::create(mapNode);
|
||||
}
|
||||
|
||||
/*
|
||||
osgEarth::Util::SkyNode *createSilverLiningSky(osgEarth::MapNode *mapNode)
|
||||
{
|
||||
osgEarth::Drivers::SilverLining::SilverLiningOptions skyOptions;
|
||||
skyOptions.user() = "OpenPilot";
|
||||
skyOptions.licenseCode() = "1f02040d24000f0e18";
|
||||
skyOptions.resourcePath() = "D:/Projects/OpenPilot/3rdparty/SilverLining-SDK-FullSource/Resources";
|
||||
skyOptions.drawClouds() = true;
|
||||
skyOptions.cloudsMaxAltitude() = 10000.0;
|
||||
|
||||
osgEarth::Util::SkyNode *skyNode = osgEarth::Util::SkyNode::create(skyOptions, mapNode);
|
||||
|
||||
return skyNode;
|
||||
}
|
||||
*/
|
||||
|
||||
bool acceptSunLightEnabled(bool enabled)
|
||||
{
|
||||
// qDebug() << "OSGSkyNode::acceptSunLightEnabled" << enabled;
|
||||
|
||||
this->sunLightEnabled = enabled;
|
||||
|
||||
// TODO should be done in a node visitor...
|
||||
if (skyNode) {
|
||||
// skyNode->setLighting(sunLightEnabled ? osg::StateAttribute::ON : osg::StateAttribute::OFF);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptDateTime(QDateTime dateTime)
|
||||
{
|
||||
qDebug() << "OSGSkyNode::acceptDateTime" << dateTime;
|
||||
|
||||
if (!dateTime.isValid()) {
|
||||
qWarning() << "OSGSkyNode::acceptDateTime - invalid date/time" << dateTime;
|
||||
return false;
|
||||
}
|
||||
|
||||
this->dateTime = dateTime;
|
||||
|
||||
// TODO should be done in a node visitor...
|
||||
if (skyNode) {
|
||||
QDate date = dateTime.date();
|
||||
QTime time = dateTime.time();
|
||||
double hours = time.hour() + (double)time.minute() / 60.0 + (double)time.second() / 3600.0;
|
||||
skyNode->setDateTime(osgEarth::DateTime(date.year(), date.month(), date.day(), hours));
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptMinimumAmbientLight(double minimumAmbientLight)
|
||||
{
|
||||
// qDebug() << "OSGSkyNode::acceptMinimumAmbientLight" << minimumAmbientLight;
|
||||
|
||||
this->minimumAmbientLight = minimumAmbientLight;
|
||||
|
||||
// TODO should be done in a node visitor...
|
||||
if (skyNode) {
|
||||
double d = minimumAmbientLight;
|
||||
//skyNode->getSunLight()->setAmbient(osg::Vec4(d, d, d, 1.0f));
|
||||
skyNode->setMinimumAmbient(osg::Vec4(d, d, d, 1.0f));
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool attach(osgViewer::View *view)
|
||||
{
|
||||
if (!skyNode.valid()) {
|
||||
qWarning() << "OSGSkyNode::attach - invalid sky node" << skyNode;
|
||||
return false;
|
||||
}
|
||||
skyNode->attach(view, 0);
|
||||
return true;
|
||||
}
|
||||
|
||||
bool detach(osgViewer::View *view)
|
||||
{
|
||||
qWarning() << "OSGSkyNode::detach - not implemented";
|
||||
return true;
|
||||
}
|
||||
|
||||
OSGSkyNode *const self;
|
||||
|
||||
OSGNode *sceneData;
|
||||
osg::ref_ptr<osgEarth::Util::SkyNode> skyNode;
|
||||
|
||||
bool sunLightEnabled;
|
||||
QDateTime dateTime;
|
||||
double minimumAmbientLight;
|
||||
|
||||
private slots:
|
||||
|
||||
void onNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGSkyNode::onNodeChanged" << node;
|
||||
acceptNode(node);
|
||||
}
|
||||
};
|
||||
|
||||
OSGSkyNode::OSGSkyNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
|
||||
{
|
||||
qDebug() << "OSGSkyNode::OSGSkyNode";
|
||||
}
|
||||
|
||||
OSGSkyNode::~OSGSkyNode()
|
||||
{
|
||||
qDebug() << "OSGSkyNode::~OSGSkyNode";
|
||||
}
|
||||
|
||||
OSGNode *OSGSkyNode::sceneData()
|
||||
{
|
||||
return h->sceneData;
|
||||
}
|
||||
|
||||
void OSGSkyNode::setSceneData(OSGNode *node)
|
||||
{
|
||||
if (h->acceptSceneNode(node)) {
|
||||
emit sceneDataChanged(node);
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGSkyNode::sunLightEnabled()
|
||||
{
|
||||
return h->sunLightEnabled;
|
||||
}
|
||||
|
||||
void OSGSkyNode::setSunLightEnabled(bool arg)
|
||||
{
|
||||
if (h->acceptSunLightEnabled(arg)) {
|
||||
emit sunLightEnabledChanged(sunLightEnabled());
|
||||
}
|
||||
}
|
||||
|
||||
QDateTime OSGSkyNode::dateTime()
|
||||
{
|
||||
return h->dateTime;
|
||||
}
|
||||
|
||||
void OSGSkyNode::setDateTime(QDateTime arg)
|
||||
{
|
||||
if (h->acceptDateTime(arg)) {
|
||||
emit dateTimeChanged(dateTime());
|
||||
}
|
||||
}
|
||||
|
||||
double OSGSkyNode::minimumAmbientLight()
|
||||
{
|
||||
return h->minimumAmbientLight;
|
||||
}
|
||||
|
||||
void OSGSkyNode::setMinimumAmbientLight(double arg)
|
||||
{
|
||||
if (h->acceptMinimumAmbientLight(arg)) {
|
||||
emit minimumAmbientLightChanged(minimumAmbientLight());
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGSkyNode::attach(osgViewer::View *view)
|
||||
{
|
||||
return h->attach(view);
|
||||
}
|
||||
|
||||
bool OSGSkyNode::detach(osgViewer::View *view)
|
||||
{
|
||||
return h->detach(view);
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGSkyNode.moc"
|
@ -0,0 +1,58 @@
|
||||
#ifndef _H_OSGQTQUICK_SKYNODE_H_
|
||||
#define _H_OSGQTQUICK_SKYNODE_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
#include <QDateTime>
|
||||
#include <QUrl>
|
||||
|
||||
namespace osgViewer {
|
||||
class View;
|
||||
}
|
||||
|
||||
QT_BEGIN_NAMESPACE
|
||||
class QUrl;
|
||||
QT_END_NAMESPACE
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGQTQUICK_EXPORT OSGSkyNode : public OSGNode {
|
||||
Q_OBJECT Q_PROPERTY(osgQtQuick::OSGNode *sceneData READ sceneData WRITE setSceneData NOTIFY sceneDataChanged)
|
||||
|
||||
Q_PROPERTY(bool sunLightEnabled READ sunLightEnabled WRITE setSunLightEnabled NOTIFY sunLightEnabledChanged)
|
||||
Q_PROPERTY(QDateTime dateTime READ dateTime WRITE setDateTime NOTIFY dateTimeChanged)
|
||||
Q_PROPERTY(double minimumAmbientLight READ minimumAmbientLight WRITE setMinimumAmbientLight NOTIFY minimumAmbientLightChanged)
|
||||
|
||||
public:
|
||||
OSGSkyNode(QObject *parent = 0);
|
||||
virtual ~OSGSkyNode();
|
||||
|
||||
OSGNode *sceneData();
|
||||
void setSceneData(OSGNode *node);
|
||||
|
||||
bool sunLightEnabled();
|
||||
void setSunLightEnabled(bool arg);
|
||||
|
||||
QDateTime dateTime();
|
||||
void setDateTime(QDateTime arg);
|
||||
|
||||
double minimumAmbientLight();
|
||||
void setMinimumAmbientLight(double arg);
|
||||
|
||||
virtual bool attach(osgViewer::View *view);
|
||||
virtual bool detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void sceneDataChanged(OSGNode *node);
|
||||
|
||||
void sunLightEnabledChanged(bool arg);
|
||||
void dateTimeChanged(QDateTime arg);
|
||||
void minimumAmbientLightChanged(double arg);
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_SKYNODE_H_
|
@ -0,0 +1,89 @@
|
||||
#include "OSGTextNode.hpp"
|
||||
|
||||
#include "../utility.h"
|
||||
|
||||
#include <osgText/Text>
|
||||
#include <osg/Geode>
|
||||
#include <osg/Group>
|
||||
|
||||
#include <QFont>
|
||||
#include <QColor>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGTextNode::Hidden {
|
||||
public:
|
||||
osg::ref_ptr<osgText::Text> text;
|
||||
};
|
||||
|
||||
OSGTextNode::OSGTextNode(QObject *parent) :
|
||||
osgQtQuick::OSGNode(parent),
|
||||
h(new Hidden)
|
||||
{
|
||||
osg::ref_ptr<osgText::Font> textFont = createFont(QFont("Times"));
|
||||
|
||||
h->text = createText(osg::Vec3(-100, 20, 0),
|
||||
"The osgQtQuick :-)\n"
|
||||
"И даже по русски!",
|
||||
20.0f,
|
||||
textFont.get());
|
||||
osg::ref_ptr<osg::Geode> textGeode = new osg::Geode();
|
||||
h->text->setColor(osg::Vec4(0.0f, 1.0f, 0.0f, 1.0f));
|
||||
textGeode->addDrawable(h->text.get());
|
||||
#if 0
|
||||
h->text->setAutoRotateToScreen(true);
|
||||
setNode(textGeode.get());
|
||||
#else
|
||||
osg::Camera *camera = createHUDCamera(-100, 100, -100, 100);
|
||||
camera->addChild(textGeode.get());
|
||||
camera->getOrCreateStateSet()->setMode(
|
||||
GL_LIGHTING, osg::StateAttribute::OFF);
|
||||
setNode(camera);
|
||||
#endif
|
||||
}
|
||||
|
||||
OSGTextNode::~OSGTextNode()
|
||||
{
|
||||
delete h;
|
||||
}
|
||||
|
||||
QString OSGTextNode::text() const
|
||||
{
|
||||
return QString::fromUtf8(
|
||||
h->text->getText().createUTF8EncodedString().data());
|
||||
}
|
||||
|
||||
void OSGTextNode::setText(const QString &text)
|
||||
{
|
||||
std::string oldText = h->text->getText().createUTF8EncodedString();
|
||||
|
||||
if (text.toStdString() != oldText) {
|
||||
h->text->setText(text.toStdString(), osgText::String::ENCODING_UTF8);
|
||||
emit textChanged(text);
|
||||
}
|
||||
}
|
||||
|
||||
QColor OSGTextNode::color() const
|
||||
{
|
||||
const osg::Vec4 osgColor = h->text->getColor();
|
||||
|
||||
return QColor::fromRgbF(
|
||||
osgColor.r(),
|
||||
osgColor.g(),
|
||||
osgColor.b(),
|
||||
osgColor.a());
|
||||
}
|
||||
|
||||
void OSGTextNode::setColor(const QColor &color)
|
||||
{
|
||||
osg::Vec4 osgColor(
|
||||
color.redF(),
|
||||
color.greenF(),
|
||||
color.blueF(),
|
||||
color.alphaF());
|
||||
|
||||
if (h->text->getColor() != osgColor) {
|
||||
h->text->setColor(osgColor);
|
||||
emit colorChanged(color);
|
||||
}
|
||||
}
|
||||
} // namespace osgQtQuick
|
@ -0,0 +1,36 @@
|
||||
#ifndef _H_OSGQTQUICK_OSGTEXTNODE_H_
|
||||
#define _H_OSGQTQUICK_OSGTEXTNODE_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
#include <QColor>
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGQTQUICK_EXPORT OSGTextNode : public OSGNode {
|
||||
Q_OBJECT Q_PROPERTY(QString text READ text WRITE setText NOTIFY textChanged)
|
||||
Q_PROPERTY(QColor color READ color WRITE setColor NOTIFY colorChanged)
|
||||
|
||||
public:
|
||||
explicit OSGTextNode(QObject *parent = 0);
|
||||
virtual ~OSGTextNode();
|
||||
|
||||
QString text() const;
|
||||
void setText(const QString &text);
|
||||
|
||||
QColor color() const;
|
||||
void setColor(const QColor &color);
|
||||
|
||||
signals:
|
||||
void textChanged(const QString &text);
|
||||
void colorChanged(const QColor &color);
|
||||
|
||||
public slots:
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_OSGTEXTNODE_H_
|
@ -0,0 +1,208 @@
|
||||
#include "OSGTransformNode.hpp"
|
||||
|
||||
#include <osg/Quat>
|
||||
#include <osg/PositionAttitudeTransform>
|
||||
#include <osg/Math>
|
||||
|
||||
#include <QDebug>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGTransformNode::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
struct NodeUpdateCallback : public osg::NodeCallback {
|
||||
public:
|
||||
NodeUpdateCallback(Hidden *h) : h(h) {}
|
||||
|
||||
void operator()(osg::Node *node, osg::NodeVisitor *nv);
|
||||
|
||||
mutable Hidden *h;
|
||||
};
|
||||
friend class NodeUpdateCallback;
|
||||
|
||||
public:
|
||||
|
||||
Hidden(OSGTransformNode *parent) : QObject(parent), self(parent), modelData(NULL), dirty(false)
|
||||
{}
|
||||
|
||||
~Hidden()
|
||||
{}
|
||||
|
||||
bool acceptModelData(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGTransformNode::acceptModelData" << node;
|
||||
if (modelData == node) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (modelData) {
|
||||
disconnect(modelData);
|
||||
}
|
||||
|
||||
modelData = node;
|
||||
|
||||
if (modelData) {
|
||||
acceptNode(modelData->node());
|
||||
connect(modelData, SIGNAL(nodeChanged(osg::Node *)), this, SLOT(onNodeChanged(osg::Node *)));
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptNode(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGTransformNode::acceptNode" << node;
|
||||
if (!node) {
|
||||
qWarning() << "OSGTransformNode::acceptNode - node is null";
|
||||
return false;
|
||||
}
|
||||
|
||||
osg::Transform *transform = getOrCreateTransform();
|
||||
if (!transform) {
|
||||
qWarning() << "OSGTransformNode::acceptNode - transform is null";
|
||||
return false;
|
||||
}
|
||||
|
||||
transform->addChild(node);
|
||||
|
||||
self->setNode(transform);
|
||||
|
||||
dirty = true;
|
||||
updateNode();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
osg::Transform *getOrCreateTransform()
|
||||
{
|
||||
if (transform.valid()) {
|
||||
return transform.get();
|
||||
}
|
||||
|
||||
transform = new osg::PositionAttitudeTransform();
|
||||
|
||||
transform->addUpdateCallback(new NodeUpdateCallback(this));
|
||||
|
||||
return transform.get();
|
||||
}
|
||||
|
||||
void updateNode()
|
||||
{
|
||||
if (!dirty || !transform.valid()) {
|
||||
return;
|
||||
}
|
||||
dirty = false;
|
||||
|
||||
// scale
|
||||
if ((scale.x() != 0.0) || (scale.y() != 0.0) || (scale.z() != 0.0)) {
|
||||
transform->setScale(osg::Vec3d(scale.x(), scale.y(), scale.z()));
|
||||
// transform->getOrCreateStateSet()->setMode(GL_NORMALIZE, osg::StateAttribute::ON);
|
||||
transform->getOrCreateStateSet()->setMode(GL_RESCALE_NORMAL, osg::StateAttribute::ON);
|
||||
}
|
||||
|
||||
// rotate
|
||||
osg::Quat q = osg::Quat(
|
||||
osg::DegreesToRadians(rotate.x()), osg::Vec3d(1, 0, 0),
|
||||
osg::DegreesToRadians(rotate.y()), osg::Vec3d(0, 1, 0),
|
||||
osg::DegreesToRadians(rotate.z()), osg::Vec3d(0, 0, 1));
|
||||
transform->setAttitude(q);
|
||||
|
||||
// translate
|
||||
transform->setPosition(osg::Vec3d(translate.x(), translate.y(), translate.z()));
|
||||
}
|
||||
|
||||
OSGTransformNode *const self;
|
||||
|
||||
OSGNode *modelData;
|
||||
|
||||
osg::ref_ptr<osg::PositionAttitudeTransform> transform;
|
||||
|
||||
bool dirty;
|
||||
|
||||
QVector3D scale;
|
||||
QVector3D rotate;
|
||||
QVector3D translate;
|
||||
|
||||
private slots:
|
||||
|
||||
void onNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGTransformNode::onNodeChanged" << node;
|
||||
acceptNode(node);
|
||||
}
|
||||
};
|
||||
|
||||
/* struct Hidden::NodeUpdateCallback */
|
||||
|
||||
void OSGTransformNode::Hidden::NodeUpdateCallback::operator()(osg::Node *node, osg::NodeVisitor *nv)
|
||||
{
|
||||
h->updateNode();
|
||||
traverse(node, nv);
|
||||
}
|
||||
|
||||
OSGTransformNode::OSGTransformNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
|
||||
{
|
||||
qDebug() << "OSGTransformNode::OSGTransformNode";
|
||||
}
|
||||
|
||||
OSGTransformNode::~OSGTransformNode()
|
||||
{
|
||||
qDebug() << "OSGTransformNode::~OSGTransformNode";
|
||||
}
|
||||
|
||||
OSGNode *OSGTransformNode::modelData()
|
||||
{
|
||||
return h->modelData;
|
||||
}
|
||||
|
||||
void OSGTransformNode::setModelData(OSGNode *node)
|
||||
{
|
||||
if (h->acceptModelData(node)) {
|
||||
emit modelDataChanged(node);
|
||||
}
|
||||
}
|
||||
|
||||
QVector3D OSGTransformNode::scale() const
|
||||
{
|
||||
return h->scale;
|
||||
}
|
||||
|
||||
void OSGTransformNode::setScale(QVector3D arg)
|
||||
{
|
||||
if (h->scale != arg) {
|
||||
h->scale = arg;
|
||||
h->dirty = true;
|
||||
emit scaleChanged(scale());
|
||||
}
|
||||
}
|
||||
|
||||
QVector3D OSGTransformNode::rotate() const
|
||||
{
|
||||
return h->rotate;
|
||||
}
|
||||
|
||||
void OSGTransformNode::setRotate(QVector3D arg)
|
||||
{
|
||||
if (h->rotate != arg) {
|
||||
h->rotate = arg;
|
||||
h->dirty = true;
|
||||
emit rotateChanged(rotate());
|
||||
}
|
||||
}
|
||||
|
||||
QVector3D OSGTransformNode::translate() const
|
||||
{
|
||||
return h->translate;
|
||||
}
|
||||
|
||||
void OSGTransformNode::setTranslate(QVector3D arg)
|
||||
{
|
||||
if (h->translate != arg) {
|
||||
h->translate = arg;
|
||||
h->dirty = true;
|
||||
emit translateChanged(translate());
|
||||
}
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGTransformNode.moc"
|
@ -0,0 +1,49 @@
|
||||
#ifndef _H_OSGQTQUICK_TRANSFORMNODE_H_
|
||||
#define _H_OSGQTQUICK_TRANSFORMNODE_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
#include <QVector3D>
|
||||
|
||||
// TODO derive from OSGGroup...
|
||||
namespace osgQtQuick {
|
||||
class OSGQTQUICK_EXPORT OSGTransformNode : public OSGNode {
|
||||
Q_OBJECT
|
||||
// TODO rename to parentNode and modelNode
|
||||
Q_PROPERTY(osgQtQuick::OSGNode *modelData READ modelData WRITE setModelData NOTIFY modelDataChanged)
|
||||
|
||||
Q_PROPERTY(QVector3D scale READ scale WRITE setScale NOTIFY scaleChanged)
|
||||
Q_PROPERTY(QVector3D rotate READ rotate WRITE setRotate NOTIFY rotateChanged)
|
||||
Q_PROPERTY(QVector3D translate READ translate WRITE setTranslate NOTIFY translateChanged)
|
||||
|
||||
public:
|
||||
OSGTransformNode(QObject *parent = 0);
|
||||
virtual ~OSGTransformNode();
|
||||
|
||||
OSGNode *modelData();
|
||||
void setModelData(OSGNode *node);
|
||||
|
||||
QVector3D scale() const;
|
||||
void setScale(QVector3D arg);
|
||||
|
||||
QVector3D rotate() const;
|
||||
void setRotate(QVector3D arg);
|
||||
|
||||
QVector3D translate() const;
|
||||
void setTranslate(QVector3D arg);
|
||||
|
||||
signals:
|
||||
void modelDataChanged(OSGNode *node);
|
||||
|
||||
void scaleChanged(QVector3D arg);
|
||||
void rotateChanged(QVector3D arg);
|
||||
void translateChanged(QVector3D arg);
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_TRANSFORMNODE_H_
|
815
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGViewport.cpp
Normal file
815
ground/openpilotgcs/src/libs/osgearth/osgQtQuick/OSGViewport.cpp
Normal file
@ -0,0 +1,815 @@
|
||||
#include "OSGViewport.hpp"
|
||||
|
||||
#include "../osgearth.h"
|
||||
#include "../utility.h"
|
||||
|
||||
#include "OSGNode.hpp"
|
||||
#include "OSGCamera.hpp"
|
||||
|
||||
#include <osg/Node>
|
||||
#include <osg/DeleteHandler>
|
||||
#include <osg/GLObjects>
|
||||
#include <osg/ApplicationUsage>
|
||||
#include <osgDB/WriteFile>
|
||||
#include <osgViewer/CompositeViewer>
|
||||
#include <osgViewer/ViewerEventHandlers>
|
||||
#include <osgGA/StateSetManipulator>
|
||||
|
||||
#include <osgEarth/MapNode>
|
||||
#include <osgEarthUtil/AutoClipPlaneHandler>
|
||||
#include <osgEarthUtil/Sky>
|
||||
|
||||
#include <QOpenGLContext>
|
||||
#include <QQuickWindow>
|
||||
#include <QOpenGLFramebufferObject>
|
||||
#include <QSGSimpleTextureNode>
|
||||
#include <QOpenGLFunctions>
|
||||
|
||||
#include <QDebug>
|
||||
|
||||
#include <QThread>
|
||||
#include <QApplication>
|
||||
|
||||
namespace osgQtQuick {
|
||||
/*
|
||||
Debugging tips
|
||||
- export OSG_NOTIFY_LEVEL=DEBUG
|
||||
|
||||
|
||||
Z-fighting can happen with coincident polygons, but it can also happen when the Z buffer has insufficient resolution
|
||||
to represent the data in the scene. In the case where you are close up to an object (the helicopter)
|
||||
and also viewing a far-off object (the earth) the Z buffer has to stretch to accommodate them both.
|
||||
This can result in loss of precision and Z fighting.
|
||||
|
||||
Assuming you are not messing around with the near/far computations, and assuming you don't have any other objects
|
||||
in the scene that are farther off than the earth, there are a couple things you can try.
|
||||
|
||||
One, adjust the near/far ratio of the camera. Look at osgearth_viewer.cpp to see how.
|
||||
|
||||
Two, you can try to use the AutoClipPlaneHandler. You can install it automatically by running osgearth_viewer --autoclip.
|
||||
|
||||
If none of that works, you can try parenting your helicopter with an osg::Camera in NESTED mode,
|
||||
which will separate the clip plane calculations of the helicopter from those of the earth. *
|
||||
|
||||
TODO : add OSGView to handle multiple views for a given OSGViewport
|
||||
*/
|
||||
struct OSGViewport::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
|
||||
Hidden(OSGViewport *quickItem) : QObject(quickItem),
|
||||
self(quickItem),
|
||||
window(NULL),
|
||||
sceneData(NULL),
|
||||
camera(NULL),
|
||||
updateMode(Discrete),
|
||||
frameTimer(-1)
|
||||
{
|
||||
qDebug() << "OSGViewport::Hidden";
|
||||
|
||||
OsgEarth::initialize();
|
||||
|
||||
// workaround to avoid using GraphicsContext #0
|
||||
if (!dummy.valid()) {
|
||||
dummy = createGraphicsContext();
|
||||
}
|
||||
|
||||
createViewer();
|
||||
|
||||
connect(quickItem, &OSGViewport::windowChanged, this, &Hidden::onWindowChanged);
|
||||
}
|
||||
|
||||
~Hidden()
|
||||
{
|
||||
qDebug() << "OSGViewport::~Hidden";
|
||||
// osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "OSGViewport::~Hidden");
|
||||
|
||||
stop();
|
||||
|
||||
destroyViewer();
|
||||
}
|
||||
|
||||
public slots:
|
||||
void onWindowChanged(QQuickWindow *window)
|
||||
{
|
||||
qDebug() << "OSGViewport::onWindowChanged" << window;
|
||||
// osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "onWindowChanged");
|
||||
if (window) {
|
||||
// window->setClearBeforeRendering(false);
|
||||
connect(window, &QQuickWindow::sceneGraphInitialized, this, &Hidden::onSceneGraphInitialized, Qt::DirectConnection);
|
||||
connect(window, &QQuickWindow::sceneGraphAboutToStop, this, &Hidden::onSceneGraphAboutToStop, Qt::DirectConnection);
|
||||
connect(window, &QQuickWindow::sceneGraphInvalidated, this, &Hidden::onSceneGraphInvalidated, Qt::DirectConnection);
|
||||
} else {
|
||||
if (this->window) {
|
||||
disconnect(this->window);
|
||||
}
|
||||
}
|
||||
this->window = window;
|
||||
}
|
||||
public:
|
||||
|
||||
bool acceptSceneData(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGViewport::acceptSceneData" << node;
|
||||
if (sceneData == node) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if (sceneData) {
|
||||
disconnect(sceneData);
|
||||
}
|
||||
|
||||
sceneData = node;
|
||||
|
||||
if (sceneData) {
|
||||
acceptNode(sceneData->node());
|
||||
connect(sceneData, &OSGNode::nodeChanged, this, &Hidden::onNodeChanged);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptNode(osg::Node *node)
|
||||
{
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool attach(osgViewer::View *view)
|
||||
{
|
||||
if (!sceneData) {
|
||||
qWarning() << "OSGViewport::attach - invalid scene!";
|
||||
return false;
|
||||
}
|
||||
if (!attach(view, sceneData->node())) {
|
||||
qWarning() << "OSGViewport::attach - failed to attach node!";
|
||||
return false;
|
||||
}
|
||||
if (camera) {
|
||||
camera->setViewport(0, 0, self->width(), self->height());
|
||||
camera->attach(view);
|
||||
} else {
|
||||
qWarning() << "OSGViewport::attach - no camera!";
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool attach(osgViewer::View *view, osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGViewport::attach" << node;
|
||||
if (!view) {
|
||||
qWarning() << "OSGViewport::attach - view is null";
|
||||
return false;
|
||||
}
|
||||
if (!node) {
|
||||
qWarning() << "OSGViewport::attach - node is null";
|
||||
view->setSceneData(NULL);
|
||||
return true;
|
||||
}
|
||||
|
||||
// TODO map handling should not be done here
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(node);
|
||||
if (false && mapNode) {
|
||||
qDebug() << "OSGViewport::attach - found map node" << mapNode;
|
||||
// install AutoClipPlaneCullCallback : computes near/far planes based on scene geometry
|
||||
qDebug() << "OSGViewport::attach - set AutoClipPlaneCullCallback on camera";
|
||||
// TODO will the AutoClipPlaneCullCallback be destroyed ?
|
||||
// TODO does it need to be added to the map node or to the view ?
|
||||
cullCallback = new osgEarth::Util::AutoClipPlaneCullCallback(mapNode);
|
||||
//view->getCamera()->addCullCallback(cullCallback);
|
||||
mapNode->addCullCallback(cullCallback);
|
||||
}
|
||||
|
||||
//view->getCamera()->setSmallFeatureCullingPixelSize(-1.0f);
|
||||
|
||||
view->setSceneData(node);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool detach(osgViewer::View *view)
|
||||
{
|
||||
qDebug() << "OSGViewport::detach" << view;
|
||||
|
||||
if (camera) {
|
||||
camera->detach(view);
|
||||
}
|
||||
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(view->getSceneData());
|
||||
if (mapNode) {
|
||||
view->getCamera()->removeCullCallback(cullCallback);
|
||||
cullCallback = NULL;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void onSceneGraphInitialized()
|
||||
{
|
||||
qDebug() << "OSGViewport::onSceneGraphInitialized";
|
||||
// osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "onSceneGraphInitialized");
|
||||
}
|
||||
|
||||
void onSceneGraphAboutToStop()
|
||||
{
|
||||
qDebug() << "OSGViewport::onSceneGraphAboutToStop";
|
||||
// osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "onSceneGraphAboutToStop");
|
||||
}
|
||||
|
||||
void onSceneGraphInvalidated()
|
||||
{
|
||||
qDebug() << "OSGViewport::onSceneGraphInvalidated";
|
||||
// osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "onSceneGraphInvalidated");
|
||||
}
|
||||
|
||||
void initializeResources()
|
||||
{
|
||||
qDebug() << "OSGViewport::initializeResources";
|
||||
if (!view.valid()) {
|
||||
qDebug() << "OSGViewport::initializeResources - creating view";
|
||||
view = createView();
|
||||
self->attach(view.get());
|
||||
viewer->addView(view);
|
||||
start();
|
||||
// osgDB::writeNodeFile(*(h->self->sceneData()->node()), "saved.osg");
|
||||
}
|
||||
}
|
||||
|
||||
void releaseResources()
|
||||
{
|
||||
qDebug() << "OSGViewport::releaseResources";
|
||||
if (!view.valid()) {
|
||||
qWarning() << "OSGViewport::releaseResources - view is not valid!";
|
||||
return;
|
||||
}
|
||||
osg::deleteAllGLObjects(view->getCamera()->getGraphicsContext()->getState()->getContextID());
|
||||
// view->getSceneData()->releaseGLObjects(view->getCamera()->getGraphicsContext()->getState());
|
||||
// view->getCamera()->releaseGLObjects(view->getCamera()->getGraphicsContext()->getState());
|
||||
// view->getCamera()->getGraphicsContext()->close();
|
||||
// view->getCamera()->setGraphicsContext(NULL);
|
||||
}
|
||||
|
||||
bool acceptUpdateMode(OSGViewport::UpdateMode mode)
|
||||
{
|
||||
// qDebug() << "OSGViewport::acceptUpdateMode" << mode;
|
||||
if (updateMode == mode) {
|
||||
return true;
|
||||
}
|
||||
|
||||
updateMode = mode;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptCamera(OSGCamera *camera)
|
||||
{
|
||||
qDebug() << "OSGViewport::acceptCamera" << camera;
|
||||
if (this->camera == camera) {
|
||||
return true;
|
||||
}
|
||||
|
||||
this->camera = camera;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
OSGViewport *self;
|
||||
|
||||
QQuickWindow *window;
|
||||
|
||||
OSGNode *sceneData;
|
||||
OSGCamera *camera;
|
||||
|
||||
OSGViewport::UpdateMode updateMode;
|
||||
|
||||
int frameTimer;
|
||||
|
||||
osg::ref_ptr<osgViewer::CompositeViewer> viewer;
|
||||
osg::ref_ptr<osgViewer::View> view;
|
||||
|
||||
osg::ref_ptr<osg::NodeCallback> cullCallback;
|
||||
|
||||
static osg::ref_ptr<osg::GraphicsContext> dummy;
|
||||
|
||||
static QtKeyboardMap keyMap;
|
||||
|
||||
void createViewer()
|
||||
{
|
||||
if (viewer.valid()) {
|
||||
qWarning() << "OSGViewport::createViewer - viewer is valid";
|
||||
return;
|
||||
}
|
||||
|
||||
qDebug() << "OSGViewport::createViewer";
|
||||
|
||||
viewer = new osgViewer::CompositeViewer();
|
||||
viewer->setThreadingModel(osgViewer::ViewerBase::SingleThreaded);
|
||||
|
||||
osg::ref_ptr<osgUtil::IncrementalCompileOperation> ico = new osgUtil::IncrementalCompileOperation();
|
||||
ico->setTargetFrameRate(30.0f);
|
||||
viewer->setIncrementalCompileOperation(ico);
|
||||
|
||||
// disable the default setting of viewer.done() by pressing Escape.
|
||||
viewer->setKeyEventSetsDone(0);
|
||||
// viewer->setQuitEventSetsDone(false);
|
||||
}
|
||||
|
||||
void destroyViewer()
|
||||
{
|
||||
if (!viewer.valid()) {
|
||||
qWarning() << "OSGViewport::destroyViewer - viewer is not valid";
|
||||
return;
|
||||
}
|
||||
|
||||
qDebug() << "OSGViewport::destroyViewer";
|
||||
|
||||
viewer = NULL;
|
||||
}
|
||||
|
||||
osgViewer::View *createView()
|
||||
{
|
||||
qWarning() << "OSGViewport::createView";
|
||||
osgViewer::View *view = new osgViewer::View();
|
||||
|
||||
// TODO will the handlers be destroyed???
|
||||
// add the state manipulator
|
||||
view->addEventHandler(new osgGA::StateSetManipulator(view->getCamera()->getOrCreateStateSet()));
|
||||
// b : Toggle Backface Culling, l : Toggle Lighting, t : Toggle Texturing, w : Cycle Polygon Mode
|
||||
|
||||
// add the thread model handler
|
||||
// view->addEventHandler(new osgViewer::ThreadingHandler);
|
||||
|
||||
// add the window size toggle handler
|
||||
// view->addEventHandler(new osgViewer::WindowSizeHandler);
|
||||
|
||||
// add the stats handler
|
||||
view->addEventHandler(new osgViewer::StatsHandler);
|
||||
|
||||
// add the help handler
|
||||
// view->addEventHandler(new osgViewer::HelpHandler(arguments.getApplicationUsage()));
|
||||
|
||||
// add the record camera path handler
|
||||
// view->addEventHandler(new osgViewer::RecordCameraPathHandler);
|
||||
|
||||
// add the LOD Scale handler
|
||||
// view->addEventHandler(new osgViewer::LODScaleHandler);
|
||||
|
||||
// add the screen capture handler
|
||||
// view->addEventHandler(new osgViewer::ScreenCaptureHandler);
|
||||
|
||||
view->getCamera()->setGraphicsContext(createGraphicsContext());
|
||||
|
||||
return view;
|
||||
}
|
||||
|
||||
osg::GraphicsContext *createGraphicsContext()
|
||||
{
|
||||
qWarning() << "OSGViewport::createGraphicsContext";
|
||||
|
||||
osg::GraphicsContext::Traits *traits = getTraits();
|
||||
// traitsInfo(*traits);
|
||||
|
||||
traits->pbuffer = true;
|
||||
osg::GraphicsContext *graphicsContext = osg::GraphicsContext::createGraphicsContext(traits);
|
||||
// if (!graphicsContext) {
|
||||
// qWarning() << "Failed to create pbuffer, failing back to normal graphics window.";
|
||||
// traits->pbuffer = false;
|
||||
// graphicsContext = osg::GraphicsContext::createGraphicsContext(traits);
|
||||
// }
|
||||
|
||||
return graphicsContext;
|
||||
}
|
||||
|
||||
osg::GraphicsContext::Traits *getTraits()
|
||||
{
|
||||
osg::DisplaySettings *ds = osg::DisplaySettings::instance().get();
|
||||
osg::GraphicsContext::Traits *traits = new osg::GraphicsContext::Traits(ds);
|
||||
|
||||
// traitsInfo(traits);
|
||||
|
||||
// traits->readDISPLAY();
|
||||
// if (traits->displayNum < 0) {
|
||||
// traits->displayNum = 0;
|
||||
// }
|
||||
|
||||
traits->windowDecoration = false;
|
||||
traits->x = 0;
|
||||
traits->y = 0;
|
||||
traits->width = self->width();
|
||||
traits->height = self->height();
|
||||
|
||||
traits->alpha = ds->getMinimumNumAlphaBits();
|
||||
traits->stencil = ds->getMinimumNumStencilBits();
|
||||
traits->sampleBuffers = ds->getMultiSamples();
|
||||
traits->samples = ds->getNumMultiSamples();
|
||||
|
||||
traits->doubleBuffer = false; //ds->getDoubleBuffer();
|
||||
traits->vsync = false;
|
||||
// traits->sharedContext = gc;
|
||||
// traits->inheritedWindowData = new osgQt::GraphicsWindowQt::WindowData(this);
|
||||
|
||||
return traits;
|
||||
}
|
||||
|
||||
void start()
|
||||
{
|
||||
if (updateMode == OSGViewport::Discrete && (frameTimer < 0)) {
|
||||
qDebug() << "OSGViewport::start - starting timer";
|
||||
frameTimer = startTimer(33, Qt::PreciseTimer);
|
||||
}
|
||||
}
|
||||
|
||||
void stop()
|
||||
{
|
||||
if (frameTimer >= 0) {
|
||||
qDebug() << "OSGViewport::stop - killing timer";
|
||||
killTimer(frameTimer);
|
||||
frameTimer = -1;
|
||||
}
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
void timerEvent(QTimerEvent *event)
|
||||
{
|
||||
if (event->timerId() == frameTimer) {
|
||||
if (self) {
|
||||
self->update();
|
||||
}
|
||||
}
|
||||
QObject::timerEvent(event);
|
||||
}
|
||||
|
||||
|
||||
private slots:
|
||||
|
||||
void onNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGViewport::onNodeChanged" << node;
|
||||
qWarning() << "OSGViewport::onNodeChanged - not implemented";
|
||||
// if (view.valid()) {
|
||||
// acceptNode(node);
|
||||
// }
|
||||
}
|
||||
};
|
||||
|
||||
/* class ViewportRenderer */
|
||||
|
||||
class ViewportRenderer : public QQuickFramebufferObject::Renderer {
|
||||
public:
|
||||
ViewportRenderer(OSGViewport::Hidden *h) : h(h)
|
||||
{
|
||||
qDebug() << "ViewportRenderer::ViewportRenderer";
|
||||
osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "ViewportRenderer::ViewportRenderer");
|
||||
|
||||
h->initializeResources();
|
||||
|
||||
requestRedraw = false;
|
||||
}
|
||||
|
||||
~ViewportRenderer()
|
||||
{
|
||||
qDebug() << "ViewportRenderer::~ViewportRenderer";
|
||||
osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "ViewportRenderer::~ViewportRenderer");
|
||||
|
||||
h->releaseResources();
|
||||
}
|
||||
|
||||
// This function is the only place when it is safe for the renderer and the item to read and write each others members.
|
||||
void synchronize(QQuickFramebufferObject *item)
|
||||
{
|
||||
// qDebug() << "ViewportRenderer::synchronize";
|
||||
// osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "ViewportRenderer::synchronize");
|
||||
|
||||
if (!h->view.valid()) {
|
||||
qWarning() << "ViewportRenderer::synchronize - invalid view";
|
||||
return;
|
||||
}
|
||||
|
||||
// need to split frame() open and do the synchronization here (calling update callbacks, etc...)
|
||||
}
|
||||
|
||||
// This function is called when the FBO should be rendered into.
|
||||
// The framebuffer is bound at this point and the glViewport has been set up to match the FBO size.
|
||||
void render()
|
||||
{
|
||||
// qDebug() << "ViewportRenderer::render";
|
||||
// osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "ViewportRenderer::render");
|
||||
|
||||
if (!h->viewer.valid()) {
|
||||
qWarning() << "ViewportRenderer::render - invalid viewport";
|
||||
return;
|
||||
}
|
||||
|
||||
// needed to properly render models without terrain (Qt bug?)
|
||||
QOpenGLContext::currentContext()->functions()->glUseProgram(0);
|
||||
|
||||
if (checkNeedToDoFrame()) {
|
||||
// TODO scene update should NOT be done here
|
||||
h->viewer->frame();
|
||||
requestRedraw = false;
|
||||
}
|
||||
|
||||
//h->self->window()->resetOpenGLState();
|
||||
|
||||
if (h->updateMode == OSGViewport::Continuous) {
|
||||
// trigger next update
|
||||
update();
|
||||
}
|
||||
}
|
||||
|
||||
QOpenGLFramebufferObject *createFramebufferObject(const QSize &size)
|
||||
{
|
||||
qDebug() << "ViewportRenderer::createFramebufferObject" << size;
|
||||
if (h->camera) {
|
||||
h->camera->setViewport(0, 0, size.width(), size.height());
|
||||
}
|
||||
|
||||
QOpenGLFramebufferObjectFormat format;
|
||||
format.setAttachment(QOpenGLFramebufferObject::CombinedDepthStencil);
|
||||
// format.setSamples(4);
|
||||
int dpr = h->self->window()->devicePixelRatio();
|
||||
QOpenGLFramebufferObject *fbo = new QOpenGLFramebufferObject(size.width() / dpr, size.height() / dpr, format);
|
||||
|
||||
return fbo;
|
||||
}
|
||||
|
||||
private:
|
||||
bool checkNeedToDoFrame()
|
||||
{
|
||||
// if (requestRedraw) {
|
||||
// return true;
|
||||
// }
|
||||
// if (getDatabasePager()->requiresUpdateSceneGraph() || getDatabasePager()->getRequestsInProgress()) {
|
||||
// return true;
|
||||
// }
|
||||
return true;
|
||||
}
|
||||
|
||||
OSGViewport::Hidden *h;
|
||||
|
||||
bool requestRedraw;
|
||||
};
|
||||
|
||||
osg::ref_ptr<osg::GraphicsContext> OSGViewport::Hidden::dummy;
|
||||
QtKeyboardMap OSGViewport::Hidden::keyMap = QtKeyboardMap();
|
||||
|
||||
/* class OSGViewport */
|
||||
|
||||
|
||||
OSGViewport::OSGViewport(QQuickItem *parent) : QQuickFramebufferObject(parent), h(new Hidden(this))
|
||||
{
|
||||
qDebug() << "OSGViewport::OSGViewport";
|
||||
// setClearBeforeRendering(false);
|
||||
setAcceptHoverEvents(true);
|
||||
setAcceptedMouseButtons(Qt::AllButtons);
|
||||
}
|
||||
|
||||
OSGViewport::~OSGViewport()
|
||||
{
|
||||
qDebug() << "OSGViewport::~OSGViewport";
|
||||
}
|
||||
|
||||
OSGViewport::UpdateMode OSGViewport::updateMode() const
|
||||
{
|
||||
return h->updateMode;
|
||||
}
|
||||
|
||||
void OSGViewport::setUpdateMode(OSGViewport::UpdateMode mode)
|
||||
{
|
||||
if (h->acceptUpdateMode(mode)) {
|
||||
emit updateModeChanged(updateMode());
|
||||
}
|
||||
}
|
||||
|
||||
QColor OSGViewport::color() const
|
||||
{
|
||||
const osg::Vec4 osgColor = h->view->getCamera()->getClearColor();
|
||||
|
||||
return QColor::fromRgbF(osgColor.r(), osgColor.g(), osgColor.b(), osgColor.a());
|
||||
}
|
||||
|
||||
void OSGViewport::setColor(const QColor &color)
|
||||
{
|
||||
osg::Vec4 osgColor(color.redF(), color.greenF(), color.blueF(), color.alphaF());
|
||||
|
||||
if (h->view->getCamera()->getClearColor() != osgColor) {
|
||||
h->view->getCamera()->setClearColor(osgColor);
|
||||
emit colorChanged(color);
|
||||
}
|
||||
}
|
||||
|
||||
OSGNode *OSGViewport::sceneData()
|
||||
{
|
||||
return h->sceneData;
|
||||
}
|
||||
|
||||
void OSGViewport::setSceneData(OSGNode *node)
|
||||
{
|
||||
if (h->acceptSceneData(node)) {
|
||||
emit sceneDataChanged(node);
|
||||
}
|
||||
}
|
||||
|
||||
OSGCamera *OSGViewport::camera()
|
||||
{
|
||||
return h->camera;
|
||||
}
|
||||
|
||||
void OSGViewport::setCamera(OSGCamera *camera)
|
||||
{
|
||||
if (h->acceptCamera(camera)) {
|
||||
emit cameraChanged(camera);
|
||||
}
|
||||
}
|
||||
|
||||
QQuickFramebufferObject::Renderer *OSGViewport::createRenderer() const
|
||||
{
|
||||
qDebug() << "OSGViewport::createRenderer";
|
||||
osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "createRenderer");
|
||||
return new ViewportRenderer(h);
|
||||
}
|
||||
|
||||
bool OSGViewport::attach(osgViewer::View *view)
|
||||
{
|
||||
qDebug() << "OSGViewport::attach" << view;
|
||||
|
||||
h->attach(view);
|
||||
|
||||
QListIterator<QObject *> i(children());
|
||||
while (i.hasNext()) {
|
||||
QObject *object= i.next();
|
||||
OSGNode *node = qobject_cast<OSGNode *>(object);
|
||||
if (node) {
|
||||
qDebug() << "OSGViewport::attach - child" << node;
|
||||
node->attach(view);
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool OSGViewport::detach(osgViewer::View *view)
|
||||
{
|
||||
qDebug() << "OSGViewport::detach" << view;
|
||||
|
||||
QListIterator<QObject *> i(children());
|
||||
while (i.hasNext()) {
|
||||
QObject *object= i.next();
|
||||
OSGNode *node = qobject_cast<OSGNode *>(object);
|
||||
if (node) {
|
||||
node->detach(view);
|
||||
}
|
||||
}
|
||||
|
||||
h->detach(view);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void OSGViewport::releaseResources()
|
||||
{
|
||||
QQuickFramebufferObject::releaseResources();
|
||||
}
|
||||
|
||||
// see https://bugreports.qt-project.org/browse/QTBUG-41073
|
||||
QSGNode *OSGViewport::updatePaintNode(QSGNode *node, QQuickItem::UpdatePaintNodeData *nodeData)
|
||||
{
|
||||
// qDebug() << "OSGViewport::updatePaintNode";
|
||||
if (!node) {
|
||||
qDebug() << "OSGViewport::updatePaintNode - set transform";
|
||||
node = QQuickFramebufferObject::updatePaintNode(node, nodeData);
|
||||
QSGSimpleTextureNode *n = static_cast<QSGSimpleTextureNode *>(node);
|
||||
if (n) {
|
||||
// flip Y axis
|
||||
n->setTextureCoordinatesTransform(QSGSimpleTextureNode::MirrorVertically);
|
||||
}
|
||||
return node;
|
||||
}
|
||||
return QQuickFramebufferObject::updatePaintNode(node, nodeData);
|
||||
}
|
||||
|
||||
|
||||
QPointF OSGViewport::mousePoint(QMouseEvent *event)
|
||||
{
|
||||
// qreal x = 0.01 * (event->x() - self->width() / 2);
|
||||
// qreal y = 0.01 * (event->y() - self->height() / 2);
|
||||
qreal x = 2.0 * (event->x() - width() / 2) / width();
|
||||
qreal y = 2.0 * (event->y() - height() / 2) / height();
|
||||
|
||||
return QPointF(x, y);
|
||||
}
|
||||
|
||||
void OSGViewport::mousePressEvent(QMouseEvent *event)
|
||||
{
|
||||
int button = 0;
|
||||
|
||||
switch (event->button()) {
|
||||
case Qt::LeftButton: button = 1; break;
|
||||
case Qt::MidButton: button = 2; break;
|
||||
case Qt::RightButton: button = 3; break;
|
||||
case Qt::NoButton: button = 0; break;
|
||||
default: button = 0; break;
|
||||
}
|
||||
setKeyboardModifiers(event);
|
||||
QPointF pos = mousePoint(event);
|
||||
if (h->view.valid()) {
|
||||
h->view.get()->getEventQueue()->mouseButtonPress(pos.x(), pos.y(), button);
|
||||
}
|
||||
}
|
||||
|
||||
void OSGViewport::setKeyboardModifiers(QInputEvent *event)
|
||||
{
|
||||
int modkey = event->modifiers() & (Qt::ShiftModifier | Qt::ControlModifier | Qt::AltModifier);
|
||||
unsigned int mask = 0;
|
||||
|
||||
if (modkey & Qt::ShiftModifier) {
|
||||
mask |= osgGA::GUIEventAdapter::MODKEY_SHIFT;
|
||||
}
|
||||
if (modkey & Qt::ControlModifier) {
|
||||
mask |= osgGA::GUIEventAdapter::MODKEY_CTRL;
|
||||
}
|
||||
if (modkey & Qt::AltModifier) {
|
||||
mask |= osgGA::GUIEventAdapter::MODKEY_ALT;
|
||||
}
|
||||
if (h->view.valid()) {
|
||||
h->view.get()->getEventQueue()->getCurrentEventState()->setModKeyMask(mask);
|
||||
}
|
||||
}
|
||||
|
||||
void OSGViewport::mouseMoveEvent(QMouseEvent *event)
|
||||
{
|
||||
setKeyboardModifiers(event);
|
||||
QPointF pos = mousePoint(event);
|
||||
if (h->view.valid()) {
|
||||
h->view.get()->getEventQueue()->mouseMotion(pos.x(), pos.y());
|
||||
}
|
||||
}
|
||||
|
||||
void OSGViewport::mouseReleaseEvent(QMouseEvent *event)
|
||||
{
|
||||
int button = 0;
|
||||
|
||||
switch (event->button()) {
|
||||
case Qt::LeftButton: button = 1; break;
|
||||
case Qt::MidButton: button = 2; break;
|
||||
case Qt::RightButton: button = 3; break;
|
||||
case Qt::NoButton: button = 0; break;
|
||||
default: button = 0; break;
|
||||
}
|
||||
setKeyboardModifiers(event);
|
||||
QPointF pos = mousePoint(event);
|
||||
if (h->view.valid()) {
|
||||
h->view.get()->getEventQueue()->mouseButtonRelease(pos.x(), pos.y(), button);
|
||||
}
|
||||
}
|
||||
|
||||
void OSGViewport::wheelEvent(QWheelEvent *event)
|
||||
{
|
||||
osgGA::GUIEventAdapter::ScrollingMotion motion =
|
||||
event->orientation() == Qt::Vertical ?
|
||||
(event->delta() > 0 ? osgGA::GUIEventAdapter::SCROLL_UP : osgGA::GUIEventAdapter::SCROLL_DOWN) :
|
||||
(event->delta() > 0 ? osgGA::GUIEventAdapter::SCROLL_LEFT : osgGA::GUIEventAdapter::SCROLL_RIGHT);
|
||||
|
||||
if (h->view.valid()) {
|
||||
h->view.get()->getEventQueue()->mouseScroll(motion);
|
||||
}
|
||||
}
|
||||
|
||||
void OSGViewport::keyPressEvent(QKeyEvent *event)
|
||||
{
|
||||
setKeyboardModifiers(event);
|
||||
int value = h->keyMap.remapKey(event);
|
||||
if (h->view.valid()) {
|
||||
h->view.get()->getEventQueue()->keyPress(value);
|
||||
}
|
||||
|
||||
// this passes the event to the regular Qt key event processing,
|
||||
// among others, it closes popup windows on ESC and forwards the event to the parent widgets
|
||||
// TODO implement
|
||||
// if( _forwardKeyEvents )
|
||||
// inherited::keyPressEvent( event );
|
||||
}
|
||||
|
||||
void OSGViewport::keyReleaseEvent(QKeyEvent *event)
|
||||
{
|
||||
if (event->isAutoRepeat()) {
|
||||
event->ignore();
|
||||
} else {
|
||||
setKeyboardModifiers(event);
|
||||
int value = h->keyMap.remapKey(event);
|
||||
if (h->view.valid()) {
|
||||
h->view.get()->getEventQueue()->keyRelease(value);
|
||||
}
|
||||
}
|
||||
|
||||
// this passes the event to the regular Qt key event processing,
|
||||
// among others, it closes popup windows on ESC and forwards the event to the parent widgets
|
||||
// TODO implement
|
||||
// if( _forwardKeyEvents )
|
||||
// inherited::keyReleaseEvent( event );
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGViewport.moc"
|
@ -0,0 +1,82 @@
|
||||
#ifndef _H_OSGQTQUICK_OSGVIEPORT_H_
|
||||
#define _H_OSGQTQUICK_OSGVIEPORT_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
|
||||
#include <QQuickFramebufferObject>
|
||||
|
||||
namespace osgViewer {
|
||||
class View;
|
||||
}
|
||||
|
||||
namespace osgQtQuick {
|
||||
class Renderer;
|
||||
class OSGNode;
|
||||
class OSGCamera;
|
||||
|
||||
class OSGQTQUICK_EXPORT OSGViewport : public QQuickFramebufferObject {
|
||||
Q_OBJECT Q_PROPERTY(QColor color READ color WRITE setColor NOTIFY colorChanged)
|
||||
Q_PROPERTY(UpdateMode updateMode READ updateMode WRITE setUpdateMode NOTIFY updateModeChanged)
|
||||
Q_PROPERTY(osgQtQuick::OSGNode * sceneData READ sceneData WRITE setSceneData NOTIFY sceneDataChanged)
|
||||
Q_PROPERTY(osgQtQuick::OSGCamera * camera READ camera WRITE setCamera NOTIFY cameraChanged)
|
||||
|
||||
Q_ENUMS(UpdateMode)
|
||||
|
||||
public:
|
||||
|
||||
friend class ViewportRenderer;
|
||||
|
||||
// TODO rename to UpdateMode or something better
|
||||
enum UpdateMode {
|
||||
Continuous,
|
||||
Discrete,
|
||||
OnDemand
|
||||
};
|
||||
|
||||
explicit OSGViewport(QQuickItem *parent = 0);
|
||||
virtual ~OSGViewport();
|
||||
|
||||
UpdateMode updateMode() const;
|
||||
void setUpdateMode(UpdateMode mode);
|
||||
|
||||
QColor color() const;
|
||||
void setColor(const QColor &color);
|
||||
|
||||
OSGNode *sceneData();
|
||||
void setSceneData(OSGNode *node);
|
||||
|
||||
OSGCamera *camera();
|
||||
void setCamera(OSGCamera *camera);
|
||||
|
||||
virtual Renderer *createRenderer() const;
|
||||
virtual void releaseResources();
|
||||
|
||||
virtual bool attach(osgViewer::View *view);
|
||||
virtual bool detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void updateModeChanged(UpdateMode mode);
|
||||
void colorChanged(const QColor &color);
|
||||
void sceneDataChanged(OSGNode *node);
|
||||
void cameraChanged(OSGCamera *camera);
|
||||
|
||||
protected:
|
||||
void mousePressEvent(QMouseEvent *event);
|
||||
void mouseMoveEvent(QMouseEvent *event);
|
||||
void mouseReleaseEvent(QMouseEvent *event);
|
||||
void wheelEvent(QWheelEvent *event);
|
||||
void keyPressEvent(QKeyEvent *event);
|
||||
void keyReleaseEvent(QKeyEvent *event);
|
||||
|
||||
void setKeyboardModifiers(QInputEvent *event);
|
||||
QPointF mousePoint(QMouseEvent *event);
|
||||
|
||||
QSGNode *updatePaintNode(QSGNode *oldNode, UpdatePaintNodeData *updatePaintNodeData);
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_OSGVIEPORT_H_
|
236
ground/openpilotgcs/src/libs/osgearth/osgearth.cpp
Normal file
236
ground/openpilotgcs/src/libs/osgearth/osgearth.cpp
Normal file
@ -0,0 +1,236 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file osgearth.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief osgearth utilities
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "osgearth.h"
|
||||
|
||||
#include "utility.h"
|
||||
#include "qtwindowingsystem.h"
|
||||
|
||||
#include "utils/gcsdirs.h"
|
||||
#include "utils/pathutils.h"
|
||||
|
||||
#include <osg/DisplaySettings>
|
||||
#include <osg/GraphicsContext>
|
||||
#include <osg/Version>
|
||||
#include <osg/Notify>
|
||||
#include <osgDB/Registry>
|
||||
|
||||
#include <osgEarth/Version>
|
||||
#include <osgEarth/Cache>
|
||||
#include <osgEarth/Capabilities>
|
||||
#include <osgEarth/Registry>
|
||||
#include <osgEarthDrivers/cache_filesystem/FileSystemCache>
|
||||
|
||||
#include <QDebug>
|
||||
|
||||
#ifdef OSG_USE_QT_PRIVATE
|
||||
#include <QtGui/private/qguiapplication_p.h>
|
||||
#include <QtGui/qpa/qplatformintegration.h>
|
||||
#endif
|
||||
|
||||
#include <deque>
|
||||
|
||||
bool OsgEarth::registered = false;
|
||||
bool OsgEarth::initialized = false;
|
||||
|
||||
class OSGEARTH_LIB_EXPORT QtNotifyHandler : public osg::NotifyHandler {
|
||||
public:
|
||||
void notify(osg::NotifySeverity severity, const char *message);
|
||||
};
|
||||
|
||||
void OsgEarth::registerQmlTypes()
|
||||
{
|
||||
// TOOO not thread safe...
|
||||
if (registered) {
|
||||
return;
|
||||
}
|
||||
registered = true;
|
||||
|
||||
// initialize();
|
||||
|
||||
// Register Qml types
|
||||
osgQtQuick::registerTypes("osgQtQuick");
|
||||
}
|
||||
|
||||
void OsgEarth::initialize()
|
||||
{
|
||||
// TOOO not thread safe...
|
||||
if (initialized) {
|
||||
return;
|
||||
}
|
||||
initialized = true;
|
||||
|
||||
qDebug() << "OsgEarth::initialize - initializing osgearth...";
|
||||
|
||||
// increase cache (default is 300);
|
||||
//setenv("OSG_MAX_PAGEDLOD", "500", 0);
|
||||
|
||||
//setenv("OSG_ASSIGN_PBO_TO_IMAGES", "on", 0);
|
||||
|
||||
// Number of threads in the DatbasePager set up, inclusive of the number of http dedicated threads.
|
||||
osg::DisplaySettings::instance()->setNumOfDatabaseThreadsHint(6);
|
||||
osg::DisplaySettings::instance()->setNumOfHttpDatabaseThreadsHint(3);
|
||||
|
||||
initializePathes();
|
||||
|
||||
initWindowingSystem();
|
||||
|
||||
initializeCache();
|
||||
|
||||
// force early initialization of osgEarth capabilities
|
||||
// Doing this too early (before main window is displayed) causes rendering glitches (black holes)
|
||||
// Not sure why... See OSGViewport for when it is called (late...)
|
||||
osgEarth::Registry::capabilities();
|
||||
|
||||
displayInfo();
|
||||
}
|
||||
|
||||
void OsgEarth::initializePathes()
|
||||
{
|
||||
// initialize data file path list
|
||||
osgDB::FilePathList &dataFilePathList = osgDB::Registry::instance()->getDataFilePathList();
|
||||
|
||||
dataFilePathList.push_front(GCSDirs::sharePath("osgearth").toStdString());
|
||||
dataFilePathList.push_front(GCSDirs::sharePath("osgearth/data").toStdString());
|
||||
|
||||
// initialize library file path list
|
||||
osgDB::FilePathList &libraryFilePathList = osgDB::Registry::instance()->getLibraryFilePathList();
|
||||
libraryFilePathList.push_front(GCSDirs::libraryPath("osg").toStdString());
|
||||
}
|
||||
|
||||
void OsgEarth::initializeCache()
|
||||
{
|
||||
QString cachePath = Utils::GetStoragePath() + "osgearth/cache";
|
||||
|
||||
osgEarth::Drivers::FileSystemCacheOptions cacheOptions;
|
||||
|
||||
cacheOptions.rootPath() = cachePath.toStdString();
|
||||
|
||||
osg::ref_ptr<osgEarth::Cache> cache = osgEarth::CacheFactory::create(cacheOptions);
|
||||
if (cache->isOK()) {
|
||||
// set cache
|
||||
osgEarth::Registry::instance()->setCache(cache.get());
|
||||
|
||||
// set cache policy
|
||||
const osgEarth::CachePolicy cachePolicy(osgEarth::CachePolicy::USAGE_READ_WRITE);
|
||||
|
||||
// The default cache policy used when no policy is set elsewhere
|
||||
osgEarth::Registry::instance()->setDefaultCachePolicy(cachePolicy);
|
||||
// The override cache policy (overrides all others if set)
|
||||
// osgEarth::Registry::instance()->setOverrideCachePolicy(cachePolicy);
|
||||
} else {
|
||||
qWarning() << "OsgEarth::initializeCache - Failed to initialize cache";
|
||||
}
|
||||
|
||||
// osgDB::SharedStateManager::ShareMode shareMode = osgDB::SharedStateManager::SHARE_NONE;// =osgDB::SharedStateManager::SHARE_ALL;
|
||||
// shareMode = true ? static_cast<osgDB::SharedStateManager::ShareMode>(shareMode | osgDB::SharedStateManager::SHARE_STATESETS) : shareMode;
|
||||
// shareMode = true ? static_cast<osgDB::SharedStateManager::ShareMode>(shareMode | osgDB::SharedStateManager::SHARE_TEXTURES) : shareMode;
|
||||
// osgDB::Registry::instance()->getOrCreateSharedStateManager()->setShareMode(shareMode);
|
||||
|
||||
// osgDB::Options::CacheHintOptions cacheHintOptions = osgDB::Options::CACHE_NONE;
|
||||
// cacheHintOptions = static_cast<osgDB::Options::CacheHintOptions>(cacheHintOptions | osgDB::Options::CACHE_IMAGES);
|
||||
// cacheHintOptions = static_cast<osgDB::Options::CacheHintOptions>(cacheHintOptions | osgDB::Options::CACHE_NODES);
|
||||
// if (osgDB::Registry::instance()->getOptions() == 0) {
|
||||
// osgDB::Registry::instance()->setOptions(new osgDB::Options());
|
||||
// }
|
||||
// osgDB::Registry::instance()->getOptions()->setObjectCacheHint(cacheHintOptions);
|
||||
}
|
||||
|
||||
void OsgEarth::displayInfo()
|
||||
{
|
||||
qDebug() << "Using osg version :" << osgGetVersion();
|
||||
qDebug() << "Using osgEarth version :" << osgEarthGetVersion();
|
||||
|
||||
// library file path list
|
||||
osgDB::FilePathList &libraryFilePathList = osgDB::Registry::instance()->getLibraryFilePathList();
|
||||
osgDB::FilePathList::iterator it = libraryFilePathList.begin();
|
||||
while (it != libraryFilePathList.end()) {
|
||||
qDebug() << "osg library file path:" << QString::fromStdString(*it);
|
||||
it++;
|
||||
}
|
||||
|
||||
// data file path list
|
||||
osgDB::FilePathList &dataFilePathList = osgDB::Registry::instance()->getDataFilePathList();
|
||||
it = dataFilePathList.begin();
|
||||
while (it != dataFilePathList.end()) {
|
||||
qDebug() << "osg data file path:" << QString::fromStdString(*it);
|
||||
it++;
|
||||
}
|
||||
|
||||
qDebug() << "osg database threads:" << osg::DisplaySettings::instance()->getNumOfDatabaseThreadsHint();
|
||||
qDebug() << "osg http database threads:" << osg::DisplaySettings::instance()->getNumOfHttpDatabaseThreadsHint();
|
||||
|
||||
// qDebug() << "Platform supports GLSL:" << osgEarth::Registry::capabilities().supportsGLSL();
|
||||
|
||||
#ifdef OSG_USE_QT_PRIVATE
|
||||
bool threadedOpenGL = QGuiApplicationPrivate::platform_integration->hasCapability(QPlatformIntegration::ThreadedOpenGL);
|
||||
qDebug() << "Platform supports threaded OpenGL:" << threadedOpenGL;
|
||||
#endif
|
||||
|
||||
osgQtQuick::capabilitiesInfo(osgEarth::Registry::capabilities());
|
||||
}
|
||||
|
||||
void QtNotifyHandler::notify(osg::NotifySeverity severity, const char *message)
|
||||
{
|
||||
QString msg(message);
|
||||
|
||||
// right trim message...
|
||||
int n = msg.size() - 1;
|
||||
|
||||
for (; n >= 0; --n) {
|
||||
if (!msg.at(n).isSpace()) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
msg = msg.left(n + 1);
|
||||
|
||||
switch (severity) {
|
||||
case osg::ALWAYS:
|
||||
qDebug().noquote() << "[OSG]" << msg;
|
||||
break;
|
||||
case osg::FATAL:
|
||||
qCritical().noquote() << "[OSG FATAL]" << msg;
|
||||
break;
|
||||
case osg::WARN:
|
||||
qWarning().noquote() << "[OSG WARN]" << msg;
|
||||
break;
|
||||
case osg::NOTICE:
|
||||
qDebug().noquote() << "[OSG NOTICE]" << msg;
|
||||
break;
|
||||
case osg::INFO:
|
||||
qDebug().noquote() << "[OSG]" << msg;
|
||||
break;
|
||||
case osg::DEBUG_INFO:
|
||||
qDebug().noquote() << "[OSG DEBUG INFO]" << msg;
|
||||
break;
|
||||
case osg::DEBUG_FP:
|
||||
qDebug().noquote() << "[OSG DEBUG FP]" << msg;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void OsgEarth::initWindowingSystem()
|
||||
{
|
||||
osg::GraphicsContext::setWindowingSystemInterface(QtWindowingSystem::getInterface());
|
||||
}
|
48
ground/openpilotgcs/src/libs/osgearth/osgearth.h
Normal file
48
ground/openpilotgcs/src/libs/osgearth/osgearth.h
Normal file
@ -0,0 +1,48 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file osgearth.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief osgearth utilities
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef OSGEARTH_H
|
||||
#define OSGEARTH_H
|
||||
|
||||
#include "osgearth_global.h"
|
||||
|
||||
class OSGEARTH_LIB_EXPORT OsgEarth {
|
||||
public:
|
||||
static void registerQmlTypes();
|
||||
static void initialize();
|
||||
|
||||
private:
|
||||
static bool registered;
|
||||
static bool initialized;
|
||||
|
||||
static void initializePathes();
|
||||
static void initializeCache();
|
||||
|
||||
// Sets the WindowingSystem to Qt.
|
||||
static void initWindowingSystem();
|
||||
|
||||
static void displayInfo();
|
||||
};
|
||||
|
||||
#endif // OSGEARTH_H
|
5
ground/openpilotgcs/src/libs/osgearth/osgearth.pri
Normal file
5
ground/openpilotgcs/src/libs/osgearth/osgearth.pri
Normal file
@ -0,0 +1,5 @@
|
||||
exists( $(OSG_SDK_DIR) ) {
|
||||
CONFIG += osg
|
||||
DEFINES += USE_OSG
|
||||
LIBS *= -l$$qtLibraryName(GCSOsgEarth)
|
||||
}
|
97
ground/openpilotgcs/src/libs/osgearth/osgearth.pro
Normal file
97
ground/openpilotgcs/src/libs/osgearth/osgearth.pro
Normal file
@ -0,0 +1,97 @@
|
||||
TEMPLATE = lib
|
||||
TARGET = GCSOsgEarth
|
||||
DEFINES += OSGEARTH_LIBRARY
|
||||
|
||||
#DEFINES += OSG_USE_QT_PRIVATE
|
||||
|
||||
QT += widgets opengl qml quick
|
||||
contains(DEFINES, OSG_USE_QT_PRIVATE) {
|
||||
QT += core-private gui-private
|
||||
}
|
||||
|
||||
include(../../openpilotgcslibrary.pri)
|
||||
include(../utils/utils.pri)
|
||||
|
||||
# osg and osgearth emit a lot of unused parameter warnings...
|
||||
QMAKE_CXXFLAGS += -Wno-unused-parameter
|
||||
|
||||
OSG_SDK_DIR = $$clean_path($$(OSG_SDK_DIR))
|
||||
message(Using osg from here: $$OSG_SDK_DIR)
|
||||
|
||||
HEADERS += \
|
||||
osgearth_global.h \
|
||||
utility.h \
|
||||
qtwindowingsystem.h \
|
||||
osgearth.h
|
||||
|
||||
SOURCES += \
|
||||
utility.cpp \
|
||||
qtwindowingsystem.cpp \
|
||||
osgearth.cpp
|
||||
|
||||
HEADERS += \
|
||||
osgQtQuick/Export.hpp \
|
||||
osgQtQuick/OSGNode.hpp \
|
||||
osgQtQuick/OSGGroup.hpp \
|
||||
osgQtQuick/OSGTransformNode.hpp \
|
||||
osgQtQuick/OSGCubeNode.hpp \
|
||||
osgQtQuick/OSGTextNode.hpp \
|
||||
osgQtQuick/OSGFileNode.hpp \
|
||||
osgQtQuick/OSGModelNode.hpp \
|
||||
osgQtQuick/OSGBackgroundNode.hpp \
|
||||
osgQtQuick/OSGSkyNode.hpp \
|
||||
osgQtQuick/OSGCamera.hpp \
|
||||
osgQtQuick/OSGViewport.hpp
|
||||
|
||||
SOURCES += \
|
||||
osgQtQuick/OSGNode.cpp \
|
||||
osgQtQuick/OSGGroup.cpp \
|
||||
osgQtQuick/OSGTransformNode.cpp \
|
||||
osgQtQuick/OSGCubeNode.cpp \
|
||||
osgQtQuick/OSGTextNode.cpp \
|
||||
osgQtQuick/OSGFileNode.cpp \
|
||||
osgQtQuick/OSGModelNode.cpp \
|
||||
osgQtQuick/OSGBackgroundNode.cpp \
|
||||
osgQtQuick/OSGSkyNode.cpp \
|
||||
osgQtQuick/OSGCamera.cpp \
|
||||
osgQtQuick/OSGViewport.cpp
|
||||
|
||||
INCLUDEPATH += $$OSG_SDK_DIR/include
|
||||
|
||||
linux {
|
||||
!exists( $(OSG_SDK_DIR)/lib64 ) {
|
||||
LIBS += -L$$OSG_SDK_DIR/lib
|
||||
} else {
|
||||
LIBS += -L$$OSG_SDK_DIR/lib64
|
||||
}
|
||||
|
||||
LIBS +=-lOpenThreads
|
||||
LIBS += -losg -losgUtil -losgDB -losgGA -losgViewer -losgText -losgQt
|
||||
LIBS += -losgEarth -losgEarthUtil -losgEarthFeatures -losgEarthSymbology -losgEarthAnnotation -losgEarthQt
|
||||
}
|
||||
|
||||
macx {
|
||||
LIBS += -L$$OSG_SDK_DIR/lib
|
||||
|
||||
LIBS += -lOpenThreads
|
||||
LIBS += -losg -losgUtil -losgDB -losgGA -losgViewer -losgText -losgQt
|
||||
LIBS += -losgEarth -losgEarthUtil -losgEarthFeatures -losgEarthSymbology -losgEarthAnnotation -losgEarthQt
|
||||
LIBS += -losgDB
|
||||
}
|
||||
|
||||
win32 {
|
||||
LIBS += -L$$OSG_SDK_DIR/lib
|
||||
|
||||
CONFIG(release, debug|release) {
|
||||
LIBS += -lOpenThreads
|
||||
LIBS += -losg -losgUtil -losgDB -losgGA -losgViewer -losgText -losgQt
|
||||
LIBS += -losgEarth -losgEarthUtil -losgEarthFeatures -losgEarthSymbology -losgEarthAnnotation -losgEarthQt
|
||||
}
|
||||
CONFIG(debug, debug|release) {
|
||||
LIBS += -lOpenThreadsd
|
||||
LIBS += -losgd -losgUtild -losgDBd -losgGAd -losgViewerd -losgTextd -losgQtd
|
||||
LIBS += -losgEarthd -losgEarthUtild -losgEarthFeaturesd -losgEarthSymbologyd -losgEarthAnnotationd -losgEarthQtd
|
||||
}
|
||||
}
|
||||
|
||||
include(copydata.pro)
|
42
ground/openpilotgcs/src/libs/osgearth/osgearth_global.h
Normal file
42
ground/openpilotgcs/src/libs/osgearth/osgearth_global.h
Normal file
@ -0,0 +1,42 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file utils_global.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup
|
||||
* @{
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef OSGEARTH_GLOBAL_H
|
||||
#define OSGEARTH_GLOBAL_H
|
||||
|
||||
#include <QtCore/qglobal.h>
|
||||
|
||||
#if defined(OSGEARTH_LIBRARY)
|
||||
# define OSGEARTH_LIB_EXPORT Q_DECL_EXPORT
|
||||
#elif defined(OSGEARTH_STATIC_LIBRARY) // Abuse single files for manual tests
|
||||
# define OSGEARTH_LIB_EXPORT
|
||||
#else
|
||||
# define OSGEARTH_LIB_EXPORT Q_DECL_IMPORT
|
||||
#endif
|
||||
|
||||
#endif // OSGEARTH_GLOBAL_H
|
411
ground/openpilotgcs/src/libs/osgearth/qtwindowingsystem.cpp
Normal file
411
ground/openpilotgcs/src/libs/osgearth/qtwindowingsystem.cpp
Normal file
@ -0,0 +1,411 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file qtwindowingsystem.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief osgearth utilities
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "qtwindowingsystem.h"
|
||||
|
||||
#include "utility.h"
|
||||
|
||||
#include <osg/DeleteHandler>
|
||||
#include <osgViewer/GraphicsWindow>
|
||||
|
||||
#include <QOpenGLContext>
|
||||
#include <QOffscreenSurface>
|
||||
#include <QDebug>
|
||||
|
||||
#include <string>
|
||||
|
||||
// TODO no need to derive from GraphicsWindow (derive directly from GraphicsContext instead)
|
||||
class GraphicsWindowQt : public osgViewer::GraphicsWindow {
|
||||
public:
|
||||
GraphicsWindowQt(osg::GraphicsContext::Traits *traits);
|
||||
~GraphicsWindowQt();
|
||||
|
||||
bool isSameKindAs(const Object *object) const
|
||||
{
|
||||
return dynamic_cast<const GraphicsWindowQt *>(object) != 0;
|
||||
}
|
||||
const char *libraryName() const
|
||||
{
|
||||
return "osgViewerXYZ";
|
||||
}
|
||||
const char *className() const
|
||||
{
|
||||
return "GraphicsWindowQt";
|
||||
}
|
||||
|
||||
bool setWindowRectangleImplementation(int x, int y, int width, int height);
|
||||
void getWindowRectangle(int & x, int & y, int & width, int & height);
|
||||
bool setWindowDecorationImplementation(bool windowDecoration);
|
||||
bool getWindowDecoration() const;
|
||||
void grabFocus();
|
||||
void grabFocusIfPointerInWindow();
|
||||
void raiseWindow();
|
||||
void setWindowName(const std::string & name);
|
||||
std::string getWindowName();
|
||||
void useCursor(bool cursorOn);
|
||||
void setCursor(MouseCursor cursor);
|
||||
bool valid() const;
|
||||
bool realizeImplementation();
|
||||
bool isRealizedImplementation() const;
|
||||
void closeImplementation();
|
||||
bool makeCurrentImplementation();
|
||||
bool releaseContextImplementation();
|
||||
void swapBuffersImplementation();
|
||||
void runOperations();
|
||||
|
||||
void requestWarpPointer(float x, float y);
|
||||
|
||||
protected:
|
||||
void init();
|
||||
|
||||
bool _initialized;
|
||||
bool _valid;
|
||||
bool _realized;
|
||||
bool _closing;
|
||||
|
||||
bool _owned;
|
||||
|
||||
QOpenGLContext *_glContext;
|
||||
QOffscreenSurface *_surface;
|
||||
};
|
||||
|
||||
GraphicsWindowQt::GraphicsWindowQt(osg::GraphicsContext::Traits *traits) :
|
||||
_initialized(false),
|
||||
_valid(false),
|
||||
_realized(false),
|
||||
_closing(false),
|
||||
_owned(false),
|
||||
_glContext(NULL),
|
||||
_surface(NULL)
|
||||
{
|
||||
qDebug() << "GraphicsWindowQt::GraphicsWindowQt";
|
||||
_traits = traits;
|
||||
|
||||
init();
|
||||
|
||||
if (valid()) {
|
||||
setState(new osg::State);
|
||||
getState()->setGraphicsContext(this);
|
||||
|
||||
if (_traits.valid() && _traits->sharedContext.valid()) {
|
||||
getState()->setContextID(_traits->sharedContext->getState()->getContextID());
|
||||
incrementContextIDUsageCount(getState()->getContextID());
|
||||
} else {
|
||||
getState()->setContextID(osg::GraphicsContext::createNewContextID());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
GraphicsWindowQt::~GraphicsWindowQt()
|
||||
{
|
||||
qDebug() << "GraphicsWindowQt::~GraphicsWindowQt";
|
||||
close();
|
||||
}
|
||||
|
||||
void GraphicsWindowQt::init()
|
||||
{
|
||||
qDebug() << "GraphicsWindowQt::init";
|
||||
if (_closing || _initialized) {
|
||||
return;
|
||||
}
|
||||
|
||||
// update by WindowData
|
||||
// WindowData* windowData = _traits.get() ? dynamic_cast<WindowData*>(_traits->inheritedWindowData.get()) : 0;
|
||||
// if ( !_widget )
|
||||
// _widget = windowData ? windowData->_widget : NULL;
|
||||
// if ( !parent )
|
||||
// parent = windowData ? windowData->_parent : NULL;
|
||||
|
||||
_initialized = true;
|
||||
|
||||
_valid = _initialized;
|
||||
}
|
||||
|
||||
bool GraphicsWindowQt::setWindowRectangleImplementation(int x, int y, int width, int height)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
void GraphicsWindowQt::getWindowRectangle(int & x, int & y, int & width, int & height)
|
||||
{}
|
||||
|
||||
bool GraphicsWindowQt::setWindowDecorationImplementation(bool windowDecoration)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GraphicsWindowQt::getWindowDecoration() const
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
void GraphicsWindowQt::grabFocus()
|
||||
{}
|
||||
|
||||
void GraphicsWindowQt::grabFocusIfPointerInWindow()
|
||||
{}
|
||||
|
||||
void GraphicsWindowQt::raiseWindow()
|
||||
{}
|
||||
|
||||
void GraphicsWindowQt::setWindowName(const std::string & name)
|
||||
{}
|
||||
|
||||
std::string GraphicsWindowQt::getWindowName()
|
||||
{
|
||||
return "";
|
||||
}
|
||||
|
||||
void GraphicsWindowQt::useCursor(bool cursorOn)
|
||||
{}
|
||||
|
||||
void GraphicsWindowQt::setCursor(MouseCursor cursor)
|
||||
{}
|
||||
|
||||
bool GraphicsWindowQt::valid() const
|
||||
{
|
||||
return _valid;
|
||||
}
|
||||
|
||||
bool GraphicsWindowQt::realizeImplementation()
|
||||
{
|
||||
qDebug() << "GraphicsWindowQt::realizeImplementation";
|
||||
// save the current context
|
||||
// note: this will save only Qt-based contexts
|
||||
|
||||
if (_realized) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if (!_initialized) {
|
||||
init();
|
||||
if (!_initialized) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
QOpenGLContext *currentContext = QOpenGLContext::currentContext();
|
||||
|
||||
if (!currentContext) {
|
||||
qDebug() << "GraphicsWindowQt::realizeImplementation - creating owned context";
|
||||
_owned = true;
|
||||
_glContext = new QOpenGLContext();
|
||||
_glContext->create();
|
||||
_surface = new QOffscreenSurface();
|
||||
_surface->setFormat(_glContext->format());
|
||||
_surface->create();
|
||||
osgQtQuick::formatInfo(_surface->format());
|
||||
} else {
|
||||
qDebug() << "GraphicsWindowQt::realizeImplementation - using current context";
|
||||
_glContext = currentContext;
|
||||
}
|
||||
|
||||
//// initialize GL context for the widget
|
||||
// if ( !valid() )
|
||||
// _widget->glInit();
|
||||
|
||||
// make current
|
||||
_realized = true;
|
||||
bool result = makeCurrent();
|
||||
_realized = false;
|
||||
|
||||
// fail if we do not have current context
|
||||
if (!result) {
|
||||
// if ( savedContext )
|
||||
// const_cast< QGLContext* >( savedContext )->makeCurrent();
|
||||
//
|
||||
qWarning() << "GraphicsWindowQt::realizeImplementation - can not make context current.";
|
||||
return false;
|
||||
}
|
||||
|
||||
_realized = true;
|
||||
|
||||
//// make sure the event queue has the correct window rectangle size and input range
|
||||
// getEventQueue()->syncWindowRectangleWithGraphcisContext();
|
||||
|
||||
// make this window's context not current
|
||||
// note: this must be done as we will probably make the context current from another thread
|
||||
// and it is not allowed to have one context current in two threads
|
||||
if (!releaseContext()) {
|
||||
qWarning() << "GraphicsWindowQt::realizeImplementation - can not release context.";
|
||||
}
|
||||
|
||||
//// restore previous context
|
||||
// if ( savedContext )
|
||||
// const_cast< QGLContext* >( savedContext )->makeCurrent();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool GraphicsWindowQt::isRealizedImplementation() const
|
||||
{
|
||||
return _realized;
|
||||
}
|
||||
|
||||
void GraphicsWindowQt::runOperations()
|
||||
{
|
||||
// While in graphics thread this is last chance to do something useful before
|
||||
// graphics thread will execute its operations.
|
||||
// if (_widget->getNumDeferredEvents() > 0)
|
||||
// _widget->processDeferredEvents();
|
||||
//
|
||||
// if (QGLContext::currentContext() != _widget->context())
|
||||
// _widget->makeCurrent();
|
||||
//
|
||||
// qDebug() << "GraphicsWindowQt::runOperations";
|
||||
GraphicsWindow::runOperations();
|
||||
}
|
||||
|
||||
bool GraphicsWindowQt::makeCurrentImplementation()
|
||||
{
|
||||
if (!_realized) {
|
||||
qWarning() << "GraphicsWindowQt::makeCurrentImplementation() - not realized; cannot make current.";
|
||||
return false;
|
||||
}
|
||||
if (_owned && _glContext) {
|
||||
// qDebug() << "GraphicsWindowQt::makeCurrentImplementation : " << _surface;
|
||||
if (!_glContext->makeCurrent(_surface)) {
|
||||
qWarning() << "GraphicsWindowQt::makeCurrentImplementation : failed to make context current";
|
||||
return false;
|
||||
}
|
||||
}
|
||||
if (_glContext != QOpenGLContext::currentContext()) {
|
||||
qWarning() << "GraphicsWindowQt::makeCurrentImplementation : context is not current";
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool GraphicsWindowQt::releaseContextImplementation()
|
||||
{
|
||||
if (_glContext != QOpenGLContext::currentContext()) {
|
||||
qWarning() << "GraphicsWindowQt::releaseContextImplementation : context is not current";
|
||||
return false;
|
||||
}
|
||||
if (_owned && _glContext) {
|
||||
qDebug() << "GraphicsWindowQt::releaseContextImplementation";
|
||||
_glContext->doneCurrent();
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void GraphicsWindowQt::closeImplementation()
|
||||
{
|
||||
qDebug() << "GraphicsWindowQt::closeImplementation";
|
||||
_closing = true;
|
||||
_initialized = false;
|
||||
_valid = false;
|
||||
_realized = false;
|
||||
if (_owned) {
|
||||
if (_glContext) {
|
||||
qDebug() << "GraphicsWindowQt::closeImplementation - deleting owned context";
|
||||
delete _glContext;
|
||||
}
|
||||
if (_surface) {
|
||||
_surface->destroy();
|
||||
delete _surface;
|
||||
}
|
||||
}
|
||||
_glContext = NULL;
|
||||
_surface = NULL;
|
||||
}
|
||||
|
||||
void GraphicsWindowQt::swapBuffersImplementation()
|
||||
{
|
||||
// _widget->swapBuffers();
|
||||
//
|
||||
//// FIXME: the processDeferredEvents should really be executed in a GUI (main) thread context but
|
||||
//// I couln't find any reliable way to do this. For now, lets hope non of *GUI thread only operations* will
|
||||
//// be executed in a QGLWidget::event handler. On the other hand, calling GUI only operations in the
|
||||
//// QGLWidget event handler is an indication of a Qt bug.
|
||||
// if (_widget->getNumDeferredEvents() > 0)
|
||||
// _widget->processDeferredEvents();
|
||||
//
|
||||
//// We need to call makeCurrent here to restore our previously current context
|
||||
//// which may be changed by the processDeferredEvents function.
|
||||
// if (QGLContext::currentContext() != _widget->context())
|
||||
// _widget->makeCurrent();
|
||||
}
|
||||
|
||||
void GraphicsWindowQt::requestWarpPointer(float x, float y)
|
||||
{}
|
||||
|
||||
QtWindowingSystem::QtWindowingSystem()
|
||||
{
|
||||
}
|
||||
|
||||
QtWindowingSystem::~QtWindowingSystem()
|
||||
{
|
||||
if (osg::Referenced::getDeleteHandler()) {
|
||||
osg::Referenced::getDeleteHandler()->setNumFramesToRetainObjects(0);
|
||||
osg::Referenced::getDeleteHandler()->flushAll();
|
||||
}
|
||||
}
|
||||
|
||||
// Return the number of screens present in the system
|
||||
unsigned int QtWindowingSystem::getNumScreens(const osg::GraphicsContext::ScreenIdentifier & /*si*/)
|
||||
{
|
||||
qWarning() << "osgQt: getNumScreens() not implemented yet.";
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Return the resolution of specified screen
|
||||
// (0,0) is returned if screen is unknown
|
||||
void QtWindowingSystem::getScreenSettings(const osg::GraphicsContext::ScreenIdentifier & /*si*/, osg::GraphicsContext::ScreenSettings & /*resolution*/)
|
||||
{
|
||||
qWarning() << "osgQt: getScreenSettings() not implemented yet.";
|
||||
}
|
||||
|
||||
// Set the resolution for given screen
|
||||
bool QtWindowingSystem::setScreenSettings(const osg::GraphicsContext::ScreenIdentifier & /*si*/, const osg::GraphicsContext::ScreenSettings & /*resolution*/)
|
||||
{
|
||||
qWarning() << "osgQt: setScreenSettings() not implemented yet.";
|
||||
return false;
|
||||
}
|
||||
|
||||
// Enumerates available resolutions
|
||||
void QtWindowingSystem::enumerateScreenSettings(const osg::GraphicsContext::ScreenIdentifier & /*screenIdentifier*/, osg::GraphicsContext::ScreenSettingsList & /*resolution*/)
|
||||
{
|
||||
qWarning() << "osgQt: enumerateScreenSettings() not implemented yet.";
|
||||
}
|
||||
|
||||
// Create a graphics context with given traits
|
||||
osg::GraphicsContext *QtWindowingSystem::createGraphicsContext(osg::GraphicsContext::Traits *traits)
|
||||
{
|
||||
// if (traits->pbuffer)
|
||||
// {
|
||||
// OSG_WARN << "osgQt: createGraphicsContext - pbuffer not implemented yet.";
|
||||
// return NULL;
|
||||
// }
|
||||
// else
|
||||
// {
|
||||
osg::ref_ptr< GraphicsWindowQt > gc = new GraphicsWindowQt(traits);
|
||||
|
||||
if (gc->valid()) {
|
||||
return gc.release();
|
||||
} else {
|
||||
return NULL;
|
||||
}
|
||||
// }
|
||||
}
|
69
ground/openpilotgcs/src/libs/osgearth/qtwindowingsystem.h
Normal file
69
ground/openpilotgcs/src/libs/osgearth/qtwindowingsystem.h
Normal file
@ -0,0 +1,69 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file qtwindowingsystem.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief osgearth utilities
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef QTWINDOWINGSYSTEM_H
|
||||
#define QTWINDOWINGSYSTEM_H
|
||||
|
||||
#include "osgearth_global.h"
|
||||
|
||||
#include <osg/GraphicsContext>
|
||||
|
||||
class QtWindowingSystem : public osg::GraphicsContext::WindowingSystemInterface {
|
||||
public:
|
||||
|
||||
QtWindowingSystem();
|
||||
~QtWindowingSystem();
|
||||
|
||||
// Access the Qt windowing system through this singleton class.
|
||||
static QtWindowingSystem *getInterface()
|
||||
{
|
||||
static QtWindowingSystem *qtInterface = new QtWindowingSystem;
|
||||
|
||||
return qtInterface;
|
||||
}
|
||||
|
||||
// Return the number of screens present in the system
|
||||
virtual unsigned int getNumScreens(const osg::GraphicsContext::ScreenIdentifier & /*si*/);
|
||||
|
||||
// Return the resolution of specified screen
|
||||
// (0,0) is returned if screen is unknown
|
||||
virtual void getScreenSettings(const osg::GraphicsContext::ScreenIdentifier & /*si*/, osg::GraphicsContext::ScreenSettings & /*resolution*/);
|
||||
|
||||
// Set the resolution for given screen
|
||||
virtual bool setScreenSettings(const osg::GraphicsContext::ScreenIdentifier & /*si*/, const osg::GraphicsContext::ScreenSettings & /*resolution*/);
|
||||
|
||||
// Enumerates available resolutions
|
||||
virtual void enumerateScreenSettings(const osg::GraphicsContext::ScreenIdentifier & /*screenIdentifier*/, osg::GraphicsContext::ScreenSettingsList & /*resolution*/);
|
||||
|
||||
// Create a graphics context with given traits
|
||||
virtual osg::GraphicsContext *createGraphicsContext(osg::GraphicsContext::Traits *traits);
|
||||
|
||||
private:
|
||||
|
||||
// No implementation for these
|
||||
QtWindowingSystem(const QtWindowingSystem &);
|
||||
QtWindowingSystem & operator=(const QtWindowingSystem &);
|
||||
};
|
||||
|
||||
#endif // QTWINDOWINGSYSTEM_H
|
6
ground/openpilotgcs/src/libs/osgearth/readme.txt
Normal file
6
ground/openpilotgcs/src/libs/osgearth/readme.txt
Normal file
@ -0,0 +1,6 @@
|
||||
This code was strongly inspired by work from Konstantin Podsvirov
|
||||
|
||||
References :
|
||||
- https://wiki.qt.io/OsgQtQuick-Demo
|
||||
- https://github.com/podsvirov
|
||||
- https://github.com/podsvirov/osgqtquick
|
489
ground/openpilotgcs/src/libs/osgearth/utility.cpp
Normal file
489
ground/openpilotgcs/src/libs/osgearth/utility.cpp
Normal file
@ -0,0 +1,489 @@
|
||||
#include "utility.h"
|
||||
|
||||
// osgQtQuick qml types
|
||||
#include "osgQtQuick/OSGNode.hpp"
|
||||
#include "osgQtQuick/OSGGroup.hpp"
|
||||
#include "osgQtQuick/OSGFileNode.hpp"
|
||||
#include "osgQtQuick/OSGTransformNode.hpp"
|
||||
#include "osgQtQuick/OSGCubeNode.hpp"
|
||||
#include "osgQtQuick/OSGTextNode.hpp"
|
||||
#include "osgQtQuick/OSGModelNode.hpp"
|
||||
#include "osgQtQuick/OSGBackgroundNode.hpp"
|
||||
#include "osgQtQuick/OSGSkyNode.hpp"
|
||||
#include "osgQtQuick/OSGCamera.hpp"
|
||||
#include "osgQtQuick/OSGViewport.hpp"
|
||||
|
||||
#include <osg/NodeCallback>
|
||||
#include <osg/Camera>
|
||||
#include <osg/io_utils>
|
||||
#include <osg/ApplicationUsage>
|
||||
#include <osgViewer/Viewer>
|
||||
#include <osgViewer/CompositeViewer>
|
||||
#include <osgDB/FileNameUtils>
|
||||
#include <osgDB/ReadFile>
|
||||
#include <osgUtil/CullVisitor>
|
||||
#include <osgGA/GUIEventAdapter>
|
||||
#include <osgText/Font>
|
||||
#include <osgText/Text>
|
||||
#include <osgText/String>
|
||||
#include <osgQt/QFontImplementation>
|
||||
|
||||
#include <osgEarth/Capabilities>
|
||||
#include <osgEarth/CullingUtils>
|
||||
#include <osgEarth/MapNode>
|
||||
#include <osgEarth/SpatialReference>
|
||||
#include <osgEarth/ElevationQuery>
|
||||
|
||||
#include <QFont>
|
||||
#include <QKeyEvent>
|
||||
#include <QCoreApplication>
|
||||
#include <QThread>
|
||||
|
||||
namespace osgQtQuick {
|
||||
class CullCallback : public osg::NodeCallback {
|
||||
public:
|
||||
CullCallback() {}
|
||||
|
||||
virtual ~CullCallback() {}
|
||||
|
||||
public:
|
||||
virtual void operator()(osg::Node *node, osg::NodeVisitor *nv)
|
||||
{
|
||||
osgUtil::CullVisitor *cv = osgEarth::Culling::asCullVisitor(nv);
|
||||
|
||||
if (cv) {
|
||||
OSG_DEBUG << "****** Node:" << node << " " << node->getName() << std::endl;
|
||||
OSG_DEBUG << "projection matrix: " << *(cv->getProjectionMatrix()) << std::endl;
|
||||
OSG_DEBUG << "model view matrix: " << *(cv->getModelViewMatrix()) << std::endl;
|
||||
}
|
||||
osg::MatrixTransform *mt = dynamic_cast<osg::MatrixTransform *>(node);
|
||||
if (mt) {
|
||||
OSG_DEBUG << "matrix: " << mt->getMatrix() << std::endl;
|
||||
}
|
||||
traverse(node, nv);
|
||||
}
|
||||
};
|
||||
|
||||
class InsertCallbacksVisitor : public osg::NodeVisitor {
|
||||
public:
|
||||
InsertCallbacksVisitor() : osg::NodeVisitor(osg::NodeVisitor::TRAVERSE_ALL_CHILDREN)
|
||||
{}
|
||||
virtual void apply(osg::Node & node)
|
||||
{
|
||||
// node.setUpdateCallback(new UpdateCallback());
|
||||
node.setCullCallback(new CullCallback());
|
||||
traverse(node);
|
||||
}
|
||||
virtual void apply(osg::Geode & geode)
|
||||
{
|
||||
// geode.setUpdateCallback(new UpdateCallback());
|
||||
////note, it makes no sense to attach a cull callback to the node
|
||||
////at there are no nodes to traverse below the geode, only
|
||||
////drawables, and as such the Cull node callbacks is ignored.
|
||||
////If you wish to control the culling of drawables
|
||||
////then use a drawable cullback...
|
||||
// for(unsigned int i=0;i<geode.getNumDrawables();++i)
|
||||
// {
|
||||
// geode.getDrawable(i)->setUpdateCallback(new DrawableUpdateCallback());
|
||||
// geode.getDrawable(i)->setCullCallback(new DrawableCullCallback());
|
||||
// geode.getDrawable(i)->setDrawCallback(new DrawableDrawCallback());
|
||||
// }
|
||||
}
|
||||
virtual void apply(osg::Transform & node)
|
||||
{
|
||||
apply((osg::Node &)node);
|
||||
}
|
||||
};
|
||||
|
||||
void insertCallbacks(osg::Node *node)
|
||||
{
|
||||
InsertCallbacksVisitor icv;
|
||||
|
||||
node->accept(icv);
|
||||
}
|
||||
|
||||
osg::Camera *createHUDCamera(double left, double right, double bottom, double top)
|
||||
{
|
||||
osg::ref_ptr<osg::Camera> camera = new osg::Camera();
|
||||
|
||||
camera->setReferenceFrame(osg::Transform::ABSOLUTE_RF);
|
||||
camera->setClearMask(GL_DEPTH_BUFFER_BIT);
|
||||
camera->setRenderOrder(osg::Camera::POST_RENDER);
|
||||
camera->setAllowEventFocus(false);
|
||||
camera->setProjectionMatrix(
|
||||
osg::Matrix::ortho2D(left, right, bottom, top));
|
||||
return camera.release();
|
||||
}
|
||||
|
||||
osgText::Font *createFont(const std::string &name)
|
||||
{
|
||||
QFont font;
|
||||
|
||||
if (!font.fromString(QString::fromStdString(osgDB::getNameLessExtension(name)))) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
return new osgText::Font(new osgQt::QFontImplementation(font));
|
||||
}
|
||||
|
||||
osgText::Font *createFont(const QFont &font)
|
||||
{
|
||||
return new osgText::Font(new osgQt::QFontImplementation(font));
|
||||
}
|
||||
|
||||
osgText::Text *createText(const osg::Vec3 &pos, const std::string &content, float size, osgText::Font *font)
|
||||
{
|
||||
osg::ref_ptr<osgText::Text> text = new osgText::Text();
|
||||
|
||||
if (font) {
|
||||
text->setFont(font);
|
||||
}
|
||||
text->setCharacterSize(size);
|
||||
text->setAxisAlignment(osgText::TextBase::XY_PLANE);
|
||||
text->setPosition(pos);
|
||||
text->setText(content, osgText::String::ENCODING_UTF8);
|
||||
return text.release();
|
||||
}
|
||||
|
||||
// Copied from "GraphicsWindowQt.cpp" (osg module osgQt)
|
||||
QtKeyboardMap::QtKeyboardMap()
|
||||
{
|
||||
mKeyMap[Qt::Key_Escape] = osgGA::GUIEventAdapter::KEY_Escape;
|
||||
mKeyMap[Qt::Key_Delete] = osgGA::GUIEventAdapter::KEY_Delete;
|
||||
mKeyMap[Qt::Key_Home] = osgGA::GUIEventAdapter::KEY_Home;
|
||||
mKeyMap[Qt::Key_Enter] = osgGA::GUIEventAdapter::KEY_KP_Enter;
|
||||
mKeyMap[Qt::Key_End] = osgGA::GUIEventAdapter::KEY_End;
|
||||
mKeyMap[Qt::Key_Return] = osgGA::GUIEventAdapter::KEY_Return;
|
||||
mKeyMap[Qt::Key_PageUp] = osgGA::GUIEventAdapter::KEY_Page_Up;
|
||||
mKeyMap[Qt::Key_PageDown] = osgGA::GUIEventAdapter::KEY_Page_Down;
|
||||
mKeyMap[Qt::Key_Left] = osgGA::GUIEventAdapter::KEY_Left;
|
||||
mKeyMap[Qt::Key_Right] = osgGA::GUIEventAdapter::KEY_Right;
|
||||
mKeyMap[Qt::Key_Up] = osgGA::GUIEventAdapter::KEY_Up;
|
||||
mKeyMap[Qt::Key_Down] = osgGA::GUIEventAdapter::KEY_Down;
|
||||
mKeyMap[Qt::Key_Backspace] = osgGA::GUIEventAdapter::KEY_BackSpace;
|
||||
mKeyMap[Qt::Key_Tab] = osgGA::GUIEventAdapter::KEY_Tab;
|
||||
mKeyMap[Qt::Key_Space] = osgGA::GUIEventAdapter::KEY_Space;
|
||||
mKeyMap[Qt::Key_Delete] = osgGA::GUIEventAdapter::KEY_Delete;
|
||||
mKeyMap[Qt::Key_Alt] = osgGA::GUIEventAdapter::KEY_Alt_L;
|
||||
mKeyMap[Qt::Key_Shift] = osgGA::GUIEventAdapter::KEY_Shift_L;
|
||||
mKeyMap[Qt::Key_Control] = osgGA::GUIEventAdapter::KEY_Control_L;
|
||||
mKeyMap[Qt::Key_Meta] = osgGA::GUIEventAdapter::KEY_Meta_L;
|
||||
|
||||
mKeyMap[Qt::Key_F1] = osgGA::GUIEventAdapter::KEY_F1;
|
||||
mKeyMap[Qt::Key_F2] = osgGA::GUIEventAdapter::KEY_F2;
|
||||
mKeyMap[Qt::Key_F3] = osgGA::GUIEventAdapter::KEY_F3;
|
||||
mKeyMap[Qt::Key_F4] = osgGA::GUIEventAdapter::KEY_F4;
|
||||
mKeyMap[Qt::Key_F5] = osgGA::GUIEventAdapter::KEY_F5;
|
||||
mKeyMap[Qt::Key_F6] = osgGA::GUIEventAdapter::KEY_F6;
|
||||
mKeyMap[Qt::Key_F7] = osgGA::GUIEventAdapter::KEY_F7;
|
||||
mKeyMap[Qt::Key_F8] = osgGA::GUIEventAdapter::KEY_F8;
|
||||
mKeyMap[Qt::Key_F9] = osgGA::GUIEventAdapter::KEY_F9;
|
||||
mKeyMap[Qt::Key_F10] = osgGA::GUIEventAdapter::KEY_F10;
|
||||
mKeyMap[Qt::Key_F11] = osgGA::GUIEventAdapter::KEY_F11;
|
||||
mKeyMap[Qt::Key_F12] = osgGA::GUIEventAdapter::KEY_F12;
|
||||
mKeyMap[Qt::Key_F13] = osgGA::GUIEventAdapter::KEY_F13;
|
||||
mKeyMap[Qt::Key_F14] = osgGA::GUIEventAdapter::KEY_F14;
|
||||
mKeyMap[Qt::Key_F15] = osgGA::GUIEventAdapter::KEY_F15;
|
||||
mKeyMap[Qt::Key_F16] = osgGA::GUIEventAdapter::KEY_F16;
|
||||
mKeyMap[Qt::Key_F17] = osgGA::GUIEventAdapter::KEY_F17;
|
||||
mKeyMap[Qt::Key_F18] = osgGA::GUIEventAdapter::KEY_F18;
|
||||
mKeyMap[Qt::Key_F19] = osgGA::GUIEventAdapter::KEY_F19;
|
||||
mKeyMap[Qt::Key_F20] = osgGA::GUIEventAdapter::KEY_F20;
|
||||
|
||||
mKeyMap[Qt::Key_hyphen] = '-';
|
||||
mKeyMap[Qt::Key_Equal] = '=';
|
||||
|
||||
mKeyMap[Qt::Key_division] = osgGA::GUIEventAdapter::KEY_KP_Divide;
|
||||
mKeyMap[Qt::Key_multiply] = osgGA::GUIEventAdapter::KEY_KP_Multiply;
|
||||
mKeyMap[Qt::Key_Minus] = '-';
|
||||
mKeyMap[Qt::Key_Plus] = '+';
|
||||
// mKeyMap[Qt::Key_H ] = osgGA::GUIEventAdapter::KEY_KP_Home;
|
||||
// mKeyMap[Qt::Key_ ] = osgGA::GUIEventAdapter::KEY_KP_Up;
|
||||
// mKeyMap[92 ] = osgGA::GUIEventAdapter::KEY_KP_Page_Up;
|
||||
// mKeyMap[86 ] = osgGA::GUIEventAdapter::KEY_KP_Left;
|
||||
// mKeyMap[87 ] = osgGA::GUIEventAdapter::KEY_KP_Begin;
|
||||
// mKeyMap[88 ] = osgGA::GUIEventAdapter::KEY_KP_Right;
|
||||
// mKeyMap[83 ] = osgGA::GUIEventAdapter::KEY_KP_End;
|
||||
// mKeyMap[84 ] = osgGA::GUIEventAdapter::KEY_KP_Down;
|
||||
// mKeyMap[85 ] = osgGA::GUIEventAdapter::KEY_KP_Page_Down;
|
||||
mKeyMap[Qt::Key_Insert] = osgGA::GUIEventAdapter::KEY_KP_Insert;
|
||||
// mKeyMap[Qt::Key_Delete ] = osgGA::GUIEventAdapter::KEY_KP_Delete;
|
||||
}
|
||||
|
||||
QtKeyboardMap::~QtKeyboardMap()
|
||||
{}
|
||||
|
||||
int QtKeyboardMap::remapKey(QKeyEvent *event)
|
||||
{
|
||||
KeyMap::iterator itr = mKeyMap.find(event->key());
|
||||
|
||||
if (itr == mKeyMap.end()) {
|
||||
return int(*(event->text().toLatin1().data()));
|
||||
}
|
||||
return itr->second;
|
||||
}
|
||||
|
||||
osgEarth::GeoPoint toGeoPoint(const QVector3D &position)
|
||||
{
|
||||
osgEarth::GeoPoint geoPoint(osgEarth::SpatialReference::get("wgs84"),
|
||||
position.x(), position.y(), position.z(), osgEarth::ALTMODE_ABSOLUTE);
|
||||
|
||||
return geoPoint;
|
||||
}
|
||||
|
||||
bool clampGeoPoint(osgEarth::GeoPoint &geoPoint, float offset, osgEarth::MapNode *mapNode)
|
||||
{
|
||||
if (!mapNode) {
|
||||
qWarning() << "Utility::clampGeoPoint - null map node";
|
||||
return false;
|
||||
}
|
||||
|
||||
// establish an elevation query interface based on the features' SRS.
|
||||
osgEarth::ElevationQuery eq(mapNode->getMap());
|
||||
// qDebug() << "Utility::clampGeoPoint - SRS :" << QString::fromStdString(mapNode->getMap()->getSRS()->getName());
|
||||
|
||||
bool clamped = false;
|
||||
double elevation;
|
||||
if (eq.getElevation(geoPoint, elevation, 0.0)) {
|
||||
clamped = ((geoPoint.z() - offset) < elevation);
|
||||
if (clamped) {
|
||||
qDebug() << "Utility::clampGeoPoint - clamping" << geoPoint.z() - offset << "/" << elevation;
|
||||
geoPoint.z() = elevation + offset;
|
||||
}
|
||||
} else {
|
||||
qDebug() << "Utility::clampGeoPoint - failed to get elevation";
|
||||
}
|
||||
|
||||
return clamped;
|
||||
}
|
||||
|
||||
QSurfaceFormat traitsToFormat(const osg::GraphicsContext::Traits *traits)
|
||||
{
|
||||
QSurfaceFormat format(QSurfaceFormat::defaultFormat());
|
||||
|
||||
format.setRedBufferSize(traits->red);
|
||||
format.setGreenBufferSize(traits->green);
|
||||
format.setBlueBufferSize(traits->blue);
|
||||
format.setAlphaBufferSize(traits->alpha);
|
||||
format.setDepthBufferSize(traits->depth);
|
||||
format.setStencilBufferSize(traits->stencil);
|
||||
|
||||
// format.setSampleBuffers(traits->sampleBuffers);
|
||||
format.setSamples(traits->samples);
|
||||
|
||||
// format.setAlpha(traits->alpha > 0);
|
||||
// format.setDepth(traits->depth > 0);
|
||||
// format.setStencil(traits->stencil > 0);
|
||||
|
||||
format.setStereo(traits->quadBufferStereo ? 1 : 0);
|
||||
|
||||
format.setSwapBehavior(traits->doubleBuffer ? QSurfaceFormat::DoubleBuffer : QSurfaceFormat::SingleBuffer);
|
||||
format.setSwapInterval(traits->vsync ? 1 : 0);
|
||||
|
||||
return format;
|
||||
}
|
||||
|
||||
void formatToTraits(const QSurfaceFormat & format, osg::GraphicsContext::Traits *traits)
|
||||
{
|
||||
traits->red = format.redBufferSize();
|
||||
traits->green = format.greenBufferSize();
|
||||
traits->blue = format.blueBufferSize();
|
||||
traits->alpha = format.hasAlpha() ? format.alphaBufferSize() : 0;
|
||||
traits->depth = format.depthBufferSize();
|
||||
traits->stencil = format.stencilBufferSize();
|
||||
|
||||
// traits->sampleBuffers = format.sampleBuffers() ? 1 : 0;
|
||||
traits->samples = format.samples();
|
||||
|
||||
traits->quadBufferStereo = format.stereo();
|
||||
|
||||
traits->doubleBuffer = format.swapBehavior() == QSurfaceFormat::DoubleBuffer;
|
||||
traits->vsync = format.swapInterval() >= 1;
|
||||
}
|
||||
|
||||
void openGLContextInfo(QOpenGLContext *context, const char *at)
|
||||
{
|
||||
qDebug() << "opengl context -----------------------------------------------------";
|
||||
qDebug() << "at :" << at;
|
||||
qDebug() << "context :" << context;
|
||||
if (context) {
|
||||
qDebug() << "share context :" << context->shareContext();
|
||||
// formatInfo(context->format());
|
||||
}
|
||||
qDebug() << "thread :" << QThread::currentThread() << "/" << QCoreApplication::instance()->thread();
|
||||
qDebug() << "--------------------------------------------------------------------";
|
||||
}
|
||||
|
||||
void formatInfo(const QSurfaceFormat & format)
|
||||
{
|
||||
qDebug().nospace() << "surface ----------------------------------------";
|
||||
qDebug().nospace() << "version : " << format.majorVersion() << "." << format.minorVersion();
|
||||
qDebug().nospace() << "profile : " << formatProfileName(format.profile());
|
||||
|
||||
qDebug().nospace() << "redBufferSize : " << format.redBufferSize();
|
||||
qDebug().nospace() << "greenBufferSize : " << format.greenBufferSize();
|
||||
qDebug().nospace() << "blueBufferSize : " << format.blueBufferSize();
|
||||
qDebug().nospace() << "alphaBufferSize : " << format.alphaBufferSize();
|
||||
qDebug().nospace() << "depthBufferSize : " << format.depthBufferSize();
|
||||
qDebug().nospace() << "stencilBufferSize : " << format.stencilBufferSize();
|
||||
|
||||
// qDebug().nospace() << "sampleBuffers" << format.sampleBuffers();
|
||||
qDebug().nospace() << "samples : " << format.samples();
|
||||
|
||||
qDebug().nospace() << "stereo : " << format.stereo();
|
||||
|
||||
qDebug().nospace() << "swapBehavior : " << formatSwapBehaviorName(format.swapBehavior());
|
||||
qDebug().nospace() << "swapInterval : " << format.swapInterval();
|
||||
}
|
||||
|
||||
void traitsInfo(const osg::GraphicsContext::Traits &traits)
|
||||
{
|
||||
unsigned int major, minor;
|
||||
|
||||
traits.getContextVersion(major, minor);
|
||||
|
||||
qDebug().nospace() << "traits ----------------------------------------";
|
||||
qDebug().nospace() << "gl version : " << major << "." << minor;
|
||||
qDebug().nospace() << "glContextVersion : " << QString::fromStdString(traits.glContextVersion);
|
||||
qDebug().nospace() << "glContextFlags : " << QString("%1").arg(traits.glContextFlags);
|
||||
qDebug().nospace() << "glContextProfileMask : " << QString("%1").arg(traits.glContextProfileMask);
|
||||
|
||||
qDebug().nospace() << "red : " << traits.red;
|
||||
qDebug().nospace() << "green : " << traits.green;
|
||||
qDebug().nospace() << "blue : " << traits.blue;
|
||||
qDebug().nospace() << "alpha : " << traits.alpha;
|
||||
qDebug().nospace() << "depth : " << traits.depth;
|
||||
qDebug().nospace() << "stencil : " << traits.stencil;
|
||||
|
||||
qDebug().nospace() << "sampleBuffers : " << traits.sampleBuffers;
|
||||
qDebug().nospace() << "samples : " << traits.samples;
|
||||
|
||||
qDebug().nospace() << "pbuffer : " << traits.pbuffer;
|
||||
qDebug().nospace() << "quadBufferStereo : " << traits.quadBufferStereo;
|
||||
qDebug().nospace() << "doubleBuffer : " << traits.doubleBuffer;
|
||||
|
||||
qDebug().nospace() << "vsync : " << traits.vsync;
|
||||
|
||||
// qDebug().nospace() << "swapMethod : " << traits.swapMethod;
|
||||
// qDebug().nospace() << "swapInterval : " << traits.swapInterval();
|
||||
}
|
||||
|
||||
void capabilitiesInfo(const osgEarth::Capabilities &caps)
|
||||
{
|
||||
qDebug().nospace() << "capabilities ----------------------------------------";
|
||||
|
||||
qDebug().nospace() << "Vendor : " << QString::fromStdString(caps.getVendor());
|
||||
qDebug().nospace() << "Version : " << QString::fromStdString(caps.getVersion());
|
||||
qDebug().nospace() << "Renderer : " << QString::fromStdString(caps.getRenderer());
|
||||
|
||||
qDebug().nospace() << "GLSL supported : " << caps.supportsGLSL();
|
||||
qDebug().nospace() << "GLSL version : " << caps.getGLSLVersionInt();
|
||||
|
||||
qDebug().nospace() << "GLES : " << caps.isGLES();
|
||||
|
||||
qDebug().nospace() << "Num Processors : " << caps.getNumProcessors();
|
||||
|
||||
qDebug().nospace() << "MaxFFPTextureUnits : " << caps.getMaxFFPTextureUnits();
|
||||
qDebug().nospace() << "MaxGPUTextureUnits : " << caps.getMaxGPUTextureUnits();
|
||||
qDebug().nospace() << "MaxGPUAttribs : " << caps.getMaxGPUAttribs();
|
||||
qDebug().nospace() << "MaxTextureSize : " << caps.getMaxTextureSize();
|
||||
qDebug().nospace() << "MaxLights : " << caps.getMaxLights();
|
||||
qDebug().nospace() << "DepthBufferBits : " << caps.getDepthBufferBits();
|
||||
qDebug().nospace() << "TextureArrays : " << caps.supportsTextureArrays();
|
||||
qDebug().nospace() << "Texture3D : " << caps.supportsTexture3D();
|
||||
qDebug().nospace() << "MultiTexture : " << caps.supportsMultiTexture();
|
||||
qDebug().nospace() << "StencilWrap : " << caps.supportsStencilWrap();
|
||||
qDebug().nospace() << "TwoSidedStencil : " << caps.supportsTwoSidedStencil();
|
||||
qDebug().nospace() << "Texture2DLod : " << caps.supportsTexture2DLod();
|
||||
qDebug().nospace() << "MipmappedTextureUpdates : " << caps.supportsMipmappedTextureUpdates();
|
||||
qDebug().nospace() << "DepthPackedStencilBuffer : " << caps.supportsDepthPackedStencilBuffer();
|
||||
qDebug().nospace() << "OcclusionQuery : " << caps.supportsOcclusionQuery();
|
||||
qDebug().nospace() << "DrawInstanced : " << caps.supportsDrawInstanced();
|
||||
qDebug().nospace() << "UniformBufferObjects : " << caps.supportsUniformBufferObjects();
|
||||
qDebug().nospace() << "NonPowerOfTwoTextures : " << caps.supportsNonPowerOfTwoTextures();
|
||||
qDebug().nospace() << "MaxUniformBlockSize : " << caps.getMaxUniformBlockSize();
|
||||
qDebug().nospace() << "PreferDisplayListsForStaticGeometry : " << caps.preferDisplayListsForStaticGeometry();
|
||||
qDebug().nospace() << "FragDepthWrite : " << caps.supportsFragDepthWrite();
|
||||
}
|
||||
|
||||
QString formatProfileName(QSurfaceFormat::OpenGLContextProfile profile)
|
||||
{
|
||||
switch (profile) {
|
||||
case QSurfaceFormat::NoProfile:
|
||||
return "No profile";
|
||||
|
||||
case QSurfaceFormat::CoreProfile:
|
||||
return "Core profile";
|
||||
|
||||
case QSurfaceFormat::CompatibilityProfile:
|
||||
return "Compatibility profile>";
|
||||
}
|
||||
return "<Unknown profile>";
|
||||
}
|
||||
|
||||
QString formatSwapBehaviorName(QSurfaceFormat::SwapBehavior swapBehavior)
|
||||
{
|
||||
switch (swapBehavior) {
|
||||
case QSurfaceFormat::DefaultSwapBehavior:
|
||||
return "Default";
|
||||
|
||||
case QSurfaceFormat::SingleBuffer:
|
||||
return "Single buffer";
|
||||
|
||||
case QSurfaceFormat::DoubleBuffer:
|
||||
return "Double buffer";
|
||||
|
||||
case QSurfaceFormat::TripleBuffer:
|
||||
return "Triple buffer";
|
||||
}
|
||||
return "<Unknown swap behavior>";
|
||||
}
|
||||
|
||||
QString getUsageString(osg::ApplicationUsage *applicationUsage) {
|
||||
const osg::ApplicationUsage::UsageMap& keyboardBinding = applicationUsage->getKeyboardMouseBindings();
|
||||
|
||||
QString desc;
|
||||
for(osg::ApplicationUsage::UsageMap::const_iterator itr = keyboardBinding.begin();
|
||||
itr != keyboardBinding.end();
|
||||
++itr)
|
||||
{
|
||||
desc += QString::fromStdString(itr->first);
|
||||
desc += " : ";
|
||||
desc += QString::fromStdString(itr->second);
|
||||
desc += "\n";
|
||||
}
|
||||
return desc;
|
||||
}
|
||||
|
||||
QString getUsageString(osgViewer::Viewer *viewer) {
|
||||
osg::ref_ptr<osg::ApplicationUsage> applicationUsage = new osg::ApplicationUsage();
|
||||
viewer->getUsage(*applicationUsage);
|
||||
return getUsageString(applicationUsage);
|
||||
}
|
||||
|
||||
QString getUsageString(osgViewer::CompositeViewer *viewer) {
|
||||
osg::ref_ptr<osg::ApplicationUsage> applicationUsage = new osg::ApplicationUsage();
|
||||
viewer->getUsage(*applicationUsage);
|
||||
return getUsageString(applicationUsage);
|
||||
}
|
||||
|
||||
void registerTypes(const char *uri)
|
||||
{
|
||||
// Q_ASSERT(uri == QLatin1String("osgQtQuick"));
|
||||
int maj = 1, min = 0;
|
||||
|
||||
// @uri osgQtQuick
|
||||
qmlRegisterType<osgQtQuick::OSGNode>(uri, maj, min, "OSGNode");
|
||||
qmlRegisterType<osgQtQuick::OSGGroup>(uri, maj, min, "OSGGroup");
|
||||
qmlRegisterType<osgQtQuick::OSGFileNode>(uri, maj, min, "OSGFileNode");
|
||||
qmlRegisterType<osgQtQuick::OSGTransformNode>(uri, maj, min, "OSGTransformNode");
|
||||
qmlRegisterType<osgQtQuick::OSGTextNode>(uri, maj, min, "OSGTextNode");
|
||||
qmlRegisterType<osgQtQuick::OSGCubeNode>(uri, maj, min, "OSGCubeNode");
|
||||
qmlRegisterType<osgQtQuick::OSGViewport>(uri, maj, min, "OSGViewport");
|
||||
|
||||
qmlRegisterType<osgQtQuick::OSGModelNode>(uri, maj, min, "OSGModelNode");
|
||||
qmlRegisterType<osgQtQuick::OSGSkyNode>(uri, maj, min, "OSGSkyNode");
|
||||
qmlRegisterType<osgQtQuick::OSGBackgroundNode>(uri, maj, min, "OSGBackgroundNode");
|
||||
qmlRegisterType<osgQtQuick::OSGCamera>(uri, maj, min, "OSGCamera");
|
||||
}
|
||||
} // namespace osgQtQuick
|
125
ground/openpilotgcs/src/libs/osgearth/utility.h
Normal file
125
ground/openpilotgcs/src/libs/osgearth/utility.h
Normal file
@ -0,0 +1,125 @@
|
||||
#ifndef OSGEARTH_UTILITY_H
|
||||
#define OSGEARTH_UTILITY_H
|
||||
|
||||
#include "osgearth_global.h"
|
||||
|
||||
#include <osg/NodeVisitor>
|
||||
#include <osg/GraphicsContext>
|
||||
|
||||
#include <osgEarth/GeoData>
|
||||
|
||||
#include <QtGlobal>
|
||||
#include <QOpenGLContext>
|
||||
#include <QSurfaceFormat>
|
||||
|
||||
#include <string>
|
||||
#include <map>
|
||||
|
||||
namespace osg {
|
||||
class Vec3f;
|
||||
typedef Vec3f Vec3;
|
||||
class Node;
|
||||
class Camera;
|
||||
} // namespace osg
|
||||
|
||||
namespace osgViewer {
|
||||
class Viewer;
|
||||
class CompositeViewer;
|
||||
} // namespace osgViewer
|
||||
|
||||
namespace osgText {
|
||||
class Text;
|
||||
class Font;
|
||||
} // namespace osgText
|
||||
|
||||
namespace osgEarth {
|
||||
class Capabilities;
|
||||
class MapNode;
|
||||
} // namespace osgEarth
|
||||
|
||||
QT_BEGIN_NAMESPACE
|
||||
class QFont;
|
||||
class QKeyEvent;
|
||||
QT_END_NAMESPACE
|
||||
|
||||
namespace osgQtQuick {
|
||||
class QtKeyboardMap {
|
||||
public:
|
||||
QtKeyboardMap();
|
||||
~QtKeyboardMap();
|
||||
|
||||
int remapKey(QKeyEvent *event);
|
||||
|
||||
private:
|
||||
typedef std::map<unsigned int, int> KeyMap;
|
||||
KeyMap mKeyMap;
|
||||
};
|
||||
|
||||
template<class T>
|
||||
class FindTopMostNodeOfTypeVisitor : public osg::NodeVisitor {
|
||||
public:
|
||||
FindTopMostNodeOfTypeVisitor() :
|
||||
osg::NodeVisitor(osg::NodeVisitor::TRAVERSE_ALL_CHILDREN),
|
||||
_foundNode(0)
|
||||
{}
|
||||
|
||||
void apply(osg::Node & node)
|
||||
{
|
||||
T *result = dynamic_cast<T *>(&node);
|
||||
|
||||
if (result) {
|
||||
_foundNode = result;
|
||||
} else {
|
||||
traverse(node);
|
||||
}
|
||||
}
|
||||
|
||||
T *_foundNode;
|
||||
};
|
||||
|
||||
template<class T>
|
||||
T *findTopMostNodeOfType(osg::Node *node)
|
||||
{
|
||||
if (!node) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
FindTopMostNodeOfTypeVisitor<T> fnotv;
|
||||
node->accept(fnotv);
|
||||
|
||||
return fnotv._foundNode;
|
||||
}
|
||||
|
||||
void insertCallbacks(osg::Node *node);
|
||||
|
||||
osg::Camera *createHUDCamera(double left, double right, double bottom, double top);
|
||||
|
||||
osgText::Font *createFont(const std::string &name);
|
||||
osgText::Font *createFont(const QFont &font);
|
||||
|
||||
osgText::Text *createText(const osg::Vec3 &pos,
|
||||
const std::string &content,
|
||||
float size,
|
||||
osgText::Font *font = 0);
|
||||
|
||||
osgEarth::GeoPoint toGeoPoint(const QVector3D &position);
|
||||
bool clampGeoPoint(osgEarth::GeoPoint &geoPoint, float offset, osgEarth::MapNode *mapNode);
|
||||
|
||||
QSurfaceFormat traitsToFormat(const osg::GraphicsContext::Traits *traits);
|
||||
void formatToTraits(const QSurfaceFormat & format, osg::GraphicsContext::Traits *traits);
|
||||
|
||||
void formatInfo(const QSurfaceFormat & format);
|
||||
void traitsInfo(const osg::GraphicsContext::Traits & traits);
|
||||
void capabilitiesInfo(const osgEarth::Capabilities & caps);
|
||||
void openGLContextInfo(QOpenGLContext *context, const char *at);
|
||||
|
||||
QString formatProfileName(QSurfaceFormat::OpenGLContextProfile profile);
|
||||
QString formatSwapBehaviorName(QSurfaceFormat::SwapBehavior swapBehavior);
|
||||
|
||||
QString getUsageString(osgViewer::Viewer *viewer);
|
||||
QString getUsageString(osgViewer::CompositeViewer *viewer);
|
||||
|
||||
void registerTypes(const char *uri);
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // OSGEARTH_UTILITY_H
|
@ -19,6 +19,7 @@ macx {
|
||||
} else {
|
||||
QMAKE_RPATHDIR = $$shell_quote(\$$ORIGIN)
|
||||
QMAKE_RPATHDIR += $$shell_quote(\$$ORIGIN/$$relative_path($$GCS_QT_LIBRARY_PATH, $$GCS_LIBRARY_PATH))
|
||||
QMAKE_RPATHDIR += $$shell_quote(\$$ORIGIN/$$relative_path($$GCS_LIBRARY_PATH/osg, $$GCS_LIBRARY_PATH))
|
||||
include(rpath.pri)
|
||||
|
||||
target.path = /$$GCS_LIBRARY_BASENAME/openpilotgcs
|
||||
|
@ -33,6 +33,7 @@ macx {
|
||||
QMAKE_RPATHDIR = $$shell_quote(\$$ORIGIN)
|
||||
QMAKE_RPATHDIR += $$shell_quote(\$$ORIGIN/$$relative_path($$GCS_LIBRARY_PATH, $$DESTDIR))
|
||||
QMAKE_RPATHDIR += $$shell_quote(\$$ORIGIN/$$relative_path($$GCS_QT_LIBRARY_PATH, $$DESTDIR))
|
||||
QMAKE_RPATHDIR += $$shell_quote(\$$ORIGIN/$$relative_path($$GCS_LIBRARY_PATH/osg, $$DESTDIR))
|
||||
include(rpath.pri)
|
||||
}
|
||||
|
||||
|
@ -62,12 +62,14 @@ ifeq ($(UNAME), Linux)
|
||||
QT_SDK_URL := http://download.qt.io/official_releases/qt/5.4/5.4.1/qt-opensource-linux-x64-5.4.1.run
|
||||
QT_SDK_MD5_URL := http://download.qt.io/official_releases/qt/5.4/5.4.1/qt-opensource-linux-x64-5.4.1.run.md5
|
||||
QT_SDK_ARCH := gcc_64
|
||||
OSG_URL := http://librepilot.github.io/tools/osg-0b63c8ffde-linux-x64-qt-5.4.1.tar.gz
|
||||
else
|
||||
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.9/4.9-2014-q4-major/+download/gcc-arm-none-eabi-4_9-2014q4-20141203-linux.tar.bz2
|
||||
ARM_SDK_MD5_URL := https://launchpad.net/gcc-arm-embedded/4.9/4.9-2014-q4-major/+download/gcc-arm-none-eabi-4_9-2014q4-20141203-linux.tar.bz2/+md5
|
||||
QT_SDK_URL := http://download.qt.io/official_releases/qt/5.4/5.4.1/qt-opensource-linux-x86-5.4.1.run
|
||||
QT_SDK_MD5_URL := http://download.qt.io/official_releases/qt/5.4/5.4.1/qt-opensource-linux-x86-5.4.1.run.md5
|
||||
QT_SDK_ARCH := gcc
|
||||
OSG_URL := http://librepilot.github.io/tools/osg-0b63c8ffde-linux-x86-qt-5.4.1.tar.gz
|
||||
endif
|
||||
UNCRUSTIFY_URL := http://librepilot.github.io/tools/uncrustify-0.60.tar.gz
|
||||
DOXYGEN_URL := http://librepilot.github.io/tools/doxygen-1.8.3.1.src.tar.gz
|
||||
@ -82,6 +84,7 @@ else ifeq ($(UNAME), Darwin)
|
||||
QT_SDK_INSTALLER_DAT := /Volumes/qt-opensource-mac-x64-clang-5.4.1/qt-opensource-mac-x64-clang-5.4.1.app/Contents/Resources/installer.dat
|
||||
UNCRUSTIFY_URL := http://librepilot.github.io/tools/uncrustify-0.60.tar.gz
|
||||
DOXYGEN_URL := http://librepilot.github.io/tools/doxygen-1.8.3.1.src.tar.gz
|
||||
OSG_URL :=
|
||||
else ifeq ($(UNAME), Windows)
|
||||
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.9/4.9-2014-q4-major/+download/gcc-arm-none-eabi-4_9-2014q4-20141203-win32.zip
|
||||
ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.9/4.9-2014-q4-major/+download/gcc-arm-none-eabi-4_9-2014q4-20141203-win32.zip/+md5
|
||||
@ -97,6 +100,7 @@ else ifeq ($(UNAME), Windows)
|
||||
CMAKE_URL := http://www.cmake.org/files/v2.8/cmake-2.8.12.2-win32-x86.zip
|
||||
CMAKE_MD5_URL := http://librepilot.github.io/tools/cmake-2.8.12.2-win32-x86.zip.md5
|
||||
MSYS_URL := http://librepilot.github.io/tools/MSYS-1.0.11.zip
|
||||
OSG_URL := http://librepilot.github.io/tools/osg-0b63c8ffde-mingw491_32-qt-5.4.1.tar.gz
|
||||
endif
|
||||
|
||||
GTEST_URL := http://librepilot.github.io/tools/gtest-1.6.0.zip
|
||||
@ -108,7 +112,13 @@ DOXYGEN_DIR := $(TOOLS_DIR)/doxygen-1.8.3.1
|
||||
GTEST_DIR := $(TOOLS_DIR)/gtest-1.6.0
|
||||
|
||||
ifeq ($(UNAME), Linux)
|
||||
ifeq ($(ARCH), x86_64)
|
||||
OSG_SDK_DIR := $(OSG_DIR)/osg-0b63c8ffde-linux-x64-qt-5.4.1
|
||||
else
|
||||
OSG_SDK_DIR := $(OSG_DIR)/osg-0b63c8ffde-linux-x86-qt-5.4.1
|
||||
endif
|
||||
else ifeq ($(UNAME), Darwin)
|
||||
OSG_SDK_DIR := $(OSG_DIR)/osg-0b63c8ffde-clang_64-qt-5.4.1
|
||||
else ifeq ($(UNAME), Windows)
|
||||
MINGW_DIR := $(QT_SDK_DIR)/Tools/$(QT_SDK_ARCH)
|
||||
# When changing PYTHON_DIR, you must also update it in ground/openpilotgcs/src/python.pri
|
||||
@ -120,6 +130,7 @@ else ifeq ($(UNAME), Windows)
|
||||
MESAWIN_DIR := $(TOOLS_DIR)/mesawin
|
||||
CMAKE_DIR := $(TOOLS_DIR)/cmake-2.8.12.2-win32-x86
|
||||
MSYS_DIR := $(TOOLS_DIR)/msys
|
||||
OSG_SDK_DIR := $(OSG_DIR)/osg-0b63c8ffde-mingw491_32-qt-5.4.1
|
||||
endif
|
||||
|
||||
QT_SDK_PREFIX := $(QT_SDK_DIR)
|
||||
@ -132,9 +143,9 @@ QT_SDK_PREFIX := $(QT_SDK_DIR)
|
||||
|
||||
BUILD_SDK_TARGETS := arm_sdk qt_sdk
|
||||
ifeq ($(UNAME), Windows)
|
||||
BUILD_SDK_TARGETS += sdl nsis mesawin openssl
|
||||
BUILD_SDK_TARGETS += sdl nsis mesawin openssl
|
||||
endif
|
||||
ALL_SDK_TARGETS := $(BUILD_SDK_TARGETS) gtest uncrustify doxygen
|
||||
ALL_SDK_TARGETS := $(BUILD_SDK_TARGETS) osg gtest uncrustify doxygen
|
||||
|
||||
define GROUP_SDK_TEMPLATE
|
||||
.PHONY: $(1)_install $(1)_clean $(1)_distclean $(1)_version
|
||||
@ -967,6 +978,25 @@ msys_version:
|
||||
|
||||
endif
|
||||
|
||||
##############################
|
||||
#
|
||||
# osg
|
||||
#
|
||||
##############################
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,osg,$(OSG_SDK_DIR),$(OSG_URL),,$(notdir $(OSG_URL))))
|
||||
|
||||
ifeq ($(shell [ -d "$(OSG_SDK_DIR)" ] && $(ECHO) "exists"), exists)
|
||||
export OSG_SDK_DIR := $(OSG_SDK_DIR)
|
||||
else
|
||||
# not installed, hope it's in the path...
|
||||
$(info $(EMPTY) WARNING $(call toprel, $(OSG_SDK_DIR)) not found (make osg_install), using system PATH)
|
||||
endif
|
||||
|
||||
.PHONY: osg_version
|
||||
osg_version:
|
||||
-$(V1) $(ECHO) "`$(OSG_SDK_DIR)/bin/osgversion`"
|
||||
-$(V1) $(ECHO) "`$(OSG_SDK_DIR)/bin/osgearth_version`"
|
||||
|
||||
|
||||
|
||||
|
@ -182,6 +182,13 @@ Section "-Plugins" InSecPlugins
|
||||
File /r "${GCS_BUILD_TREE}\lib\${GCS_SMALL_NAME}\plugins\*.pluginspec"
|
||||
SectionEnd
|
||||
|
||||
; Copy OSG libs
|
||||
Section "-OsgLibs" InSecOsgLibs
|
||||
SectionIn RO
|
||||
SetOutPath "$INSTDIR\lib\${GCS_SMALL_NAME}\osg"
|
||||
File /r "${GCS_BUILD_TREE}\lib\${GCS_SMALL_NAME}\osg\*.dll"
|
||||
SectionEnd
|
||||
|
||||
; Copy GCS resources
|
||||
Section "-Resources" InSecResources
|
||||
SetOutPath "$INSTDIR\share\${GCS_SMALL_NAME}\cloudconfig"
|
||||
|
Loading…
Reference in New Issue
Block a user