1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-19 04:52:12 +01:00

LP-29 extract CameraManipulator out of OSGCamera

- clean up Camera/Viewport
- clean up SkyNode
- replace attach/detach with use of QQmlParserStatus
This commit is contained in:
Philippe Renon 2016-03-20 18:23:10 +01:00
parent 911e3118f5
commit b19898ac5d
38 changed files with 1770 additions and 968 deletions

View File

@ -35,6 +35,8 @@
#include <QDebug>
namespace osgQtQuick {
enum DirtyFlag { URL = 1 << 0 };
struct OSGBackgroundNode::Hidden : public QObject {
Q_OBJECT
@ -44,17 +46,15 @@ private:
public:
QUrl url;
Hidden(OSGBackgroundNode *parent) : QObject(parent), self(parent), url() {}
Hidden(OSGBackgroundNode *self) : QObject(self), self(self), url()
{}
void updateNode()
void updateURL()
{
// qDebug() << "OSGBackgroundNode::realize - reading image file" << url.path();
qDebug() << "OSGBackgroundNode::updateNode - reading image file" << 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::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());
@ -75,21 +75,20 @@ public:
ss->setAttributeAndModes(new osg::Depth(osg::Depth::LEQUAL, 1.0, 1.0));
self->setNode(camera);
osg::ref_ptr<osg::Image> image = osgDB::readImageFile(url.path().toStdString());
texture->setImage(image.get());
}
};
/* class OSGBackgroundNode */
enum DirtyFlag { URL = 1 << 0 };
OSGBackgroundNode::OSGBackgroundNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
{
qDebug() << "OSGBackgroundNode::OSGBackgroundNode";
}
{}
OSGBackgroundNode::~OSGBackgroundNode()
{
// qDebug() << "OSGBackgroundNode::~OSGBackgroundNode";
qDebug() << "OSGBackgroundNode::~OSGBackgroundNode";
delete h;
}
@ -100,7 +99,6 @@ const QUrl OSGBackgroundNode::imageFile() const
void OSGBackgroundNode::setImageFile(const QUrl &url)
{
// qDebug() << "OSGBackgroundNode::setImageFile" << url;
if (h->url != url) {
h->url = url;
setDirty(URL);
@ -111,18 +109,9 @@ void OSGBackgroundNode::setImageFile(const QUrl &url)
void OSGBackgroundNode::update()
{
if (isDirty(URL)) {
h->updateNode();
h->updateURL();
}
}
void OSGBackgroundNode::attach(osgViewer::View *view)
{
update();
clearDirty();
}
void OSGBackgroundNode::detach(osgViewer::View *view)
{}
} // namespace osgQtQuick
#include "OSGBackgroundNode.moc"

View File

@ -55,9 +55,6 @@ private:
Hidden *const h;
virtual void update();
virtual void attach(osgViewer::View *view);
virtual void detach(osgViewer::View *view);
};
} // namespace osgQtQuick

View File

@ -29,28 +29,18 @@
#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>
#ifdef USE_OSGEARTH
#include <osgEarthUtil/EarthManipulator>
#include <osgEarthUtil/LogarithmicDepthBuffer>
#endif
#include <QDebug>
#include <QThread>
#include <QApplication>
namespace osgQtQuick {
enum DirtyFlag { FieldOfView = 1 << 0, ClearColor = 1 << 1, LogDepthBuffer = 1 << 4 };
struct OSGCamera::Hidden : public QObject {
Q_OBJECT
@ -60,34 +50,34 @@ private:
osg::ref_ptr<osg::Camera> camera;
public:
OSGNode *sceneNode;
// Camera vertical field of view in degrees
qreal fieldOfView;
// fov depends on the scenery space (probably 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;
ManipulatorMode::Enum manipulatorMode;
QColor clearColor;
// for NodeTrackerManipulator
TrackerMode::Enum trackerMode;
OSGNode *trackNode;
bool logDepthBufferEnabled;
bool logDepthBufferEnabled;
#ifdef USE_OSGEARTH
osgEarth::Util::LogarithmicDepthBuffer *logDepthBuffer;
#endif
bool clampToTerrain;
bool intoTerrain;
QVector3D attitude;
QVector3D position;
public:
Hidden(OSGCamera *camera) :
QObject(camera), self(camera), sceneNode(NULL), fieldOfView(90),
manipulatorMode(ManipulatorMode::Default), trackerMode(TrackerMode::NodeCenterAndAzim), trackNode(NULL),
logDepthBufferEnabled(false), clampToTerrain(false), intoTerrain(false)
Hidden(OSGCamera *self) : QObject(self), self(self), fieldOfView(90), clearColor(0, 0, 0, 255), logDepthBufferEnabled(false)
{
// default blue osg::Vec4f(0.2f, 0.99f, 0.4f, 1.0f)
camera = new osg::Camera();
camera->setClearColor(osg::Vec4(clearColor.redF(), clearColor.greenF(), clearColor.blueF(), clearColor.alphaF()));
osg::StateSet *stateset = camera->getOrCreateStateSet();
stateset->setGlobalDefaults();
self->setNode(camera);
#ifdef USE_OSGEARTH
logDepthBuffer = NULL;
#endif
@ -95,97 +85,6 @@ public:
~Hidden()
{
#ifdef USE_OSGEARTH
if (logDepthBuffer) {
delete logDepthBuffer;
logDepthBuffer = NULL;
}
#endif
}
bool acceptSceneNode(OSGNode *node)
{
qDebug() << "OSGCamera::acceptSceneNode" << node;
if (sceneNode == node) {
return true;
}
if (sceneNode) {
disconnect(sceneNode);
}
sceneNode = node;
if (sceneNode) {
connect(sceneNode, &OSGNode::nodeChanged, this, &Hidden::onSceneNodeChanged);
}
return true;
}
bool acceptManipulatorMode(ManipulatorMode::Enum mode)
{
// qDebug() << "OSGCamera::acceptManipulatorMode" << mode;
if (manipulatorMode == mode) {
return false;
}
manipulatorMode = mode;
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;
}
void attachCamera(osg::Camera *camera)
{
qDebug() << "OSGCamera::attach" << camera;
this->camera = camera;
self->setNode(this->camera.get());
#ifdef USE_OSGEARTH
// 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);
}
#endif
updateFieldOfView();
updateAspectRatio();
}
void detachCamera(osg::Camera *camera)
{
qDebug() << "OSGCamera::detach" << camera;
if (camera != this->camera) {
qWarning() << "OSGCamera::detach - camera not attached" << camera;
return;
}
this->camera = NULL;
#ifdef USE_OSGEARTH
if (logDepthBuffer) {
logDepthBuffer->uninstall(camera);
@ -195,93 +94,26 @@ public:
#endif
}
void attachManipulator(osgViewer::View *view)
void updateClearColor()
{
qDebug() << "OSGCamera::attachManipulator" << view;
osgGA::CameraManipulator *cm = NULL;
switch (manipulatorMode) {
case ManipulatorMode::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 ManipulatorMode::User:
qDebug() << "OSGCamera::attachManipulator - no camera manipulator";
// disable any installed camera manipulator
// TODO create and use own camera manipulator to avoid disabling ON_DEMAND frame update scheme
// see https://github.com/gwaldron/osgearth/commit/796daf4792ccaf18ae7eb6a5cb268eef0d42888d
// TODO see StandardManipulator for an example on how to react to events (to have FOV changes without the need for an update callback?)
cm = NULL;
break;
case ManipulatorMode::Earth:
{
#ifdef USE_OSGEARTH
qDebug() << "OSGCamera::attachManipulator - use EarthManipulator";
osgEarth::Util::EarthManipulator *em = new osgEarth::Util::EarthManipulator();
em->getSettings()->setThrowingEnabled(true);
cm = em;
#endif
break;
}
case ManipulatorMode::Track:
qDebug() << "OSGCamera::attachManipulator - use NodeTrackerManipulator";
if (trackNode && trackNode->node()) {
// setup tracking camera
// TODO when camera is thrown, then changing attitude has jitter
osgGA::NodeTrackerManipulator *ntm = new osgGA::NodeTrackerManipulator(
/*osgGA::StandardManipulator::COMPUTE_HOME_USING_BBOX | osgGA::StandardManipulator::DEFAULT_SETTINGS*/);
switch (trackerMode) {
case TrackerMode::NodeCenter:
ntm->setTrackerMode(osgGA::NodeTrackerManipulator::NODE_CENTER);
break;
case TrackerMode::NodeCenterAndAzim:
ntm->setTrackerMode(osgGA::NodeTrackerManipulator::NODE_CENTER_AND_AZIM);
break;
case TrackerMode::NodeCenterAndRotation:
ntm->setTrackerMode(osgGA::NodeTrackerManipulator::NODE_CENTER_AND_ROTATION);
break;
}
ntm->setTrackNode(trackNode->node());
ntm->setVerticalAxisFixed(false);
cm = ntm;
} else {
qWarning() << "OSGCamera::attachManipulator - no track node provided.";
cm = NULL;
}
break;
default:
qWarning() << "OSGCamera::attachManipulator - should not reach here!";
break;
if (!camera.valid()) {
qDebug() << "OSGCamera::updateClearColor - invalid camera";
return;
}
view->setCameraManipulator(cm, false);
if (cm && sceneNode && sceneNode->node()) {
qDebug() << "OSGCamera::attachManipulator - camera node" << sceneNode;
// 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(sceneNode->node());
}
if (cm) {
view->home();
}
}
qDebug() << "OSGCamera::updateClearColor" << clearColor;
void detachManipulator(osgViewer::View *view)
{
qDebug() << "OSGCamera::detachManipulator" << view;
view->setCameraManipulator(NULL, false);
camera->setClearColor(osg::Vec4(clearColor.redF(), clearColor.greenF(), clearColor.blueF(), clearColor.alphaF()));
}
void updateFieldOfView()
{
qDebug() << "OSGCamera::updateCameraFOV" << fieldOfView;
if (!camera.valid()) {
qDebug() << "OSGCamera::updateFieldOfView - invalid camera";
return;
}
qDebug() << "OSGCamera::updateFieldOfView" << fieldOfView;
double fovy, ar, zn, zf;
camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf);
@ -291,7 +123,16 @@ public:
void updateAspectRatio()
{
if (!camera.valid()) {
qDebug() << "OSGCamera::updateAspectRatio - invalid camera";
return;
}
osg::Viewport *viewport = camera->getViewport();
if (!viewport) {
qDebug() << "OSGCamera::updateAspectRatio - no viewport" << viewport;
return;
}
double aspectRatio = static_cast<double>(viewport->width()) / static_cast<double>(viewport->height());
qDebug() << "OSGCamera::updateAspectRatio" << aspectRatio;
@ -302,80 +143,57 @@ public:
camera->setProjectionMatrixAsPerspective(fovy, ar, zn, zf);
}
void updatePosition()
void updateLogDepthBuffer()
{
if (manipulatorMode != ManipulatorMode::User) {
qDebug() << "OSGCamera::updateLogDepthBuffer" << logDepthBufferEnabled;
if (!camera.valid()) {
qWarning() << "OSGCamera::updateLogDepthBuffer - invalid camera";
return;
}
// 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
osg::Matrix cameraPosition;
#ifdef USE_OSGEARTH
osgEarth::GeoPoint geoPoint = osgQtQuick::toGeoPoint(position);
if (clampToTerrain) {
if (sceneNode) {
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneNode->node());
if (mapNode) {
intoTerrain = clampGeoPoint(geoPoint, 0.5f, mapNode);
} else {
qWarning() << "OSGCamera::updateNode - scene data does not contain a map node";
}
}
// install log depth buffer if requested
if (logDepthBufferEnabled && !logDepthBuffer) {
qDebug() << "OSGCamera::updateLogDepthBuffer - installing logarithmic depth buffer";
logDepthBuffer = new osgEarth::Util::LogarithmicDepthBuffer();
logDepthBuffer->setUseFragDepth(true);
logDepthBuffer->install(camera);
} else if (!logDepthBufferEnabled && logDepthBuffer) {
qDebug() << "OSGCamera::updateLogDepthBuffer - uninstalling logarithmic depth buffer";
logDepthBuffer->uninstall(camera);
delete logDepthBuffer;
logDepthBuffer = NULL;
}
#endif
}
void setGraphicsContext(osg::GraphicsContext *gc)
{
if (!camera.valid()) {
qDebug() << "OSGCamera::setGraphicsContext - invalid camera";
return;
}
geoPoint.createLocalToWorld(cameraPosition);
#endif
qDebug() << "OSGCamera::setGraphicsContext" << gc;
// 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));
camera->setGraphicsContext(gc);
camera->setViewport(0, 0, gc->getTraits()->width, gc->getTraits()->height);
// Final camera matrix
double roll = osg::DegreesToRadians(attitude.x());
double pitch = osg::DegreesToRadians(attitude.y());
double yaw = osg::DegreesToRadians(attitude.z());
osg::Matrix cameraMatrix = cameraRotation
* osg::Matrix::rotate(roll, osg::Vec3(0, 1, 0))
* osg::Matrix::rotate(pitch, osg::Vec3(1, 0, 0))
* osg::Matrix::rotate(yaw, osg::Vec3(0, 0, -1)) * cameraPosition;
double aspectRatio = static_cast<double>(gc->getTraits()->width) / static_cast<double>(gc->getTraits()->height);
// Inverse the camera's position and orientation matrix to obtain the view matrix
cameraMatrix = osg::Matrix::inverse(cameraMatrix);
camera->setViewMatrix(cameraMatrix);
}
camera->setProjectionMatrixAsPerspective(fieldOfView, aspectRatio, 1.0f, 10000.0f);
private slots:
void onSceneNodeChanged(osg::Node *node)
{
qDebug() << "OSGCamera::onSceneNodeChanged" << node;
qWarning() << "OSGCamera::onSceneNodeChanged - needs to be implemented";
}
double fovy, ar, zn, zf;
camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf);
void onTrackNodeChanged(osg::Node *node)
{
qDebug() << "OSGCamera::onTrackNodeChanged" << node;
qWarning() << "OSGCamera::onTrackNodeChanged - needs to be implemented";
// FIXME this is needed for PFD + Terrain (because of "user" mode)
// updatePosition();
}
};
/* class OSGCamera */
enum DirtyFlag { FieldOfView = 1 << 0, Position = 1 << 1, Attitude = 1 << 2 };
OSGCamera::OSGCamera(QObject *parent) : OSGNode(parent), h(new Hidden(this))
{
qDebug() << "OSGCamera::OSGCamera";
}
{}
OSGCamera::~OSGCamera()
{
@ -383,15 +201,16 @@ OSGCamera::~OSGCamera()
delete h;
}
OSGNode *OSGCamera::sceneNode() const
QColor OSGCamera::clearColor() const
{
return h->sceneNode;
return h->clearColor;
}
void OSGCamera::setSceneNode(OSGNode *node)
void OSGCamera::setClearColor(const QColor &color)
{
if (h->acceptSceneNode(node)) {
emit sceneNodeChanged(node);
if (h->clearColor != color) {
h->clearColor = color;
emit clearColorChanged(color);
}
}
@ -409,89 +228,6 @@ void OSGCamera::setFieldOfView(qreal arg)
}
}
ManipulatorMode::Enum OSGCamera::manipulatorMode() const
{
return h->manipulatorMode;
}
void OSGCamera::setManipulatorMode(ManipulatorMode::Enum mode)
{
if (h->acceptManipulatorMode(mode)) {
emit manipulatorModeChanged(manipulatorMode());
}
}
OSGNode *OSGCamera::trackNode() const
{
return h->trackNode;
}
void OSGCamera::setTrackNode(OSGNode *node)
{
if (h->acceptTrackNode(node)) {
emit trackNodeChanged(node);
}
}
TrackerMode::Enum OSGCamera::trackerMode() const
{
return h->trackerMode;
}
void OSGCamera::setTrackerMode(TrackerMode::Enum 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;
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;
setDirty(Attitude);
emit attitudeChanged(attitude());
}
}
QVector3D OSGCamera::position() const
{
return h->position;
}
void OSGCamera::setPosition(QVector3D arg)
{
if (h->position != arg) {
h->position = arg;
setDirty(Position);
emit positionChanged(position());
}
}
bool OSGCamera::logarithmicDepthBuffer() const
{
return h->logDepthBufferEnabled;
@ -501,33 +237,34 @@ void OSGCamera::setLogarithmicDepthBuffer(bool enabled)
{
if (h->logDepthBufferEnabled != enabled) {
h->logDepthBufferEnabled = enabled;
setDirty(LogDepthBuffer);
emit logarithmicDepthBufferChanged(logarithmicDepthBuffer());
}
}
osg::Camera *OSGCamera::asCamera() const
{
// BAD introduce templating
return (osg::Camera *)node();
}
void OSGCamera::setGraphicsContext(osg::GraphicsContext *gc)
{
h->setGraphicsContext(gc);
}
void OSGCamera::update()
{
if (isDirty(ClearColor)) {
h->updateClearColor();
}
if (isDirty(FieldOfView)) {
h->updateFieldOfView();
}
if (isDirty(Position | Attitude)) {
h->updatePosition();
if (isDirty(LogDepthBuffer)) {
h->updateLogDepthBuffer();
}
}
void OSGCamera::attach(osgViewer::View *view)
{
h->attachCamera(view->getCamera());
h->attachManipulator(view);
update();
clearDirty();
}
void OSGCamera::detach(osgViewer::View *view)
{
h->detachManipulator(view);
h->detachCamera(view->getCamera());
}
} // namespace osgQtQuick
#include "OSGCamera.moc"

View File

@ -32,47 +32,17 @@
#include "OSGNode.hpp"
#include <QObject>
#include <QVector3D>
#include <QColor>
namespace osgViewer {
class View;
namespace osg {
class Camera;
class GraphicsContext;
}
namespace osgQtQuick {
class ManipulatorMode : public QObject {
Q_OBJECT
public:
enum Enum { Default, Earth, Track, User };
Q_ENUMS(Enum) // TODO switch to Q_ENUM once on Qt 5.5
};
class TrackerMode : public QObject {
Q_OBJECT
public:
enum Enum { NodeCenter, NodeCenterAndAzim, NodeCenterAndRotation };
Q_ENUMS(Enum) // TODO switch to Q_ENUM once on Qt 5.5
};
// 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 OSGNode {
Q_OBJECT Q_PROPERTY(osgQtQuick::OSGNode *sceneNode READ sceneNode WRITE setSceneNode NOTIFY sceneNodeChanged)
Q_OBJECT Q_PROPERTY(QColor clearColor READ clearColor WRITE setClearColor NOTIFY clearColorChanged)
Q_PROPERTY(qreal fieldOfView READ fieldOfView WRITE setFieldOfView NOTIFY fieldOfViewChanged)
Q_PROPERTY(osgQtQuick::ManipulatorMode::Enum manipulatorMode READ manipulatorMode WRITE setManipulatorMode NOTIFY manipulatorModeChanged)
Q_PROPERTY(osgQtQuick::OSGNode * trackNode READ trackNode WRITE setTrackNode NOTIFY trackNodeChanged)
Q_PROPERTY(osgQtQuick::TrackerMode::Enum 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)
friend class OSGViewport;
@ -81,65 +51,28 @@ public:
explicit OSGCamera(QObject *parent = 0);
virtual ~OSGCamera();
OSGNode *sceneNode() const;
void setSceneNode(OSGNode *node);
QColor clearColor() const;
void setClearColor(const QColor &color);
// 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);
ManipulatorMode::Enum manipulatorMode() const;
void setManipulatorMode(ManipulatorMode::Enum);
OSGNode *trackNode() const;
void setTrackNode(OSGNode *node);
TrackerMode::Enum trackerMode() const;
void setTrackerMode(TrackerMode::Enum);
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() const;
void setLogarithmicDepthBuffer(bool enabled);
signals:
void sceneNodeChanged(OSGNode *node);
void clearColorChanged(const QColor &color);
void fieldOfViewChanged(qreal arg);
void manipulatorModeChanged(ManipulatorMode::Enum);
void trackNodeChanged(OSGNode *node);
void trackerModeChanged(TrackerMode::Enum);
void clampToTerrainChanged(bool arg);
void intoTerrainChanged(bool arg);
void attitudeChanged(QVector3D arg);
void positionChanged(QVector3D arg);
void logarithmicDepthBufferChanged(bool enabled);
private:
struct Hidden;
Hidden *const h;
virtual void update();
osg::Camera *asCamera() const;
void setGraphicsContext(osg::GraphicsContext *gc);
virtual void attach(osgViewer::View *view);
virtual void detach(osgViewer::View *view);
virtual void update();
};
} // namespace osgQtQuick

View File

@ -37,11 +37,14 @@
#include <QDebug>
namespace osgQtQuick {
enum DirtyFlag { Source = 1 << 0, Async = 1 << 1, OptimizeMode = 1 << 2 };
class OSGFileLoader : public QThread {
Q_OBJECT
public:
OSGFileLoader(const QUrl &url) : url(url) {}
OSGFileLoader(const QUrl &url) : url(url)
{}
void run()
{
@ -54,9 +57,12 @@ public:
QElapsedTimer t;
t.start();
qDebug() << "OSGFileLoader::load - reading node file" << url.path();
// qDebug() << "OSGFileLoader::load - reading node file" << url.path();
// qDebug() << "OSGFileLoader - load - currentContext" << QOpenGLContext::currentContext();
osg::Node *node = osgDB::readNodeFile(url.path().toStdString());
if (!node) {
qWarning() << "OSGFileLoader::load - failed to load" << url.path();
}
// qDebug() << "OSGFileLoader::load - reading node" << node << "took" << t.elapsed() << "ms";
return node;
}
@ -79,11 +85,12 @@ public:
bool async;
OptimizeMode::Enum optimizeMode;
Hidden(OSGFileNode *node) : QObject(node), self(node), source(), async(false), optimizeMode(OptimizeMode::None) {}
Hidden(OSGFileNode *self) : QObject(self), self(self), source(), async(false), optimizeMode(OptimizeMode::None)
{}
void updateNode()
{
// qDebug() << "OSGFileNode::updateNode" << source;
qDebug() << "OSGFileNode::updateNode" << source;
if (!source.isValid()) {
self->setNode(NULL);
if (!source.isEmpty()) {
@ -118,7 +125,7 @@ private:
void setNode(osg::Node *node)
{
qDebug() << "OSGFileNode::setNode" << node;
// qDebug() << "OSGFileNode::setNode" << node;
if (node && optimizeMode != OptimizeMode::None) {
// qDebug() << "OSGFileNode::acceptNode - optimize" << node << optimizeMode;
osgUtil::Optimizer optimizer;
@ -139,18 +146,12 @@ private slots:
/* class OSGFileNode */
enum DirtyFlag { Source = 1 << 0, Async = 1 << 1, OptimizeMode = 1 << 2 };
OSGFileNode::OSGFileNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
{
qDebug() << "OSGFileNode::OSGFileNode";
setAsync(false);
setOptimizeMode(OptimizeMode::None);
}
{}
OSGFileNode::~OSGFileNode()
{
// qDebug() << "OSGFileNode::~OSGFileNode";
qDebug() << "OSGFileNode::~OSGFileNode";
delete h;
}
@ -161,7 +162,6 @@ const QUrl OSGFileNode::source() const
void OSGFileNode::setSource(const QUrl &source)
{
qDebug() << "OSGFileNode::setSource" << source;
if (h->source != source) {
h->source = source;
setDirty(Source);
@ -176,7 +176,6 @@ bool OSGFileNode::async() const
void OSGFileNode::setAsync(const bool async)
{
// qDebug() << "OSGFileNode::setAsync" << async;
if (h->async != async) {
h->async = async;
setDirty(Async);
@ -191,7 +190,6 @@ OptimizeMode::Enum OSGFileNode::optimizeMode() const
void OSGFileNode::setOptimizeMode(OptimizeMode::Enum optimizeMode)
{
// qDebug() << "OSGFileNode::setOptimizeMode" << optimizeMode;
if (h->optimizeMode != optimizeMode) {
h->optimizeMode = optimizeMode;
setDirty(OptimizeMode);
@ -211,15 +209,6 @@ void OSGFileNode::update()
h->updateNode();
}
}
void OSGFileNode::attach(osgViewer::View *view)
{
update();
clearDirty();
}
void OSGFileNode::detach(osgViewer::View *view)
{}
} // namespace osgQtQuick
#include "OSGFileNode.moc"

View File

@ -72,9 +72,6 @@ private:
Hidden *const h;
virtual void update();
virtual void attach(osgViewer::View *view);
virtual void detach(osgViewer::View *view);
};
} // namespace osgQtQuick

View File

@ -38,6 +38,8 @@
#include <QDebug>
namespace osgQtQuick {
enum DirtyFlag { Child = 1 << 0, Scene = 1 << 1, Position = 1 << 2, Clamp = 1 << 3 };
struct OSGGeoTransformNode::Hidden : public QObject {
Q_OBJECT
@ -57,7 +59,7 @@ public:
QVector3D position;
Hidden(OSGGeoTransformNode *node) : QObject(node), self(node), childNode(NULL), sceneNode(NULL), offset(-1.0), clampToTerrain(false), intoTerrain(false)
Hidden(OSGGeoTransformNode *self) : QObject(self), self(self), childNode(NULL), sceneNode(NULL), offset(-1.0), clampToTerrain(false), intoTerrain(false)
{
transform = new osgEarth::GeoTransform();
transform->setAutoRecomputeHeights(true);
@ -104,10 +106,10 @@ public:
return true;
}
void updateTransformNode()
void updateChildNode()
{
qDebug() << "OSGGeoTransformNode::updateChildNode" << childNode;
bool updated = false;
if (transform->getNumChildren() == 0) {
if (childNode && childNode->node()) {
updated |= transform->addChild(childNode->node());
@ -129,6 +131,7 @@ public:
void updateSceneNode()
{
qDebug() << "OSGGeoTransformNode::updateSceneNode" << sceneNode;
if (sceneNode && sceneNode->node()) {
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneNode->node());
if (mapNode) {
@ -141,15 +144,19 @@ public:
void updatePosition()
{
osgEarth::MapNode *mapNode = NULL;
qDebug() << "OSGGeoTransformNode::updatePosition" << position;
osgEarth::MapNode *mapNode = NULL;
if (sceneNode && sceneNode->node()) {
mapNode = osgEarth::MapNode::findMapNode(sceneNode->node());
}
if (!mapNode) {
qWarning() << "OSGGeoTransformNode::updatePosition - scene node does not contain a map node";
if (!mapNode) {
qWarning() << "OSGGeoTransformNode::updatePosition - scene node does not contain a map node";
}
} else {
qWarning() << "OSGGeoTransformNode::updatePosition - scene node is not valid";
}
// TODO factorize this logic to utility (same logic is found elsewhere)
osgEarth::GeoPoint geoPoint;
if (mapNode) {
geoPoint = osgQtQuick::toGeoPoint(mapNode->getTerrain()->getSRS(), position);
@ -168,7 +175,10 @@ public:
// clamp model to terrain if needed
intoTerrain = clampGeoPoint(geoPoint, offset, mapNode);
} else if (clampToTerrain) {
qWarning() << "OSGGeoTransformNode::onChildNodeChanged - cannot clamp without map node";
}
transform->setPosition(geoPoint);
}
@ -176,28 +186,25 @@ private slots:
void onChildNodeChanged(osg::Node *node)
{
qDebug() << "OSGGeoTransformNode::onChildNodeChanged" << node;
updateTransformNode();
updateChildNode();
}
void onSceneNodeChanged(osg::Node *node)
{
qDebug() << "OSGGeoTransformNode::onSceneNodeChanged" << node;
// TODO
updateSceneNode();
updatePosition();
}
};
/* class OSGGeoTransformNode */
enum DirtyFlag { Child = 1 << 0, Scene = 1 << 1, Position = 1 << 2, Clamp = 1 << 3 };
OSGGeoTransformNode::OSGGeoTransformNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
{
qDebug() << "OSGGeoTransformNode::OSGGeoTransformNode";
}
{}
OSGGeoTransformNode::~OSGGeoTransformNode()
{
// qDebug() << "OSGGeoTransformNode::~OSGGeoTransformNode";
qDebug() << "OSGGeoTransformNode::~OSGGeoTransformNode";
delete h;
}
@ -263,29 +270,18 @@ void OSGGeoTransformNode::setPosition(QVector3D arg)
void OSGGeoTransformNode::update()
{
if (isDirty(Child)) {
h->updateTransformNode();
h->updateChildNode();
}
if (isDirty(Scene)) {
h->updateSceneNode();
}
if (isDirty(Clamp)) {}
if (isDirty(Clamp)) {
// do nothing...
}
if (isDirty(Position)) {
h->updatePosition();
}
}
void OSGGeoTransformNode::attach(osgViewer::View *view)
{
OSGNode::attach(h->childNode, view);
update();
clearDirty();
}
void OSGGeoTransformNode::detach(osgViewer::View *view)
{
OSGNode::detach(h->childNode, view);
}
} // namespace osgQtQuick
#include "OSGGeoTransformNode.moc"

View File

@ -37,9 +37,9 @@
namespace osgQtQuick {
class OSGQTQUICK_EXPORT OSGGeoTransformNode : public OSGNode {
Q_OBJECT
// TODO rename to childNode
Q_PROPERTY(osgQtQuick::OSGNode *modelData READ childNode WRITE setChildNode NOTIFY childNodeChanged)
// TODO rename to sceneNode
Q_PROPERTY(osgQtQuick::OSGNode *modelData READ childNode WRITE setChildNode NOTIFY childNodeChanged)
// TODO rename to earthNode
Q_PROPERTY(osgQtQuick::OSGNode * sceneData READ sceneNode WRITE setSceneNode NOTIFY sceneNodeChanged)
Q_PROPERTY(bool clampToTerrain READ clampToTerrain WRITE setClampToTerrain NOTIFY clampToTerrainChanged)
@ -80,9 +80,6 @@ private:
Hidden *const h;
virtual void update();
virtual void attach(osgViewer::View *view);
virtual void detach(osgViewer::View *view);
};
} // namespace osgQtQuick

View File

@ -46,14 +46,14 @@ private:
QMap<OSGNode *, osg::Node *> cache;
public:
Hidden(OSGGroup *node) : QObject(node), self(node), group(new osg::Group)
QList<OSGNode *> children;
Hidden(OSGGroup *self) : QObject(self), self(self)
{
group = new osg::Group();
self->setNode(group);
}
QList<OSGNode *> children;
void appendChild(OSGNode *childNode)
{
cache[childNode] = childNode->node();
@ -88,6 +88,7 @@ public:
void updateGroupNode()
{
qDebug() << "OSGGeoTransformNode::updateGroupNode";
bool updated = false;
unsigned int index = 0;
@ -161,13 +162,11 @@ private slots:
/* class OSGGGroupNode */
OSGGroup::OSGGroup(QObject *parent) : OSGNode(parent), h(new Hidden(this))
{
qDebug() << "OSGGroup::OSGGroup";
}
{}
OSGGroup::~OSGGroup()
{
// qDebug() << "OSGGroup::~OSGGroup";
qDebug() << "OSGGroup::~OSGGroup";
delete h;
}
@ -186,30 +185,6 @@ void OSGGroup::update()
h->updateGroupNode();
}
}
void OSGGroup::attach(osgViewer::View *view)
{
// qDebug() << "OSGGroup::attach " << view;
QListIterator<OSGNode *> i(h->children);
while (i.hasNext()) {
OSGNode *node = i.next();
// qDebug() << "OSGGroup::attach - child" << node;
OSGNode::attach(node, view);
}
update();
clearDirty();
}
void OSGGroup::detach(osgViewer::View *view)
{
// qDebug() << "OSGGroup::detach " << view;
QListIterator<OSGNode *> i(h->children);
while (i.hasNext()) {
OSGNode *node = i.next();
// qDebug() << "OSGGroup::detach - child" << node;
OSGNode::detach(node, view);
}
}
} // namespace osgQtQuick
#include "OSGGroup.moc"

View File

@ -50,9 +50,6 @@ private:
Hidden *const h;
virtual void update();
virtual void attach(osgViewer::View *view);
virtual void detach(osgViewer::View *view);
};
} // namespace osgQtQuick

View File

@ -36,9 +36,10 @@ namespace osgQtQuick {
class OSGNode;
class Hidden;
struct NodeUpdateCallback : public osg::NodeCallback {
struct OSGNode::NodeUpdateCallback : public osg::NodeCallback {
public:
NodeUpdateCallback(OSGNode::Hidden *h) : h(h) {}
NodeUpdateCallback(OSGNode::Hidden *h) : h(h)
{}
void operator()(osg::Node *node, osg::NodeVisitor *nv);
@ -58,53 +59,46 @@ private:
osg::ref_ptr<osg::NodeCallback> nodeUpdateCallback;
int dirty;
bool complete;
int dirty;
public:
Hidden(OSGNode *node) : QObject(node), self(node), dirty(0)
Hidden(OSGNode *self) : QObject(self), self(self), complete(false), dirty(0)
{}
bool isDirty(int mask) const
{
return (dirty && mask) != 0;
return (dirty & mask) != 0;
}
void setDirty(int mask)
{
// qDebug() << "OSGNode::setDirty BEGIN";
if (!dirty) {
if (node) {
if (!nodeUpdateCallback.valid()) {
// lazy creation
// qDebug() << "OSGNode::setDirty CREATE";
nodeUpdateCallback = new NodeUpdateCallback(this);
}
// qDebug() << "OSGNode::setDirty ADD" << node;
node->setUpdateCallback(nodeUpdateCallback);
node->addUpdateCallback(nodeUpdateCallback.get());
}
}
dirty |= mask;
// qDebug() << "OSGNode::setDirty DONE";
}
void clearDirty()
{
dirty = 0;
if (node && nodeUpdateCallback.valid()) {
// qDebug() << "OSGNode::clearDirty REMOVE CALLBACK";
node->setUpdateCallback(NULL);
node->removeUpdateCallback(nodeUpdateCallback.get());
}
dirty = 0;
}
void update()
{
// qDebug() << "OSGNode::update BEGIN";
if (dirty) {
// qDebug() << "OSGNode::update UPDATE";
self->update();
}
clearDirty();
// qDebug() << "OSGNode::update DONE";
}
bool acceptNode(osg::Node *aNode)
@ -113,7 +107,6 @@ public:
return false;
}
if (node && dirty) {
// qDebug() << "OSGNode::acceptNode REMOVE CALLBACK" << node;
node->setUpdateCallback(NULL);
}
node = aNode;
@ -121,10 +114,8 @@ public:
if (dirty) {
if (!nodeUpdateCallback.valid()) {
// lazy creation
// qDebug() << "OSGNode::acceptNode CREATE CALLBACK";
nodeUpdateCallback = new NodeUpdateCallback(this);
}
// qDebug() << "OSGNode::acceptNode ADD CALLBACK";
node->setUpdateCallback(nodeUpdateCallback);
}
}
@ -132,14 +123,18 @@ public:
}
};
void NodeUpdateCallback::operator()(osg::Node *node, osg::NodeVisitor *nv)
/* struct OSGNode::NodeUpdateCallback */
void OSGNode::NodeUpdateCallback::operator()(osg::Node *node, osg::NodeVisitor *nv)
{
// qDebug() << "NodeUpdateCallback::";
// qDebug() << "OSGNode::NodeUpdateCallback";
nv->traverse(*node);
h->update();
}
OSGNode::OSGNode(QObject *parent) : QObject(parent), h(new Hidden(this))
/* class OSGNode */
OSGNode::OSGNode(QObject *parent) : QObject(parent), QQmlParserStatus(), h(new Hidden(this))
{}
OSGNode::~OSGNode()
@ -155,7 +150,7 @@ osg::Node *OSGNode::node() const
void OSGNode::setNode(osg::Node *node)
{
if (h->acceptNode(node)) {
emit nodeChanged(node);
emitNodeChanged();
}
}
@ -179,30 +174,37 @@ void OSGNode::clearDirty()
h->clearDirty();
}
void OSGNode::attach(OSGNode *node, osgViewer::View *view)
void OSGNode::classBegin()
{
if (!node) {
return;
}
node->attach(view);
// qDebug() << "OSGNode::classBegin" << this;
}
void OSGNode::detach(OSGNode *node, osgViewer::View *view)
void OSGNode::componentComplete()
{
if (!node) {
return;
qDebug() << "OSGNode::componentComplete" << this;
update();
clearDirty();
h->complete = h->node.valid();
if (!isComponentComplete()) {
qWarning() << "OSGNode::componentComplete - not complete !!!" << this;
}
}
bool OSGNode::isComponentComplete()
{
return h->complete;
}
void OSGNode::emitNodeChanged()
{
if (isComponentComplete()) {
emit nodeChanged(node());
}
node->detach(view);
}
void OSGNode::update()
{}
void OSGNode::attach(osgViewer::View *view)
{}
void OSGNode::detach(osgViewer::View *view)
{}
} // namespace osgQtQuick
#include "OSGNode.moc"

View File

@ -31,6 +31,7 @@
#include "Export.hpp"
#include <QObject>
#include <QQmlParserStatus>
/**
* Only update() methods are allowed to update the OSG scenegraph.
@ -44,17 +45,15 @@
* - if a child sets a parent dirty, the parent will be updated later on the next update traversal (i.e. before the next frame).
*
*/
namespace osg {
class Node;
} // namespace osg
namespace osgViewer {
class View;
} // namespace osgViewer
namespace osgQtQuick {
class OSGQTQUICK_EXPORT OSGNode : public QObject {
class OSGQTQUICK_EXPORT OSGNode : public QObject, public QQmlParserStatus {
Q_OBJECT
Q_INTERFACES(QQmlParserStatus)
friend class OSGViewport;
friend class NodeUpdateCallback;
@ -72,24 +71,21 @@ protected:
void setDirty(int mask);
void clearDirty();
void emitNodeChanged()
{
emit nodeChanged(node());
}
void classBegin();
void componentComplete();
void attach(OSGNode *node, osgViewer::View *view);
void detach(OSGNode *node, osgViewer::View *view);
bool isComponentComplete();
void emitNodeChanged();
signals:
void nodeChanged(osg::Node *node) const;
private:
struct Hidden;
struct NodeUpdateCallback;
Hidden *const h;
virtual void attach(osgViewer::View *view);
virtual void detach(osgViewer::View *view);
virtual void update();
};
} // namespace osgQtQuick

View File

@ -37,6 +37,8 @@
#include <QDebug>
namespace osgQtQuick {
enum DirtyFlag { Type = 1 << 0 };
struct OSGShapeNode::Hidden : public QObject {
Q_OBJECT
@ -46,7 +48,7 @@ private:
public:
ShapeType::Enum shapeType;
Hidden(OSGShapeNode *node) : QObject(node), self(node), shapeType(ShapeType::Sphere)
Hidden(OSGShapeNode *self) : QObject(self), self(self), shapeType(ShapeType::Sphere)
{}
void updateNode()
@ -74,19 +76,16 @@ public:
/* class OSGShapeNode */
enum DirtyFlag { Type = 1 << 0 };
// TODO turn into generic shape node...
// see http://trac.openscenegraph.org/projects/osg//wiki/Support/Tutorials/TransformsAndStates
OSGShapeNode::OSGShapeNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
{
qDebug() << "OSGShapeNode::OSGShapeNode";
setShapeType(ShapeType::Sphere);
setDirty(Type);
}
OSGShapeNode::~OSGShapeNode()
{
// qDebug() << "OSGShapeNode::~OSGShapeNode";
qDebug() << "OSGShapeNode::~OSGShapeNode";
delete h;
}
@ -110,15 +109,6 @@ void OSGShapeNode::update()
h->updateNode();
}
}
void OSGShapeNode::attach(osgViewer::View *view)
{
update();
clearDirty();
}
void OSGShapeNode::detach(osgViewer::View *view)
{}
} // namespace osgQtQuick
#include "OSGShapeNode.moc"

View File

@ -57,9 +57,6 @@ private:
Hidden *const h;
virtual void update();
virtual void attach(osgViewer::View *view);
virtual void detach(osgViewer::View *view);
};
} // namespace osgQtQuick

View File

@ -27,6 +27,8 @@
#include "OSGSkyNode.hpp"
#include "OSGViewport.hpp"
#include <osgViewer/View>
#include <osgEarth/Config>
@ -39,6 +41,8 @@
#include <QDebug>
namespace osgQtQuick {
enum DirtyFlag { Scene = 1 << 0, Viewport = 1 << 1, DateTime = 1 << 2, Light = 1 << 3 };
struct OSGSkyNode::Hidden : public QObject {
Q_OBJECT
@ -48,13 +52,15 @@ private:
osg::ref_ptr<osgEarth::Util::SkyNode> skyNode;
public:
OSGNode *sceneNode;
OSGNode *sceneNode;
OSGViewport *viewport;
bool sunLightEnabled;
QDateTime dateTime;
double minimumAmbientLight;
bool sunLightEnabled;
QDateTime dateTime;
double minimumAmbientLight;
Hidden(OSGSkyNode *node) : QObject(node), self(node), sceneNode(NULL), sunLightEnabled(true), minimumAmbientLight(0.03)
Hidden(OSGSkyNode *self) : QObject(self), self(self), sceneNode(NULL), viewport(NULL),
sunLightEnabled(true), minimumAmbientLight(0.03)
{
dateTime = QDateTime::currentDateTime();
}
@ -85,18 +91,19 @@ public:
void updateSkyNode()
{
if (!sceneNode || !sceneNode->node()) {
qWarning() << "OSGSkyNode::acceptNode - scene node not valid";
qWarning() << "OSGSkyNode::updateSkyNode - scene node not valid";
self->setNode(NULL);
return;
}
qDebug() << "OSGSkyNode::updateSkyNode - scene node" << sceneNode->node();
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneNode->node());
if (!mapNode) {
qWarning() << "OSGSkyNode::acceptNode - scene node does not contain a map node";
qWarning() << "OSGSkyNode::updateSkyNode - scene node does not contain a map node";
self->setNode(NULL);
return;
}
if (!mapNode->getMap()->isGeocentric()) {
qWarning() << "OSGSkyNode::acceptNode - map node is not geocentric";
qWarning() << "OSGSkyNode::updateSkyNode - map node is not geocentric";
self->setNode(NULL);
return;
}
@ -142,8 +149,23 @@ public:
}
*/
void updateViewport()
{
qDebug() << "OSGSkyNode::updateViewport" << skyNode;
if (!skyNode.valid()) {
qWarning() << "OSGSkyNode::updateViewport - invalid sky node" << skyNode;
return;
}
qDebug() << "OSGSkyNode::updateViewport - attaching to" << viewport->asView();
skyNode->attach(viewport->asView());
}
void updateSunLightEnabled()
{
if (!skyNode.valid()) {
qWarning() << "OSGSkyNode::updateSunLightEnabled - invalid sky node";
return;
}
if (!skyNode.valid()) {
return;
}
@ -153,10 +175,11 @@ public:
void updateDateTime()
{
if (!skyNode.valid()) {
qWarning() << "OSGSkyNode::updateDateTime - invalid sky node";
return;
}
if (!dateTime.isValid()) {
qWarning() << "OSGSkyNode::acceptDateTime - invalid date/time" << dateTime;
qWarning() << "OSGSkyNode::updateDateTime - invalid date/time" << dateTime;
}
QDate date = dateTime.date();
@ -168,6 +191,7 @@ public:
void updateMinimumAmbientLight()
{
if (!skyNode.valid()) {
qWarning() << "OSGSkyNode::updateMinimumAmbientLight - invalid sky node";
return;
}
double d = minimumAmbientLight;
@ -199,18 +223,14 @@ private slots:
/* class OSGSkyNode */
enum DirtyFlag { Child = 1 << 0, DateTime = 1 << 1, Light = 1 << 2 };
OSGSkyNode::OSGSkyNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
{
qDebug() << "OSGSkyNode::OSGSkyNode";
setSunLightEnabled(true);
setMinimumAmbientLight(0.03);
setDirty(DateTime | Light);
}
OSGSkyNode::~OSGSkyNode()
{
// qDebug() << "OSGSkyNode::~OSGSkyNode";
qDebug() << "OSGSkyNode::~OSGSkyNode";
delete h;
}
@ -222,11 +242,25 @@ OSGNode *OSGSkyNode::sceneNode() const
void OSGSkyNode::setSceneNode(OSGNode *node)
{
if (h->acceptSceneNode(node)) {
setDirty(Child);
setDirty(Scene);
emit sceneNodeChanged(node);
}
}
OSGViewport *OSGSkyNode::viewport() const
{
return h->viewport;
}
void OSGSkyNode::setViewport(OSGViewport *viewport)
{
if (h->viewport != viewport) {
h->viewport = viewport;
setDirty(Viewport);
emit viewportChanged(viewport);
}
}
bool OSGSkyNode::sunLightEnabled() const
{
return h->sunLightEnabled;
@ -271,9 +305,12 @@ void OSGSkyNode::setMinimumAmbientLight(double ambient)
void OSGSkyNode::update()
{
if (isDirty(Child)) {
if (isDirty(Scene)) {
h->updateSkyNode();
}
if (isDirty(Viewport)) {
h->updateViewport();
}
if (isDirty(Light)) {
h->updateSunLightEnabled();
h->updateMinimumAmbientLight();
@ -282,23 +319,6 @@ void OSGSkyNode::update()
h->updateDateTime();
}
}
void OSGSkyNode::attach(osgViewer::View *view)
{
// qDebug() << "OSGSkyNode::attach " << view;
OSGNode::attach(h->sceneNode, view);
h->attachSkyNode(view);
update();
clearDirty();
}
void OSGSkyNode::detach(osgViewer::View *view)
{
// qDebug() << "OSGSkyNode::detach " << view;
h->detachSkyNode(view);
OSGNode::detach(h->sceneNode, view);
}
} // namespace osgQtQuick
#include "OSGSkyNode.moc"

View File

@ -43,9 +43,12 @@ class QUrl;
QT_END_NAMESPACE
namespace osgQtQuick {
class OSGViewport;
class OSGQTQUICK_EXPORT OSGSkyNode : public OSGNode {
// TODO rename to sceneNode
Q_OBJECT Q_PROPERTY(osgQtQuick::OSGNode *sceneData READ sceneNode WRITE setSceneNode NOTIFY sceneNodeChanged)
Q_PROPERTY(osgQtQuick::OSGViewport * viewport READ viewport WRITE setViewport NOTIFY viewportChanged)
Q_PROPERTY(bool sunLightEnabled READ sunLightEnabled WRITE setSunLightEnabled NOTIFY sunLightEnabledChanged)
Q_PROPERTY(QDateTime dateTime READ dateTime WRITE setDateTime NOTIFY dateTimeChanged)
@ -58,6 +61,9 @@ public:
OSGNode *sceneNode() const;
void setSceneNode(OSGNode *node);
OSGViewport *viewport() const;
void setViewport(OSGViewport *viewport);
bool sunLightEnabled() const;
void setSunLightEnabled(bool arg);
@ -69,6 +75,7 @@ public:
signals:
void sceneNodeChanged(OSGNode *node);
void viewportChanged(OSGViewport *viewport);
void sunLightEnabledChanged(bool arg);
void dateTimeChanged(QDateTime arg);
@ -79,9 +86,6 @@ private:
Hidden *const h;
virtual void update();
virtual void attach(osgViewer::View *view);
virtual void detach(osgViewer::View *view);
};
} // namespace osgQtQuick

View File

@ -37,6 +37,8 @@
#include <QColor>
namespace osgQtQuick {
enum DirtyFlag { Text = 1 << 0, Color = 1 << 1 };
struct OSGTextNode::Hidden : public QObject {
Q_OBJECT
@ -49,7 +51,7 @@ public:
QString textString;
QColor color;
Hidden(OSGTextNode *node) : QObject(node), self(node)
Hidden(OSGTextNode *self) : QObject(self), self(self)
{
osg::ref_ptr<osgText::Font> textFont = createFont(QFont("Times"));
@ -88,10 +90,10 @@ public:
/* class OSGTextNode */
enum DirtyFlag { Text = 1 << 0, Color = 1 << 1 };
OSGTextNode::OSGTextNode(QObject *node) : OSGNode(node), h(new Hidden(this))
{}
OSGTextNode::OSGTextNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
{
setDirty(Text | Color);
}
OSGTextNode::~OSGTextNode()
{
@ -135,15 +137,6 @@ void OSGTextNode::update()
h->updateColor();
}
}
void OSGTextNode::attach(osgViewer::View *view)
{
update();
clearDirty();
}
void OSGTextNode::detach(osgViewer::View *view)
{}
} // namespace osgQtQuick
#include "OSGTextNode.moc"

View File

@ -57,9 +57,6 @@ private:
Hidden *const h;
virtual void update();
virtual void attach(osgViewer::View *view);
virtual void detach(osgViewer::View *view);
};
} // namespace osgQtQuick

View File

@ -34,6 +34,8 @@
#include <QDebug>
namespace osgQtQuick {
enum DirtyFlag { Child = 1 << 0, Scale = 1 << 1, Position = 1 << 2, Attitude = 1 << 3 };
struct OSGTransformNode::Hidden : public QObject {
Q_OBJECT
@ -49,7 +51,7 @@ public:
QVector3D attitude;
QVector3D position;
Hidden(OSGTransformNode *node) : QObject(node), self(node), childNode(NULL)
Hidden(OSGTransformNode *self) : QObject(self), self(self), childNode(NULL)
{
transform = new osg::PositionAttitudeTransform();
self->setNode(transform);
@ -75,10 +77,10 @@ public:
return true;
}
void updateTransformNode()
void updateChildNode()
{
qDebug() << "OSGTransformNode::updateChildNode" << childNode;
bool updated = false;
if (transform->getNumChildren() == 0) {
if (childNode && childNode->node()) {
updated |= transform->addChild(childNode->node());
@ -100,6 +102,7 @@ public:
void updateScale()
{
qDebug() << "OSGTransformNode::updateScale" << 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);
@ -118,9 +121,6 @@ public:
yaw, osg::Vec3d(0, 0, -1));
transform->setAttitude(q);
// position
transform->setPosition(osg::Vec3d(position.x(), position.y(), position.z()));
}
void updatePosition()
@ -132,22 +132,18 @@ private slots:
void onChildNodeChanged(osg::Node *node)
{
qDebug() << "OSGTransformNode::onChildNodeChanged" << node;
updateTransformNode();
updateChildNode();
}
};
/* class OSGTransformNode */
enum DirtyFlag { Child = 1 << 0, Scale = 1 << 1, Position = 1 << 2, Attitude = 1 << 3 };
OSGTransformNode::OSGTransformNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
{
qDebug() << "OSGTransformNode::OSGTransformNode";
}
{}
OSGTransformNode::~OSGTransformNode()
{
// qDebug() << "OSGTransformNode::~OSGTransformNode";
qDebug() << "OSGTransformNode::~OSGTransformNode";
delete h;
}
@ -209,7 +205,7 @@ void OSGTransformNode::setPosition(QVector3D arg)
void OSGTransformNode::update()
{
if (isDirty(Child)) {
h->updateTransformNode();
h->updateChildNode();
}
if (isDirty(Scale)) {
h->updateScale();
@ -221,19 +217,6 @@ void OSGTransformNode::update()
h->updatePosition();
}
}
void OSGTransformNode::attach(osgViewer::View *view)
{
OSGNode::attach(h->childNode, view);
update();
clearDirty();
}
void OSGTransformNode::detach(osgViewer::View *view)
{
OSGNode::detach(h->childNode, view);
}
} // namespace osgQtQuick
#include "OSGTransformNode.moc"

View File

@ -72,9 +72,6 @@ private:
Hidden *const h;
virtual void update();
virtual void attach(osgViewer::View *view);
virtual void detach(osgViewer::View *view);
};
} // namespace osgQtQuick

View File

@ -34,6 +34,7 @@
#include "OSGCamera.hpp"
#include <osg/Node>
#include <osg/Vec4>
#include <osg/DeleteHandler>
#include <osg/GLObjects>
#include <osg/ApplicationUsage>
@ -41,10 +42,7 @@
#include <osgViewer/CompositeViewer>
#include <osgViewer/ViewerEventHandlers>
#include <osgGA/StateSetManipulator>
#ifdef USE_OSGEARTH
#include <osgEarth/MapNode>
#endif
#include <osgGA/CameraManipulator>
#include <QOpenGLContext>
#include <QQuickWindow>
@ -55,9 +53,6 @@
#include <QDebug>
#include <QThread>
#include <QApplication>
/*
Debugging tips
- export OSG_NOTIFY_LEVEL=DEBUG
@ -80,6 +75,8 @@
*/
namespace osgQtQuick {
enum DirtyFlag { Scene = 1 << 0, Camera = 1 << 1 };
class ViewportRenderer;
struct OSGViewport::Hidden : public QObject {
@ -94,27 +91,26 @@ private:
int frameTimer;
osg::ref_ptr<osg::GraphicsContext> gc;
public:
OSGNode *sceneNode;
OSGCamera *camera;
OSGCamera *cameraNode;
osg::ref_ptr<osgViewer::CompositeViewer> viewer;
osg::ref_ptr<osgViewer::View> view;
UpdateMode::Enum updateMode;
OSGCameraManipulator *manipulator;
UpdateMode::Enum updateMode;
bool busy;
static QtKeyboardMap keyMap;
Hidden(OSGViewport *viewport) : QObject(viewport),
self(viewport),
window(NULL),
frameTimer(-1),
sceneNode(NULL),
camera(NULL),
updateMode(UpdateMode::OnDemand),
busy(false)
Hidden(OSGViewport *self) : QObject(self), self(self), window(NULL), frameTimer(-1),
sceneNode(NULL), cameraNode(NULL), manipulator(NULL), updateMode(UpdateMode::OnDemand), busy(false)
{
OsgEarth::initialize();
@ -125,7 +121,9 @@ public:
~Hidden()
{
stop();
disconnect(self);
stopTimer();
destroyViewer();
}
@ -137,13 +135,16 @@ public slots:
// 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);
// 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);
// connect(window, &QQuickWindow::visibleChanged, this, &Hidden::visibleChanged, Qt::DirectConnection);
// connect(window, &QQuickWindow::widthChanged, this, &Hidden::widthChanged, Qt::DirectConnection);
// connect(window, &QQuickWindow::heightChanged, this, &Hidden::heightChanged, Qt::DirectConnection);
} else {
if (this->window) {
disconnect(this->window);
}
// if (this->window) {
// disconnect(this->window);
// }
}
this->window = window;
}
@ -163,123 +164,99 @@ public:
sceneNode = node;
if (sceneNode) {
connect(sceneNode, &OSGNode::nodeChanged, this, &Hidden::onNodeChanged);
connect(sceneNode, &OSGNode::nodeChanged, this, &Hidden::onSceneNodeChanged);
}
return true;
}
void attach(osgViewer::View *view)
bool acceptCameraNode(OSGCamera *node)
{
if (!sceneNode) {
qWarning() << "OSGViewport::attach - invalid scene!";
return;
qDebug() << "OSGViewport::acceptCameraNode" << node;
if (cameraNode == node) {
return true;
}
// attach scene
attach(view, sceneNode->node());
// attach camera
if (camera) {
camera->attach(view);
} else {
qWarning() << "OSGViewport::attach - no camera!";
if (cameraNode) {
disconnect(cameraNode);
}
cameraNode = node;
if (cameraNode) {
connect(cameraNode, &OSGNode::nodeChanged, this, &Hidden::onCameraNodeChanged);
}
return true;
}
void attach(osgViewer::View *view, osg::Node *node)
bool acceptManipulator(OSGCameraManipulator *m)
{
if (!view) {
qWarning() << "OSGViewport::attach - view is null";
return;
}
if (!node) {
qWarning() << "OSGViewport::attach - node is null";
view->setSceneData(NULL);
return;
qDebug() << "OSGViewport::acceptManipulator" << manipulator;
if (manipulator == m) {
return true;
}
#ifdef USE_OSGEARTH
// TODO map handling should not be done here
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(node);
if (mapNode) {
qDebug() << "OSGViewport::attach - found map node" << mapNode;
manipulator = m;
// remove light to prevent unnecessary state changes in SceneView
// scene will get light from sky (works only with latest > 2.7)
// view->setLightingMode(osg::View::NO_LIGHT);
}
#endif
qDebug() << "OSGViewport::attach - set scene" << node;
view->setSceneData(node);
}
void detach(osgViewer::View *view)
{
// detach camera
if (camera) {
camera->detach(view);
}
// detach scene
view->setSceneData(NULL);
}
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");
return true;
}
void initializeResources()
{
qDebug() << "OSGViewport::initializeResources";
if (view.valid()) {
qWarning() << "OSGViewport::initializeResources - view already created!";
if (gc.valid()) {
// qWarning() << "OSGViewport::initializeResources - gc already created!";
return;
}
view = createView();
viewer->addView(view);
self->attach(view.get());
start();
qDebug() << "OSGViewport::initializeResources";
// setup graphics context and camera
gc = createGraphicsContext();
cameraNode->setGraphicsContext(gc);
qDebug() << "OSGViewport::initializeResources - camera" << cameraNode->asCamera();
view->setCamera(cameraNode->asCamera());
qDebug() << "OSGViewport::initializeResources - scene data" << sceneNode->node();
view->setSceneData(sceneNode->node());
if (manipulator) {
osgGA::CameraManipulator *m = manipulator->asCameraManipulator();
qDebug() << "OSGViewport::initializeResources - manipulator" << m;
// Setting the manipulator on the camera will change the manipulator node (used to compute the camera home position)
// to the view scene node. So we need to save and restore the manipulator node.
osg::Node *node = m->getNode();
view->setCameraManipulator(m, false);
if (node) {
m->setNode(node);
}
view->home();
} else {
view->setCameraManipulator(NULL, false);
}
installHanders();
startTimer();
}
void releaseResources()
{
qDebug() << "OSGViewport::releaseResources";
if (!view.valid()) {
qWarning() << "OSGViewport::releaseResources - view is not valid!";
if (!gc.valid()) {
qWarning() << "OSGViewport::releaseResources - gc is not valid!";
return;
}
osg::deleteAllGLObjects(view->getCamera()->getGraphicsContext()->getState()->getContextID());
osg::deleteAllGLObjects(gc->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 acceptCamera(OSGCamera *camera)
{
qDebug() << "OSGViewport::acceptCamera" << camera;
if (this->camera == camera) {
return true;
}
this->camera = camera;
return true;
}
private:
void createViewer()
{
@ -297,6 +274,9 @@ private:
// disable the default setting of viewer.done() by pressing Escape.
viewer->setKeyEventSetsDone(0);
// viewer->setQuitEventSetsDone(false);
view = createView();
viewer->addView(view);
}
void destroyViewer()
@ -316,6 +296,15 @@ private:
qDebug() << "OSGViewport::createView";
osgViewer::View *view = new osgViewer::View();
// TODO expose as Qml properties
view->setLightingMode(osgViewer::View::SKY_LIGHT);
view->getLight()->setAmbient(osg::Vec4(0.6f, 0.6f, 0.6f, 1.0f));
return view;
}
void installHanders()
{
// TODO will the handlers be destroyed???
// add the state manipulator
view->addEventHandler(new osgGA::StateSetManipulator(view->getCamera()->getOrCreateStateSet()));
@ -341,19 +330,6 @@ private:
// add the screen capture handler
// view->addEventHandler(new osgViewer::ScreenCaptureHandler);
// setup graphics context and camera
osg::GraphicsContext *gc = createGraphicsContext();
// TODO expose as Qml properties
view->setLightingMode(osgViewer::View::SKY_LIGHT);
view->getLight()->setAmbient(osg::Vec4(0.6f, 0.6f, 0.6f, 1.0f));
osg::Camera *camera = view->getCamera();
camera->setGraphicsContext(gc);
camera->setViewport(0, 0, gc->getTraits()->width, gc->getTraits()->height);
return view;
}
osg::GraphicsContext *createGraphicsContext()
@ -407,19 +383,19 @@ private:
return traits;
}
void start()
void startTimer()
{
if (updateMode != UpdateMode::Continuous && (frameTimer < 0)) {
qDebug() << "OSGViewport::start - starting timer";
frameTimer = startTimer(33, Qt::PreciseTimer);
if ((updateMode != UpdateMode::Continuous) && (frameTimer < 0)) {
qDebug() << "OSGViewport::startTimer - starting timer";
frameTimer = QObject::startTimer(33, Qt::PreciseTimer);
}
}
void stop()
void stopTimer()
{
if (frameTimer >= 0) {
qDebug() << "OSGViewport::stop - killing timer";
killTimer(frameTimer);
qDebug() << "OSGViewport::stopTimer - killing timer";
QObject::killTimer(frameTimer);
frameTimer = -1;
}
}
@ -439,29 +415,33 @@ protected:
private slots:
void onNodeChanged(osg::Node *node)
void onSceneNodeChanged(osg::Node *node)
{
qDebug() << "OSGViewport::onNodeChanged" << node;
qWarning() << "OSGViewport::onNodeChanged - not implemented";
// if (view.valid()) {
// acceptNode(node);
// }
qWarning() << "OSGViewport::onSceneNodeChanged - not implemented";
}
void onCameraNodeChanged(osg::Node *node)
{
qWarning() << "OSGViewport::onCameraNodeChanged - not implemented";
}
};
/* class ViewportRenderer */
class ViewportRenderer : public QQuickFramebufferObject::Renderer {
private:
OSGViewport::Hidden *const h;
int frameCount;
bool needToDoFrame;
public:
ViewportRenderer(OSGViewport::Hidden *h) : h(h)
ViewportRenderer(OSGViewport::Hidden *h) : h(h), frameCount(0), needToDoFrame(false)
{
qDebug() << "ViewportRenderer::ViewportRenderer";
// osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "ViewportRenderer::ViewportRenderer");
h->initializeResources();
firstFrame = true;
needToDoFrame = false;
}
~ViewportRenderer()
@ -486,25 +466,42 @@ public:
return;
}
needToDoFrame = firstFrame;
// we want to always draw the first frame
needToDoFrame = (frameCount == 0);
// if not on-demand then do frame
if (h->updateMode != UpdateMode::OnDemand) {
needToDoFrame = true;
}
if (firstFrame) {
if (frameCount == 0) {
h->view->init();
if (!h->viewer->isRealized()) {
h->viewer->realize();
}
firstFrame = false;
}
osg::Viewport *viewport = h->view->getCamera()->getViewport();
if ((viewport->width() != item->width()) || (viewport->height() != item->height())) {
qDebug() << "*** RESIZE" << frameCount << viewport->width() << "x" << viewport->height() << "->" << item->width() << "x" << item->height();
needToDoFrame = true;
// h->view->getCamera()->resize(item->width(), item->height());
int dpr = h->self->window()->devicePixelRatio();
h->view->getCamera()->getGraphicsContext()->resized(0, 0, item->width() * dpr, item->height() * dpr);
// h->view.get()->getEventQueue()->windowResize(0, 0, item->width() * dpr, item->height() * dpr);
// trick to force a "home" on first few frames to absorb initial spurious resizes
if (frameCount <= 2) {
h->view->home();
}
}
// refresh busy state
h->self->setBusy(h->view->getDatabasePager()->getRequestsInProgress());
// TODO also expose request list size to Qml
if (h->view->getDatabasePager()->getFileRequestListSize() > 0) {
// qDebug() << h->view->getDatabasePager()->getFileRequestListSize();
}
h->self->setBusy(h->view->getDatabasePager()->getRequestsInProgress());
@ -515,16 +512,39 @@ public:
needToDoFrame = h->viewer->checkNeedToDoFrame();
}
if (!needToDoFrame) {
// calling checkNeedToDoFrame is not enough...
// workarounds to osg issues
needToDoFrame = !h->view->getEventQueue()->empty();
if (h->view->getSceneData()) {
needToDoFrame |= !(h->view->getSceneData()->getUpdateCallback() == NULL);
}
}
if (needToDoFrame) {
// qDebug() << "ViewportRenderer::synchronize - update scene" << frameCount;
// info();
h->viewer->advance();
h->viewer->eventTraversal();
h->viewer->updateTraversal();
}
}
void info()
{
if (!h->view.valid()) {
return;
}
// If the database pager is going to update the scene the render flag is
// set so that the updates show up
qDebug() << "DatabasePager" << (h->view->getDatabasePager()->requiresUpdateSceneGraph() || h->view->getDatabasePager()->getRequestsInProgress());
// if there update callbacks then we need to do frame.
qDebug() << "Camera" << (h->view->getCamera()->getUpdateCallback());
qDebug() << "Scene" << (h->view->getSceneData() && h->view->getSceneData()->getNumChildrenRequiringUpdateTraversal() > 0);
// check if events are available and need processing
qDebug() << "Events" << (h->viewer->checkEvents());
}
// 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()
@ -538,6 +558,8 @@ public:
}
if (needToDoFrame) {
// qDebug() << "ViewportRenderer::render - render scene" << frameCount;
// needed to properly render models without terrain (Qt bug?)
QOpenGLContext::currentContext()->functions()->glUseProgram(0);
h->viewer->renderingTraversals();
@ -548,6 +570,8 @@ public:
// trigger next update
update();
}
++frameCount;
}
QOpenGLFramebufferObject *createFramebufferObject(const QSize &size)
@ -557,6 +581,28 @@ public:
format.setAttachment(QOpenGLFramebufferObject::CombinedDepthStencil);
// format.setSamples(4);
/**
* that's a typical error when working with high-resolution (retina)
displays. The issue here is that on the high-resolution devices, the UI
operates with a virtual pixel size that is smaller than the real number
of pixels on the device. For example, you get coordinates from 0 to 2048
while the real device resolution if 4096 pixels. This factor has to be
taken into account when mapping from window coordinates to OpenGL, e.g.,
when calling glViewport.
How you can get this factor depends on the GUI library you are using. In
Qt, you can query it with QWindow::devicePixelRatio():
http://doc.qt.io/qt-5/qwindow.html#devicePixelRatio
So, there should be something like
glViewport(0, 0, window->width() * window->devicePixelRatio(),
window->height() * window->devicePixelRatio()).
Also keep in mind that you have to do the same e.g. for mouse coordinates.
I think osgQt already handles this correctly, so you shouldn't have to
worry about this if you use the classes provided by osgQt ...
*/
// Keeping this for reference :
// Mac need(ed) to have devicePixelRatio (dpr) taken into account (i.e. dpr = 2).
// Further tests on Mac have shown that although dpr is still 2 it should not be used to scale the fbo.
@ -566,12 +612,6 @@ public:
return fbo;
}
private:
OSGViewport::Hidden *const h;
bool firstFrame;
bool needToDoFrame;
};
QtKeyboardMap OSGViewport::Hidden::keyMap = QtKeyboardMap();
@ -580,7 +620,6 @@ QtKeyboardMap OSGViewport::Hidden::keyMap = QtKeyboardMap();
OSGViewport::OSGViewport(QQuickItem *parent) : QQuickFramebufferObject(parent), h(new Hidden(this))
{
qDebug() << "OSGViewport::OSGViewport";
// setClearBeforeRendering(false);
setMirrorVertically(true);
setAcceptHoverEvents(true);
@ -601,19 +640,34 @@ OSGNode *OSGViewport::sceneNode() const
void OSGViewport::setSceneNode(OSGNode *node)
{
if (h->acceptSceneNode(node)) {
// setDirty(Scene);
emit sceneNodeChanged(node);
}
}
OSGCamera *OSGViewport::camera() const
OSGCamera *OSGViewport::cameraNode() const
{
return h->camera;
return h->cameraNode;
}
void OSGViewport::setCamera(OSGCamera *camera)
void OSGViewport::setCameraNode(OSGCamera *node)
{
if (h->acceptCamera(camera)) {
emit cameraChanged(camera);
if (h->acceptCameraNode(node)) {
// setDirty(Camera);
emit cameraNodeChanged(node);
}
}
OSGCameraManipulator *OSGViewport::manipulator() const
{
return h->manipulator;
}
void OSGViewport::setManipulator(OSGCameraManipulator *manipulator)
{
if (h->acceptManipulator(manipulator)) {
// setDirty(Manipulator);
emit manipulatorChanged(manipulator);
}
}
@ -643,21 +697,9 @@ void OSGViewport::setBusy(const bool busy)
}
}
QColor OSGViewport::color() const
osgViewer::View *OSGViewport::asView() 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);
}
return h->view;
}
QQuickFramebufferObject::Renderer *OSGViewport::createRenderer() const
@ -667,29 +709,23 @@ QQuickFramebufferObject::Renderer *OSGViewport::createRenderer() const
return new ViewportRenderer(h);
}
void OSGViewport::attach(osgViewer::View *view)
{
// qDebug() << "OSGViewport::attach" << view;
if (h->sceneNode) {
h->sceneNode->attach(view);
}
h->attach(view);
}
void OSGViewport::detach(osgViewer::View *view)
{
qDebug() << "OSGViewport::detach" << view;
h->detach(view);
if (h->sceneNode) {
h->sceneNode->detach(view);
}
}
void OSGViewport::releaseResources()
{
QQuickFramebufferObject::releaseResources();
}
void OSGViewport::classBegin()
{
// qDebug() << "OSGViewport::classBegin" << this;
QQuickFramebufferObject::classBegin();
}
void OSGViewport::componentComplete()
{
qDebug() << "OSGViewport::componentComplete" << this;
QQuickFramebufferObject::componentComplete();
}
// see https://bugreports.qt-project.org/browse/QTBUG-41073
QSGNode *OSGViewport::updatePaintNode(QSGNode *node, QQuickItem::UpdatePaintNodeData *nodeData)
{

View File

@ -30,6 +30,8 @@
#include "Export.hpp"
#include "ga/OSGCameraManipulator.hpp"
#include <QQuickFramebufferObject>
namespace osgViewer {
@ -50,10 +52,10 @@ public:
class OSGQTQUICK_EXPORT OSGViewport : public QQuickFramebufferObject {
Q_OBJECT Q_PROPERTY(osgQtQuick::OSGNode *sceneData READ sceneNode WRITE setSceneNode NOTIFY sceneNodeChanged)
Q_PROPERTY(osgQtQuick::OSGCamera * camera READ camera WRITE setCamera NOTIFY cameraChanged)
Q_PROPERTY(osgQtQuick::OSGCamera * camera READ cameraNode WRITE setCameraNode NOTIFY cameraNodeChanged)
Q_PROPERTY(osgQtQuick::OSGCameraManipulator * manipulator READ manipulator WRITE setManipulator NOTIFY manipulatorChanged)
Q_PROPERTY(osgQtQuick::UpdateMode::Enum updateMode READ updateMode WRITE setUpdateMode NOTIFY updateModeChanged)
Q_PROPERTY(bool busy READ busy NOTIFY busyChanged)
Q_PROPERTY(QColor color READ color WRITE setColor NOTIFY colorChanged)
public:
friend class ViewportRenderer;
@ -64,8 +66,11 @@ public:
OSGNode *sceneNode() const;
void setSceneNode(OSGNode *node);
OSGCamera *camera() const;
void setCamera(OSGCamera *camera);
OSGCamera *cameraNode() const;
void setCameraNode(OSGCamera *node);
OSGCameraManipulator *manipulator() const;
void setManipulator(OSGCameraManipulator *manipulator);
UpdateMode::Enum updateMode() const;
void setUpdateMode(UpdateMode::Enum mode);
@ -73,20 +78,24 @@ public:
bool busy() const;
void setBusy(const bool busy);
QColor color() const;
void setColor(const QColor &color);
Renderer *createRenderer() const;
void releaseResources();
osgViewer::View *asView() const;
signals:
void sceneNodeChanged(OSGNode *node);
void cameraChanged(OSGCamera *camera);
void cameraNodeChanged(OSGCamera *node);
void manipulatorChanged(OSGCameraManipulator *manipulator);
void updateModeChanged(UpdateMode::Enum mode);
void busyChanged(bool busy);
void colorChanged(const QColor &color);
protected:
QSGNode *updatePaintNode(QSGNode *oldNode, UpdatePaintNodeData *updatePaintNodeData);
void classBegin();
void componentComplete();
void mousePressEvent(QMouseEvent *event);
void mouseMoveEvent(QMouseEvent *event);
void mouseReleaseEvent(QMouseEvent *event);
@ -97,11 +106,6 @@ protected:
void setKeyboardModifiers(QInputEvent *event);
QPointF mousePoint(QMouseEvent *event);
QSGNode *updatePaintNode(QSGNode *oldNode, UpdatePaintNodeData *updatePaintNodeData);
void attach(osgViewer::View *view);
void detach(osgViewer::View *view);
private:
struct Hidden;
Hidden *const h;

View File

@ -0,0 +1,143 @@
/**
******************************************************************************
*
* @file OSGCameraManipulator.cpp
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @addtogroup
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* 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 "OSGCameraManipulator.hpp"
#include "../OSGNode.hpp"
#include <osgGA/CameraManipulator>
#include <QDebug>
namespace osgQtQuick {
struct OSGCameraManipulator::Hidden : public QObject {
Q_OBJECT
private:
OSGCameraManipulator * const self;
public:
osg::ref_ptr<osgGA::CameraManipulator> manipulator;
OSGNode *sceneNode;
public:
Hidden(OSGCameraManipulator *self) : QObject(self), self(self), sceneNode(NULL)
{}
~Hidden()
{}
bool acceptSceneNode(OSGNode *node)
{
qDebug() << "OSGCameraManipulator::acceptSceneNode" << node;
if (sceneNode == node) {
return true;
}
if (sceneNode) {
disconnect(sceneNode);
}
sceneNode = node;
if (sceneNode) {
connect(sceneNode, &OSGNode::nodeChanged, this, &Hidden::onSceneNodeChanged);
}
return true;
}
void updateSceneNode()
{
if (!sceneNode) {
qWarning() << "OSGCameraManipulator::updateSceneNode - no scene node";
return;
}
qDebug() << "OSGCameraManipulator::updateSceneNode" << sceneNode->node();
manipulator->setNode(sceneNode->node());
}
private slots:
void onSceneNodeChanged(osg::Node *node)
{
qDebug() << "OSGCameraManipulator::onSceneNodeChanged" << node;
qWarning() << "OSGCameraManipulator::onSceneNodeChanged - needs to be implemented";
}
};
/* class OSGCameraManipulator */
OSGCameraManipulator::OSGCameraManipulator(QObject *parent) : QObject(parent), h(new Hidden(this))
{}
OSGCameraManipulator::~OSGCameraManipulator()
{
qDebug() << "OSGCameraManipulator::~OSGCameraManipulator";
delete h;
}
OSGNode *OSGCameraManipulator::sceneNode() const
{
return h->sceneNode;
}
void OSGCameraManipulator::setSceneNode(OSGNode *node)
{
if (h->acceptSceneNode(node)) {
emit sceneNodeChanged(node);
}
}
void OSGCameraManipulator::classBegin()
{
// qDebug() << "OSGCameraManipulator::classBegin" << this;
}
void OSGCameraManipulator::componentComplete()
{
qDebug() << "OSGCameraManipulator::componentComplete" << this;
h->updateSceneNode();
}
osgGA::CameraManipulator *OSGCameraManipulator::manipulator() const
{
return h->manipulator;
}
void OSGCameraManipulator::setManipulator(osgGA::CameraManipulator *manipulator)
{
h->manipulator = manipulator;
}
osgGA::CameraManipulator *OSGCameraManipulator::asCameraManipulator() const
{
return h->manipulator;
}
} // namespace osgQtQuick
#include "OSGCameraManipulator.moc"

View File

@ -0,0 +1,74 @@
/**
******************************************************************************
*
* @file OSGCameraManipulator.hpp
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @addtogroup
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* 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 _H_OSGQTQUICK_OSGCAMERAMANIPULATOR_H_
#define _H_OSGQTQUICK_OSGCAMERAMANIPULATOR_H_
#include "../Export.hpp"
#include <QObject>
#include <QQmlParserStatus>
namespace osgGA {
class CameraManipulator;
}
namespace osgQtQuick {
class OSGNode;
class OSGQTQUICK_EXPORT OSGCameraManipulator : public QObject, public QQmlParserStatus {
Q_OBJECT
Q_INTERFACES(QQmlParserStatus)
Q_PROPERTY(osgQtQuick::OSGNode * sceneNode READ sceneNode WRITE setSceneNode NOTIFY sceneNodeChanged)
public:
explicit OSGCameraManipulator(QObject *parent = 0);
virtual ~OSGCameraManipulator();
osgGA::CameraManipulator *asCameraManipulator() const;
OSGNode *sceneNode() const;
void setSceneNode(OSGNode *node);
signals:
void sceneNodeChanged(OSGNode *node);
protected:
void classBegin();
void componentComplete();
osgGA::CameraManipulator *manipulator() const;
void setManipulator(osgGA::CameraManipulator *manipulator);
private:
struct Hidden;
Hidden *const h;
};
} // namespace osgQtQuick
#endif // _H_OSGQTQUICK_OSGCAMERAMANIPULATOR_H_

View File

@ -0,0 +1,70 @@
/**
******************************************************************************
*
* @file OSGEarthManipulator.cpp
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @addtogroup
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* 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 "OSGEarthManipulator.hpp"
#include "../OSGNode.hpp"
#include <osgEarthUtil/EarthManipulator>
#include <QDebug>
namespace osgQtQuick {
struct OSGEarthManipulator::Hidden : public QObject {
Q_OBJECT
private:
OSGEarthManipulator * const self;
public:
osg::ref_ptr<osgEarth::Util::EarthManipulator> manipulator;
Hidden(OSGEarthManipulator *self) : QObject(self), self(self)
{
manipulator = new osgEarth::Util::EarthManipulator(
/*osgGA::StandardManipulator::COMPUTE_HOME_USING_BBOX | osgGA::StandardManipulator::DEFAULT_SETTINGS*/);
manipulator->getSettings()->setThrowingEnabled(true);
self->setManipulator(manipulator);
}
~Hidden()
{}
};
/* class OSGEarthManipulator */
OSGEarthManipulator::OSGEarthManipulator(QObject *parent) : OSGCameraManipulator(parent), h(new Hidden(this))
{}
OSGEarthManipulator::~OSGEarthManipulator()
{
qDebug() << "OSGEarthManipulator::~OSGEarthManipulator";
delete h;
}
} // namespace osgQtQuick
#include "OSGEarthManipulator.moc"

View File

@ -0,0 +1,50 @@
/**
******************************************************************************
*
* @file OSGEarthManipulator.hpp
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @addtogroup
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* 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 _H_OSGQTQUICK_OSGEARTHMANIPULATOR_H_
#define _H_OSGQTQUICK_OSGEARTHMANIPULATOR_H_
#include "../Export.hpp"
#include "OSGCameraManipulator.hpp"
#include <QObject>
namespace osgQtQuick {
class OSGQTQUICK_EXPORT OSGEarthManipulator : public OSGCameraManipulator {
Q_OBJECT
public:
explicit OSGEarthManipulator(QObject *parent = 0);
virtual ~OSGEarthManipulator();
private:
struct Hidden;
Hidden *const h;
};
} // namespace osgQtQuick
#endif // _H_OSGQTQUICK_OSGEARTHMANIPULATOR_H_

View File

@ -0,0 +1,337 @@
/**
******************************************************************************
*
* @file OSGGeoTransformManipulator.cpp
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @addtogroup
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* 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 "OSGGeoTransformManipulator.hpp"
#include "../OSGNode.hpp"
#include "../../utility.h"
#include <osg/Matrix>
#include <osg/Node>
#include <osg/NodeVisitor>
#include <osg/Vec3d>
#include <osgGA/CameraManipulator>
#include <osgEarth/GeoData>
#include <osgEarth/MapNode>
#include <QDebug>
namespace osgQtQuick {
class MyManipulator : public osgGA::CameraManipulator {
public:
MyManipulator()
{}
virtual void updateCamera(osg::Camera &camera);
virtual const char *className() const
{
return "MyManipulator";
}
virtual void setByMatrix(const osg::Matrixd &matrix)
{
this->matrix = matrix;
}
virtual void setByInverseMatrix(const osg::Matrixd &matrix)
{
this->invMatrix = matrix;
}
virtual osg::Matrixd getMatrix() const
{
return matrix;
}
virtual osg::Matrixd getInverseMatrix() const
{
return invMatrix;
}
virtual void setNode(osg::Node *node)
{
this->node = node;
}
virtual const osg::Node *getNode() const
{
return node.get();
}
virtual osg::Node *getNode()
{
return node.get();
}
private:
osg::Matrixd matrix;
osg::Matrixd invMatrix;
osg::ref_ptr<osg::Node> node;
};
struct OSGGeoTransformManipulator::NodeUpdateCallback : public osg::NodeCallback {
public:
NodeUpdateCallback(OSGGeoTransformManipulator::Hidden *h) : h(h)
{}
void operator()(osg::Node *node, osg::NodeVisitor *nv);
private:
OSGGeoTransformManipulator::Hidden *const h;
};
struct OSGGeoTransformManipulator::Hidden : public QObject {
Q_OBJECT
private:
OSGGeoTransformManipulator * const self;
osg::ref_ptr<osg::NodeCallback> nodeUpdateCallback;
osg::Matrix cameraPosition;
osg::Matrix cameraRotation;
bool dirty;
public:
osg::ref_ptr<MyManipulator> manipulator;
QVector3D attitude;
QVector3D position;
bool clampToTerrain;
bool intoTerrain;
Hidden(OSGGeoTransformManipulator *self) : QObject(self), self(self), dirty(false), clampToTerrain(false), intoTerrain(false)
{
manipulator = new MyManipulator();
self->setManipulator(manipulator);
}
~Hidden()
{}
// TODO factorize up
void setDirty()
{
if (dirty) {
return;
}
// qDebug() << "OSGGeoTransformManipulator::setDirty";
dirty = true;
osg::Node *node = manipulator->getNode();
if (node) {
if (!nodeUpdateCallback.valid()) {
// lazy creation
nodeUpdateCallback = new NodeUpdateCallback(this);
}
node->addUpdateCallback(nodeUpdateCallback.get());
} else {
qWarning() << "OSGGeoTransformManipulator::setDirty - no node...";
}
}
// TODO factorize up
void clearDirty()
{
// qDebug() << "OSGGeoTransformManipulator::clearDirty";
osg::Node *node = manipulator->getNode();
if (node && nodeUpdateCallback.valid()) {
node->removeUpdateCallback(nodeUpdateCallback.get());
}
dirty = false;
}
void update()
{
updatePosition();
updateAttitude();
updateManipulator();
}
void updateManipulator()
{
// qDebug() << "OSGGeoTransformManipulator::updateManipulator";
osg::Matrix cameraMatrix = cameraRotation * cameraPosition;
manipulator->setByMatrix(cameraMatrix);
// Inverse the camera's position and orientation matrix to obtain the view matrix
cameraMatrix = osg::Matrix::inverse(cameraMatrix);
manipulator->setByInverseMatrix(cameraMatrix);
}
void updatePosition()
{
// qDebug() << "OSGGeoTransformManipulator::updatePosition" << position;
// 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) ;)
osgEarth::MapNode *mapNode = NULL;
if (manipulator->getNode()) {
mapNode = osgEarth::MapNode::findMapNode(manipulator->getNode());
if (!mapNode) {
qWarning() << "OSGGeoTransformManipulator::updatePosition - manipulator node does not contain a map node";
}
} else {
qWarning() << "OSGGeoTransformManipulator::updatePosition - manipulator node is null";
}
osgEarth::GeoPoint geoPoint;
if (mapNode) {
geoPoint = osgQtQuick::toGeoPoint(mapNode->getTerrain()->getSRS(), position);
} else {
geoPoint = osgQtQuick::toGeoPoint(position);
}
if (clampToTerrain && mapNode) {
// clamp model to terrain if needed
intoTerrain = osgQtQuick::clampGeoPoint(geoPoint, 0, mapNode);
} else if (clampToTerrain) {
qWarning() << "OSGGeoTransformManipulator::updatePosition - cannot clamp without map node";
}
geoPoint.createLocalToWorld(cameraPosition);
}
void updateAttitude()
{
// qDebug() << "OSGGeoTransformManipulator::updateAttitude" << attitude;
// By default the camera looks toward -Z, we must rotate it so it looks toward Y
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
double roll = osg::DegreesToRadians(attitude.x());
double pitch = osg::DegreesToRadians(attitude.y());
double yaw = osg::DegreesToRadians(attitude.z());
cameraRotation = cameraRotation
* osg::Matrix::rotate(roll, osg::Vec3(0, 1, 0))
* osg::Matrix::rotate(pitch, osg::Vec3(1, 0, 0))
* osg::Matrix::rotate(yaw, osg::Vec3(0, 0, -1));
}
};
/* class OSGGeoTransformManipulator::MyManipulator */
void MyManipulator::updateCamera(osg::Camera & camera)
{
// qDebug() << "MyManipulator::updateCamera";
CameraManipulator::updateCamera(camera);
}
/* struct OSGGeoTransformManipulator::NodeUpdateCallback */
void OSGGeoTransformManipulator::NodeUpdateCallback::operator()(osg::Node *node, osg::NodeVisitor *nv)
{
// qDebug() << "OSGGeoTransformManipulator::NodeUpdateCallback";
nv->traverse(*node);
h->update();
h->clearDirty();
}
/* class OSGGeoTransformManipulator */
OSGGeoTransformManipulator::OSGGeoTransformManipulator(QObject *parent) : OSGCameraManipulator(parent), h(new Hidden(this))
{}
OSGGeoTransformManipulator::~OSGGeoTransformManipulator()
{
qDebug() << "OSGGeoTransformManipulator::~OSGGeoTransformManipulator";
delete h;
}
bool OSGGeoTransformManipulator::clampToTerrain() const
{
return h->clampToTerrain;
}
void OSGGeoTransformManipulator::setClampToTerrain(bool arg)
{
if (h->clampToTerrain != arg) {
h->clampToTerrain = arg;
emit clampToTerrainChanged(clampToTerrain());
}
}
bool OSGGeoTransformManipulator::intoTerrain() const
{
return h->intoTerrain;
}
QVector3D OSGGeoTransformManipulator::attitude() const
{
return h->attitude;
}
void OSGGeoTransformManipulator::setAttitude(QVector3D arg)
{
if (h->attitude != arg) {
h->attitude = arg;
h->setDirty();
emit attitudeChanged(attitude());
}
}
QVector3D OSGGeoTransformManipulator::position() const
{
return h->position;
}
void OSGGeoTransformManipulator::setPosition(QVector3D arg)
{
if (h->position != arg) {
h->position = arg;
h->setDirty();
emit positionChanged(position());
}
}
// TODO factorize up
void OSGGeoTransformManipulator::componentComplete()
{
OSGCameraManipulator::componentComplete();
qDebug() << "OSGGeoTransformManipulator::componentComplete" << this;
h->update();
h->clearDirty();
}
} // namespace osgQtQuick
#include "OSGGeoTransformManipulator.moc"

View File

@ -0,0 +1,78 @@
/**
******************************************************************************
*
* @file OSGGeoTransformManipulator.hpp
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @addtogroup
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* 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 _H_OSGQTQUICK_OSGGEOTRANSFORMMANIPULATOR_H_
#define _H_OSGQTQUICK_OSGGEOTRANSFORMMANIPULATOR_H_
#include "../Export.hpp"
#include "OSGCameraManipulator.hpp"
#include <QObject>
#include <QVector3D>
namespace osgQtQuick {
class OSGQTQUICK_EXPORT OSGGeoTransformManipulator : public OSGCameraManipulator {
Q_OBJECT Q_PROPERTY(QVector3D attitude READ attitude WRITE setAttitude NOTIFY attitudeChanged)
Q_PROPERTY(QVector3D position READ position WRITE setPosition NOTIFY positionChanged)
Q_PROPERTY(bool clampToTerrain READ clampToTerrain WRITE setClampToTerrain NOTIFY clampToTerrainChanged)
Q_PROPERTY(bool intoTerrain READ intoTerrain NOTIFY intoTerrainChanged)
friend class NodeUpdateCallback;
friend class MyManipulator;
public:
explicit OSGGeoTransformManipulator(QObject *parent = 0);
virtual ~OSGGeoTransformManipulator();
QVector3D attitude() const;
void setAttitude(QVector3D arg);
QVector3D position() const;
void setPosition(QVector3D arg);
bool clampToTerrain() const;
void setClampToTerrain(bool arg);
bool intoTerrain() const;
signals:
void attitudeChanged(QVector3D arg);
void positionChanged(QVector3D arg);
void clampToTerrainChanged(bool arg);
void intoTerrainChanged(bool arg);
protected:
void componentComplete();
private:
struct Hidden;
struct NodeUpdateCallback;
Hidden *const h;
};
} // namespace osgQtQuick
#endif // _H_OSGQTQUICK_OSGGEOTRANSFORMMANIPULATOR_H_

View File

@ -0,0 +1,169 @@
/**
******************************************************************************
*
* @file OSGNodeTrackerManipulator.cpp
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @addtogroup
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* 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 "OSGNodeTrackerManipulator.hpp"
#include "../OSGNode.hpp"
#include <osgGA/NodeTrackerManipulator>
#include <QDebug>
namespace osgQtQuick {
struct OSGNodeTrackerManipulator::Hidden : public QObject {
Q_OBJECT
private:
OSGNodeTrackerManipulator * const self;
public:
osg::ref_ptr<osgGA::NodeTrackerManipulator> manipulator;
OSGNode *trackNode;
TrackerMode::Enum trackerMode;
public:
Hidden(OSGNodeTrackerManipulator *self) : QObject(self), self(self),
trackNode(NULL), trackerMode(TrackerMode::NodeCenterAndAzim)
{
manipulator = new osgGA::NodeTrackerManipulator(
/*osgGA::StandardManipulator::COMPUTE_HOME_USING_BBOX | osgGA::StandardManipulator::DEFAULT_SETTINGS*/);
manipulator->setTrackerMode(toOsg(trackerMode));
manipulator->setVerticalAxisFixed(false);
self->setManipulator(manipulator);
}
~Hidden()
{}
bool acceptTrackNode(OSGNode *node)
{
qDebug() << "OSGNodeTrackerManipulator::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;
}
void updateTrackNode()
{
if (!trackNode) {
qWarning() << "OSGNodeTrackerManipulator::updateTrackNode - no track node";
return;
}
qDebug() << "OSGNodeTrackerManipulator::updateTrackNode" << trackNode->node();
manipulator->setTrackNode(trackNode->node());
}
void updateTrackerMode()
{
// qDebug() << "OSGNodeTrackerManipulator::updateTrackerMode" << mode;
manipulator->setTrackerMode(toOsg(trackerMode));
}
osgGA::NodeTrackerManipulator::TrackerMode toOsg(TrackerMode::Enum mode)
{
switch (mode) {
case TrackerMode::NodeCenter:
return osgGA::NodeTrackerManipulator::NODE_CENTER;
case TrackerMode::NodeCenterAndAzim:
return osgGA::NodeTrackerManipulator::NODE_CENTER_AND_AZIM;
case TrackerMode::NodeCenterAndRotation:
return osgGA::NodeTrackerManipulator::NODE_CENTER_AND_ROTATION;
}
return osgGA::NodeTrackerManipulator::NODE_CENTER_AND_ROTATION;
}
private slots:
void onTrackNodeChanged(osg::Node *node)
{
qDebug() << "OSGNodeTrackerManipulator::onTrackNodeChanged" << node;
qWarning() << "OSGNodeTrackerManipulator::onTrackNodeChanged - needs to be implemented";
}
};
/* class OSGNodeTrackerManipulator */
OSGNodeTrackerManipulator::OSGNodeTrackerManipulator(QObject *parent) : OSGCameraManipulator(parent), h(new Hidden(this))
{}
OSGNodeTrackerManipulator::~OSGNodeTrackerManipulator()
{
qDebug() << "OSGNodeTrackerManipulator::~OSGNodeTrackerManipulator";
delete h;
}
OSGNode *OSGNodeTrackerManipulator::trackNode() const
{
return h->trackNode;
}
void OSGNodeTrackerManipulator::setTrackNode(OSGNode *node)
{
if (h->acceptTrackNode(node)) {
emit trackNodeChanged(node);
}
}
TrackerMode::Enum OSGNodeTrackerManipulator::trackerMode() const
{
return h->trackerMode;
}
void OSGNodeTrackerManipulator::setTrackerMode(TrackerMode::Enum mode)
{
if (h->trackerMode != mode) {
h->trackerMode = mode;
emit trackerModeChanged(trackerMode());
}
}
void OSGNodeTrackerManipulator::componentComplete()
{
OSGCameraManipulator::componentComplete();
qDebug() << "OSGNodeTrackerManipulator::componentComplete" << this;
h->updateTrackerMode();
h->updateTrackNode();
}
} // namespace osgQtQuick
#include "OSGNodeTrackerManipulator.moc"

View File

@ -0,0 +1,71 @@
/**
******************************************************************************
*
* @file OSGNodeTrackerManipulator.hpp
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @addtogroup
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* 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 _H_OSGQTQUICK_OSGNODETRACKERMANIPULATOR_H_
#define _H_OSGQTQUICK_OSGNODETRACKERMANIPULATOR_H_
#include "../Export.hpp"
#include "OSGCameraManipulator.hpp"
#include <QObject>
namespace osgQtQuick {
class TrackerMode : public QObject {
Q_OBJECT
public:
enum Enum { NodeCenter, NodeCenterAndAzim, NodeCenterAndRotation };
Q_ENUMS(Enum) // TODO switch to Q_ENUM once on Qt 5.5
};
class OSGQTQUICK_EXPORT OSGNodeTrackerManipulator : public OSGCameraManipulator {
Q_OBJECT Q_PROPERTY(osgQtQuick::OSGNode *trackNode READ trackNode WRITE setTrackNode NOTIFY trackNodeChanged)
Q_PROPERTY(osgQtQuick::TrackerMode::Enum trackerMode READ trackerMode WRITE setTrackerMode NOTIFY trackerModeChanged)
public:
explicit OSGNodeTrackerManipulator(QObject *parent = 0);
virtual ~OSGNodeTrackerManipulator();
OSGNode *trackNode() const;
void setTrackNode(OSGNode *node);
TrackerMode::Enum trackerMode() const;
void setTrackerMode(TrackerMode::Enum);
signals:
void trackNodeChanged(OSGNode *node);
void trackerModeChanged(TrackerMode::Enum);
protected:
void componentComplete();
private:
struct Hidden;
Hidden *const h;
};
} // namespace osgQtQuick
#endif // _H_OSGQTQUICK_OSGNODETRACKERMANIPULATOR_H_

View File

@ -0,0 +1,70 @@
/**
******************************************************************************
*
* @file OSGTrackballManipulator.cpp
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @addtogroup
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* 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 "OSGTrackballManipulator.hpp"
#include "../OSGNode.hpp"
#include <osgGA/TrackballManipulator>
#include <QDebug>
namespace osgQtQuick {
struct OSGTrackballManipulator::Hidden : public QObject {
Q_OBJECT
private:
OSGTrackballManipulator * const self;
public:
osg::ref_ptr<osgGA::TrackballManipulator> manipulator;
Hidden(OSGTrackballManipulator *self) : QObject(self), self(self)
{
manipulator = new osgGA::TrackballManipulator(
/*osgGA::StandardManipulator::COMPUTE_HOME_USING_BBOX | osgGA::StandardManipulator::DEFAULT_SETTINGS*/);
self->setManipulator(manipulator);
}
~Hidden()
{}
};
/* class OSGTrackballManipulator */
OSGTrackballManipulator::OSGTrackballManipulator(QObject *parent) : OSGCameraManipulator(parent), h(new Hidden(this))
{}
OSGTrackballManipulator::~OSGTrackballManipulator()
{
qDebug() << "OSGTrackballManipulator::~OSGTrackballManipulator";
delete h;
}
} // namespace osgQtQuick
#include "OSGTrackballManipulator.moc"

View File

@ -0,0 +1,50 @@
/**
******************************************************************************
*
* @file OSGTrackballManipulator.hpp
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @addtogroup
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* 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 _H_OSGQTQUICK_OSGTRACKBALLMANIPULATOR_H_
#define _H_OSGQTQUICK_OSGTRACKBALLMANIPULATOR_H_
#include "../Export.hpp"
#include "OSGCameraManipulator.hpp"
#include <QObject>
namespace osgQtQuick {
class OSGQTQUICK_EXPORT OSGTrackballManipulator : public OSGCameraManipulator {
Q_OBJECT
public:
explicit OSGTrackballManipulator(QObject *parent = 0);
virtual ~OSGTrackballManipulator();
private:
struct Hidden;
Hidden *const h;
};
} // namespace osgQtQuick
#endif // _H_OSGQTQUICK_OSGTRACKBALLMANIPULATOR_H_

View File

@ -69,6 +69,16 @@ SOURCES += \
osgQtQuick/OSGCamera.cpp \
osgQtQuick/OSGViewport.cpp
HEADERS += \
osgQtQuick/ga/OSGCameraManipulator.hpp \
osgQtQuick/ga/OSGNodeTrackerManipulator.hpp \
osgQtQuick/ga/OSGTrackballManipulator.hpp
SOURCES += \
osgQtQuick/ga/OSGCameraManipulator.cpp \
osgQtQuick/ga/OSGNodeTrackerManipulator.cpp \
osgQtQuick/ga/OSGTrackballManipulator.cpp
osgearth:HEADERS += \
osgQtQuick/OSGSkyNode.hpp \
osgQtQuick/OSGGeoTransformNode.hpp
@ -77,4 +87,12 @@ osgearth:SOURCES += \
osgQtQuick/OSGSkyNode.cpp \
osgQtQuick/OSGGeoTransformNode.cpp
osgearth:HEADERS += \
osgQtQuick/ga/OSGEarthManipulator.hpp \
osgQtQuick/ga/OSGGeoTransformManipulator.hpp
osgearth:SOURCES += \
osgQtQuick/ga/OSGEarthManipulator.cpp \
osgQtQuick/ga/OSGGeoTransformManipulator.cpp
copy_osg:include(copydata.pro)

View File

@ -38,6 +38,10 @@
#include "osgQtQuick/OSGCamera.hpp"
#include "osgQtQuick/OSGViewport.hpp"
#include "osgQtQuick/ga/OSGCameraManipulator.hpp"
#include "osgQtQuick/ga/OSGNodeTrackerManipulator.hpp"
#include "osgQtQuick/ga/OSGTrackballManipulator.hpp"
#include <osg/NodeCallback>
#include <osg/Camera>
#include <osg/MatrixTransform>
@ -61,6 +65,9 @@
#include "osgQtQuick/OSGSkyNode.hpp"
#include "osgQtQuick/OSGGeoTransformNode.hpp"
#include "osgQtQuick/ga/OSGEarthManipulator.hpp"
#include "osgQtQuick/ga/OSGGeoTransformManipulator.hpp"
#include <osgEarth/Capabilities>
#include <osgEarth/MapNode>
#include <osgEarth/SpatialReference>
@ -75,9 +82,11 @@
namespace osgQtQuick {
class CullCallback : public osg::NodeCallback {
public:
CullCallback() {}
CullCallback()
{}
virtual ~CullCallback() {}
virtual ~CullCallback()
{}
public:
virtual void operator()(osg::Node *node, osg::NodeVisitor *nv)
@ -101,12 +110,14 @@ 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());
@ -122,6 +133,7 @@ public:
// geode.getDrawable(i)->setDrawCallback(new DrawableDrawCallback());
// }
}
virtual void apply(osg::Transform & node)
{
apply((osg::Node &)node);
@ -543,12 +555,18 @@ void registerTypes()
qmlRegisterType<osgQtQuick::UpdateMode>("OsgQtQuick", maj, min, "UpdateMode");
qmlRegisterType<osgQtQuick::OSGCamera>("OsgQtQuick", maj, min, "OSGCamera");
qmlRegisterType<osgQtQuick::ManipulatorMode>("OsgQtQuick", maj, min, "ManipulatorMode");
qmlRegisterType<osgQtQuick::OSGCameraManipulator>("OsgQtQuick", maj, min, "OSGCameraManipulator");
qmlRegisterType<osgQtQuick::OSGNodeTrackerManipulator>("OsgQtQuick", maj, min, "OSGNodeTrackerManipulator");
qmlRegisterType<osgQtQuick::TrackerMode>("OsgQtQuick", maj, min, "TrackerMode");
qmlRegisterType<osgQtQuick::OSGTrackballManipulator>("OsgQtQuick", maj, min, "OSGTrackballManipulator");
#ifdef USE_OSGEARTH
qmlRegisterType<osgQtQuick::OSGSkyNode>("OsgQtQuick", maj, min, "OSGSkyNode");
qmlRegisterType<osgQtQuick::OSGGeoTransformNode>("OsgQtQuick", maj, min, "OSGGeoTransformNode");
qmlRegisterType<osgQtQuick::OSGEarthManipulator>("OsgQtQuick", maj, min, "OSGEarthManipulator");
qmlRegisterType<osgQtQuick::OSGGeoTransformManipulator>("OsgQtQuick", maj, min, "OSGGeoTransformManipulator");
#endif // USE_OSGEARTH
}
} // namespace osgQtQuick

View File

@ -28,14 +28,27 @@ import "common.js" as Utils
Item {
OSGViewport {
id: osgViewport
anchors.fill: parent
focus: true
sceneData: skyNode
camera: camera
manipulator: earthManipulator
OSGCamera {
id: camera
fieldOfView: 90
}
OSGEarthManipulator {
id: earthManipulator
}
OSGSkyNode {
id: skyNode
sceneData: terrainNode
viewport: osgViewport
dateTime: Utils.getDateTime()
minimumAmbientLight: pfdContext.minimumAmbientLight
}
@ -46,11 +59,7 @@ Item {
async: false
}
OSGCamera {
id: camera
fieldOfView: 90
manipulatorMode: ManipulatorMode.Earth
}
}
BusyIndicator {
width: 24

View File

@ -28,34 +28,46 @@ import "../uav.js" as UAV
OSGViewport {
id: osgViewport
anchors.fill: parent
focus: true
sceneData: skyNode
camera: camera
manipulator: nodeTrackerManipulator
OSGCamera {
id: camera
fieldOfView: 90
logarithmicDepthBuffer: true
}
OSGNodeTrackerManipulator {
id: nodeTrackerManipulator
// use model to compute camera home position
sceneNode: modelTransformNode
// model will be tracked
trackNode: modelTransformNode
}
OSGSkyNode {
id: skyNode
sceneData: sceneGroup
viewport: osgViewport
dateTime: Utils.getDateTime()
minimumAmbientLight: pfdContext.minimumAmbientLight
}
OSGGroup {
id: sceneGroup
children: [ terrainNode, modelNode ]
}
OSGFileNode {
id: terrainNode
source: pfdContext.terrainFile
async: false
children: [ terrainFileNode, modelNode ]
}
OSGGeoTransformNode {
id: modelNode
modelData: modelTransformNode
sceneData: terrainNode
sceneData: terrainFileNode
clampToTerrain: true
@ -70,6 +82,11 @@ OSGViewport {
attitude: UAV.attitude()
}
OSGFileNode {
id: terrainFileNode
source: pfdContext.terrainFile
}
OSGFileNode {
id: modelFileNode
@ -77,21 +94,9 @@ OSGViewport {
// see http://docs.osgearth.org/en/latest/faq.html#i-added-a-node-but-it-has-no-texture-lighting-etc-in-osgearth-why
source: pfdContext.modelFile + ".osgearth_shadergen"
async: false
optimizeMode: OptimizeMode.OptimizeAndCheck
}
OSGCamera {
id: camera
fieldOfView: 90
logarithmicDepthBuffer: true
manipulatorMode: ManipulatorMode.Track
// use model to compute camera home position
sceneNode: modelTransformNode
// model will be tracked
trackNode: modelTransformNode
}
Keys.onUpPressed: {
pfdContext.nextModel();
}

View File

@ -28,8 +28,20 @@ Item {
OSGViewport {
anchors.fill: parent
focus: true
sceneData: sceneNode
camera: camera
manipulator: trackballManipulator
OSGCamera {
id: camera
fieldOfView: 90
}
OSGTrackballManipulator {
id: trackballManipulator
sceneNode: transformNode
}
OSGGroup {
id: sceneNode
@ -57,12 +69,6 @@ Item {
optimizeMode: OptimizeMode.OptimizeAndCheck
}
OSGCamera {
id: camera
fieldOfView: 90
sceneNode: transformNode
}
Keys.onUpPressed: {
pfdContext.nextModel();
}

View File

@ -26,11 +26,14 @@ import "../common.js" as Utils
import "../uav.js" as UAV
OSGViewport {
id: fullview
id: osgViewport
//anchors.fill: parent
focus: true
sceneData: skyNode
camera: camera
manipulator: geoTransformManipulator
property real horizontCenter : horizontCenterItem.horizontCenter
@ -41,31 +44,36 @@ OSGViewport {
//height: height * (1 + factor)
y: -height * factor
OSGCamera {
id: camera
fieldOfView: 100
logarithmicDepthBuffer: true
}
OSGGeoTransformManipulator {
id: geoTransformManipulator
clampToTerrain: true
attitude: UAV.attitude()
position: UAV.position()
}
OSGSkyNode {
id: skyNode
sceneData: terrainNode
sceneData: terrainFileNode
viewport: osgViewport
dateTime: Utils.getDateTime()
minimumAmbientLight: pfdContext.minimumAmbientLight
}
OSGFileNode {
id: terrainNode
id: terrainFileNode
source: pfdContext.terrainFile
async: false
}
OSGCamera {
id: camera
fieldOfView: 100
sceneNode: terrainNode
logarithmicDepthBuffer: true
clampToTerrain: true
manipulatorMode: ManipulatorMode.User
attitude: UAV.attitude()
position: UAV.position()
}
Rectangle {
// using rectangle instead of svg rendered to pixmap
// as it's much more memory efficient
@ -104,7 +112,7 @@ OSGViewport {
property variant scaledBounds: svgRenderer.scaledElementBounds("pfd/pfd.svg", "pitch-window-terrain")
x: Math.floor(scaledBounds.x * sceneItem.width)
y: Math.floor(scaledBounds.y * sceneItem.height) - fullview.y
y: Math.floor(scaledBounds.y * sceneItem.height) - osgViewport.y
width: Math.floor(scaledBounds.width * sceneItem.width)
height: Math.floor(scaledBounds.height * sceneItem.height)