mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-19 04:52:12 +01:00
Merged in filnet/librepilot/filnet/LP-29_osgearth_integration (pull request #179)
LP-29 fix osg attitude handling issue when pitch close to +/-90 (thank you @liftbag for reporting it)
This commit is contained in:
commit
07f2bb3bc4
@ -165,20 +165,6 @@ public:
|
||||
return true;
|
||||
}
|
||||
|
||||
bool attach(osgViewer::View *view)
|
||||
{
|
||||
attachCamera(view->getCamera());
|
||||
attachManipulator(view);
|
||||
return true;
|
||||
}
|
||||
|
||||
bool detach(osgViewer::View *view)
|
||||
{
|
||||
detachManipulator(view);
|
||||
detachCamera(view->getCamera());
|
||||
return true;
|
||||
}
|
||||
|
||||
void attachCamera(osg::Camera *camera)
|
||||
{
|
||||
qDebug() << "OSGCamera::attach" << camera;
|
||||
@ -252,7 +238,7 @@ public:
|
||||
// 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 StandardManaipulator for example on how to react to events (tohabd FOV changes without the need for an update callback?)
|
||||
// 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:
|
||||
@ -269,8 +255,7 @@ public:
|
||||
qDebug() << "OSGCamera::attachManipulator - use NodeTrackerManipulator";
|
||||
if (trackNode && trackNode->node()) {
|
||||
// setup tracking camera
|
||||
// TODO when camera is thrown, then changing attitude has jitter (could be due to different frequency between refresh and animation)
|
||||
// TODO who takes ownership?
|
||||
// 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) {
|
||||
@ -331,23 +316,24 @@ public:
|
||||
}
|
||||
fovDirty = false;
|
||||
|
||||
// qDebug() << "OSGCamera::updateCameraFOV";
|
||||
qDebug() << "OSGCamera::updateCameraFOV" << fieldOfView;
|
||||
|
||||
double fovy, ar, zn, zf;
|
||||
|
||||
camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf);
|
||||
|
||||
fovy = fieldOfView;
|
||||
camera->setProjectionMatrixAsPerspective(fovy, ar, zn, zf);
|
||||
}
|
||||
|
||||
void updateAspectRatio()
|
||||
{
|
||||
double fovy, ar, zn, zf;
|
||||
|
||||
camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf);
|
||||
|
||||
osg::Viewport *viewport = camera->getViewport();
|
||||
ar = static_cast<double>(viewport->width()) / static_cast<double>(viewport->height());
|
||||
double aspectRatio = static_cast<double>(viewport->width()) / static_cast<double>(viewport->height());
|
||||
|
||||
qDebug() << "OSGCamera::updateAspectRatio" << aspectRatio;
|
||||
|
||||
double fovy, ar, zn, zf;
|
||||
camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf);
|
||||
ar = aspectRatio;
|
||||
camera->setProjectionMatrixAsPerspective(fovy, ar, zn, zf);
|
||||
}
|
||||
|
||||
@ -392,10 +378,13 @@ public:
|
||||
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());
|
||||
osg::Matrix cameraMatrix = cameraRotation
|
||||
* osg::Matrix::rotate(osg::DegreesToRadians(attitude.x()), osg::Vec3(1.0, 0.0, 0.0))
|
||||
* osg::Matrix::rotate(osg::DegreesToRadians(attitude.y()), osg::Vec3(0.0, 1.0, 0.0))
|
||||
* osg::Matrix::rotate(osg::DegreesToRadians(attitude.z()), osg::Vec3(0.0, 0.0, 1.0)) * cameraPosition;
|
||||
* 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.0)) * cameraPosition;
|
||||
|
||||
// Inverse the camera's position and orientation matrix to obtain the view matrix
|
||||
cameraMatrix = osg::Matrix::inverse(cameraMatrix);
|
||||
@ -454,7 +443,6 @@ private slots:
|
||||
void OSGCamera::Hidden::CameraUpdateCallback::operator()(osg::Node *node, osg::NodeVisitor *nv)
|
||||
{
|
||||
h->updateCamera();
|
||||
// traverse(node, nv);
|
||||
}
|
||||
|
||||
/* class OSGCamera */
|
||||
@ -605,14 +593,16 @@ void OSGCamera::setLogarithmicDepthBuffer(bool enabled)
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGCamera::attach(osgViewer::View *view)
|
||||
void OSGCamera::attach(osgViewer::View *view)
|
||||
{
|
||||
return h->attach(view);
|
||||
h->attachCamera(view->getCamera());
|
||||
h->attachManipulator(view);
|
||||
}
|
||||
|
||||
bool OSGCamera::detach(osgViewer::View *view)
|
||||
void OSGCamera::detach(osgViewer::View *view)
|
||||
{
|
||||
return h->detach(view);
|
||||
h->detachCamera(view->getCamera());
|
||||
h->detachManipulator(view);
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
|
@ -117,8 +117,8 @@ public:
|
||||
bool logarithmicDepthBuffer();
|
||||
void setLogarithmicDepthBuffer(bool enabled);
|
||||
|
||||
virtual bool attach(osgViewer::View *view);
|
||||
virtual bool detach(osgViewer::View *view);
|
||||
virtual void attach(osgViewer::View *view);
|
||||
virtual void detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void fieldOfViewChanged(qreal arg);
|
||||
|
@ -1,91 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file OSGCubeNode.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 "OSGCubeNode.hpp"
|
||||
|
||||
#include <osg/Geode>
|
||||
#include <osg/Group>
|
||||
#include <osg/Shape>
|
||||
#include <osg/ShapeDrawable>
|
||||
|
||||
#include <QDebug>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGCubeNode::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
Hidden(OSGCubeNode *parent) : QObject(parent), self(parent) {}
|
||||
|
||||
void realize()
|
||||
{
|
||||
qDebug() << "OSGCubeNode::realize";
|
||||
|
||||
// Declare a group to act as root node of a scene:
|
||||
// osg::Group* root = new osg::Group();
|
||||
|
||||
// Declare a box class (derived from shape class) instance
|
||||
// This constructor takes an osg::Vec3 to define the center
|
||||
// and a float to define the height, width and depth.
|
||||
// (an overloaded constructor allows you to specify unique
|
||||
// height, width and height values.)
|
||||
osg::Box *unitCube = new osg::Box(osg::Vec3(0, 0, 0), 1.0f);
|
||||
|
||||
// Declare an instance of the shape drawable class and initialize
|
||||
// it with the unitCube shape we created above.
|
||||
// This class is derived from 'drawable' so instances of this
|
||||
// class can be added to Geode instances.
|
||||
osg::ShapeDrawable *unitCubeDrawable = new osg::ShapeDrawable(unitCube);
|
||||
|
||||
// Declare a instance of the geode class:
|
||||
osg::Geode *basicShapesGeode = new osg::Geode();
|
||||
|
||||
// Add the unit cube drawable to the geode:
|
||||
basicShapesGeode->addDrawable(unitCubeDrawable);
|
||||
|
||||
// Add the geode to the scene:
|
||||
self->setNode(basicShapesGeode);
|
||||
}
|
||||
|
||||
OSGCubeNode *self;
|
||||
};
|
||||
|
||||
// TODO turn into generic shape node...
|
||||
// see http://trac.openscenegraph.org/projects/osg//wiki/Support/Tutorials/TransformsAndStates
|
||||
OSGCubeNode::OSGCubeNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
|
||||
{
|
||||
qDebug() << "OSGCubeNode::OSGCubeNode";
|
||||
h->realize();
|
||||
}
|
||||
|
||||
OSGCubeNode::~OSGCubeNode()
|
||||
{
|
||||
qDebug() << "OSGCubeNode::~OSGCubeNode";
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGCubeNode.moc"
|
@ -145,6 +145,28 @@ QQmlListProperty<OSGNode> OSGGroup::children()
|
||||
&Hidden::at_child,
|
||||
&Hidden::clear_child);
|
||||
}
|
||||
|
||||
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;
|
||||
node->attach(view);
|
||||
}
|
||||
}
|
||||
|
||||
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;
|
||||
node->detach(view);
|
||||
}
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGGroup.moc"
|
||||
|
@ -45,6 +45,9 @@ public:
|
||||
|
||||
QQmlListProperty<OSGNode> children();
|
||||
|
||||
virtual void attach(osgViewer::View *view);
|
||||
virtual void detach(osgViewer::View *view);
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
Hidden *h;
|
||||
|
@ -123,12 +123,6 @@ public:
|
||||
}
|
||||
modelNode->addUpdateCallback(nodeUpdateCallback.get());
|
||||
|
||||
// get "size" of model
|
||||
osg::ComputeBoundsVisitor cbv;
|
||||
modelNode->accept(cbv);
|
||||
const osg::BoundingBox & bbox = cbv.getBoundingBox();
|
||||
offset = bbox.radius();
|
||||
|
||||
self->setNode(modelNode);
|
||||
|
||||
dirty = true;
|
||||
@ -136,17 +130,6 @@ public:
|
||||
return true;
|
||||
}
|
||||
|
||||
bool attach(osgViewer::View *view)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
bool detach(osgViewer::View *view)
|
||||
{
|
||||
qWarning() << "OSGModelNode::detach - not implemented";
|
||||
return true;
|
||||
}
|
||||
|
||||
bool acceptSceneData(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGModelNode::acceptSceneData" << node;
|
||||
@ -183,6 +166,14 @@ public:
|
||||
if (clampToTerrain) {
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneData->node());
|
||||
if (mapNode) {
|
||||
// get "size" of model
|
||||
// TODO this should be done once only...
|
||||
osg::ComputeBoundsVisitor cbv;
|
||||
modelNode->accept(cbv);
|
||||
const osg::BoundingBox & bbox = cbv.getBoundingBox();
|
||||
offset = bbox.radius();
|
||||
|
||||
// clamp model to terrain if needed
|
||||
intoTerrain = clampGeoPoint(geoPoint, offset, mapNode);
|
||||
} else {
|
||||
qWarning() << "OSGModelNode::updateNode - scene data does not contain a map node";
|
||||
@ -194,10 +185,13 @@ public:
|
||||
|
||||
osg::Quat localRotation()
|
||||
{
|
||||
osg::Quat q = osg::Quat(
|
||||
osg::DegreesToRadians(attitude.x()), osg::Vec3d(1, 0, 0),
|
||||
osg::DegreesToRadians(attitude.y()), osg::Vec3d(0, 1, 0),
|
||||
osg::DegreesToRadians(attitude.z()), osg::Vec3d(0, 0, 1));
|
||||
double roll = osg::DegreesToRadians(attitude.x());
|
||||
double pitch = osg::DegreesToRadians(attitude.y());
|
||||
double yaw = osg::DegreesToRadians(attitude.z());
|
||||
osg::Quat q = osg::Quat(
|
||||
roll, osg::Vec3d(0, 1, 0),
|
||||
pitch, osg::Vec3d(1, 0, 0),
|
||||
yaw, osg::Vec3d(0, 0, -1));
|
||||
|
||||
return q;
|
||||
}
|
||||
@ -269,7 +263,6 @@ private slots:
|
||||
void OSGModelNode::Hidden::NodeUpdateCallback::operator()(osg::Node *node, osg::NodeVisitor *nv)
|
||||
{
|
||||
h->updateNode();
|
||||
traverse(node, nv);
|
||||
}
|
||||
|
||||
OSGModelNode::OSGModelNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
|
||||
@ -353,14 +346,21 @@ void OSGModelNode::setPosition(QVector3D arg)
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGModelNode::attach(osgViewer::View *view)
|
||||
void OSGModelNode::attach(osgViewer::View *view)
|
||||
{
|
||||
return h->attach(view);
|
||||
// qDebug() << "OSGModelNode::attach " << view;
|
||||
if (h->modelData) {
|
||||
h->modelData->attach(view);
|
||||
}
|
||||
h->updateNode();
|
||||
}
|
||||
|
||||
bool OSGModelNode::detach(osgViewer::View *view)
|
||||
void OSGModelNode::detach(osgViewer::View *view)
|
||||
{
|
||||
return h->detach(view);
|
||||
// qDebug() << "OSGModelNode::detach " << view;
|
||||
if (h->modelData) {
|
||||
h->modelData->detach(view);
|
||||
}
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
|
@ -72,8 +72,8 @@ public:
|
||||
QVector3D position() const;
|
||||
void setPosition(QVector3D arg);
|
||||
|
||||
virtual bool attach(osgViewer::View *view);
|
||||
virtual bool detach(osgViewer::View *view);
|
||||
virtual void attach(osgViewer::View *view);
|
||||
virtual void detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void modelDataChanged(OSGNode *node);
|
||||
|
@ -57,27 +57,11 @@ void OSGNode::setNode(osg::Node *node)
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGNode::attach(osgViewer::View *view)
|
||||
void OSGNode::attach(osgViewer::View *view)
|
||||
{
|
||||
QListIterator<QObject *> i(children());
|
||||
while (i.hasNext()) {
|
||||
OSGNode *node = qobject_cast<OSGNode *>(i.next());
|
||||
if (node) {
|
||||
node->attach(view);
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool OSGNode::detach(osgViewer::View *view)
|
||||
void OSGNode::detach(osgViewer::View *view)
|
||||
{
|
||||
QListIterator<QObject *> i(children());
|
||||
while (i.hasNext()) {
|
||||
OSGNode *node = qobject_cast<OSGNode *>(i.next());
|
||||
if (node) {
|
||||
node->detach(view);
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
@ -41,6 +41,7 @@ class View;
|
||||
} // namespace osgViewer
|
||||
|
||||
namespace osgQtQuick {
|
||||
|
||||
class OSGQTQUICK_EXPORT OSGNode : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
@ -51,8 +52,8 @@ public:
|
||||
osg::Node *node() const;
|
||||
void setNode(osg::Node *node);
|
||||
|
||||
virtual bool attach(osgViewer::View *view);
|
||||
virtual bool detach(osgViewer::View *view);
|
||||
virtual void attach(osgViewer::View *view);
|
||||
virtual void detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void nodeChanged(osg::Node *node) const;
|
||||
|
115
ground/gcs/src/libs/osgearth/osgQtQuick/OSGShapeNode.cpp
Normal file
115
ground/gcs/src/libs/osgearth/osgQtQuick/OSGShapeNode.cpp
Normal file
@ -0,0 +1,115 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file OSGShapeNode.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 "OSGShapeNode.hpp"
|
||||
|
||||
#include "../shapeutils.h"
|
||||
|
||||
#include <osg/Geode>
|
||||
#include <osg/Group>
|
||||
#include <osg/Shape>
|
||||
#include <osg/ShapeDrawable>
|
||||
|
||||
#include <QDebug>
|
||||
|
||||
namespace osgQtQuick {
|
||||
struct OSGShapeNode::Hidden : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
Hidden(OSGShapeNode *parent) : QObject(parent), self(parent), shapeType(ShapeType::Sphere) {}
|
||||
|
||||
void realize()
|
||||
{
|
||||
qDebug() << "OSGShapeNode::realize";
|
||||
|
||||
osg::Node *node = NULL;
|
||||
|
||||
switch (shapeType) {
|
||||
case ShapeType::Cube:
|
||||
node = ShapeUtils::createCube();
|
||||
break;
|
||||
case ShapeType::Sphere:
|
||||
node = ShapeUtils::createSphere(osg::Vec4(1, 0, 0, 1), 1.0);
|
||||
break;
|
||||
case ShapeType::Torus:
|
||||
node = ShapeUtils::createOrientatedTorus(0.8, 1.0);
|
||||
break;
|
||||
case ShapeType::Axis:
|
||||
node = ShapeUtils::create3DAxis();
|
||||
break;
|
||||
}
|
||||
|
||||
// Add the node to the scene:
|
||||
self->setNode(node);
|
||||
}
|
||||
|
||||
bool acceptShapeType(ShapeType::Enum type)
|
||||
{
|
||||
if (shapeType == type) {
|
||||
return false;
|
||||
}
|
||||
qDebug() << "OSGShapeNode::acceptShapeType" << type;
|
||||
|
||||
shapeType = type;
|
||||
realize();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
OSGShapeNode *self;
|
||||
|
||||
ShapeType::Enum shapeType;
|
||||
};
|
||||
|
||||
// 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";
|
||||
h->realize();
|
||||
}
|
||||
|
||||
OSGShapeNode::~OSGShapeNode()
|
||||
{
|
||||
qDebug() << "OSGShapeNode::~OSGShapeNode";
|
||||
}
|
||||
|
||||
ShapeType::Enum OSGShapeNode::shapeType() const
|
||||
{
|
||||
return h->shapeType;
|
||||
}
|
||||
|
||||
void OSGShapeNode::setShapeType(ShapeType::Enum type)
|
||||
{
|
||||
if (h->acceptShapeType(type)) {
|
||||
emit shapeTypeChanged(shapeType());
|
||||
}
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#include "OSGShapeNode.moc"
|
@ -1,7 +1,7 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file OSGCubeNode.hpp
|
||||
* @file OSGShapeNode.hpp
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* @addtogroup
|
||||
* @{
|
||||
@ -25,19 +25,32 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef _H_OSGQTQUICK_CUBENODE_H_
|
||||
#define _H_OSGQTQUICK_CUBENODE_H_
|
||||
#ifndef _H_OSGQTQUICK_SHAPENODE_H_
|
||||
#define _H_OSGQTQUICK_SHAPENODE_H_
|
||||
|
||||
#include "Export.hpp"
|
||||
#include "OSGNode.hpp"
|
||||
|
||||
namespace osgQtQuick {
|
||||
class OSGQTQUICK_EXPORT OSGCubeNode : public OSGNode {
|
||||
class ShapeType : public QObject {
|
||||
Q_OBJECT
|
||||
public:
|
||||
enum Enum { Cube, Sphere, Torus, Axis };
|
||||
Q_ENUMS(Enum) // TODO switch to Q_ENUM once on Qt 5.5
|
||||
};
|
||||
|
||||
class OSGQTQUICK_EXPORT OSGShapeNode : public OSGNode {
|
||||
Q_OBJECT Q_PROPERTY(osgQtQuick::ShapeType::Enum shapeType READ shapeType WRITE setShapeType NOTIFY shapeTypeChanged)
|
||||
|
||||
public:
|
||||
OSGCubeNode(QObject *parent = 0);
|
||||
virtual ~OSGCubeNode();
|
||||
OSGShapeNode(QObject *parent = 0);
|
||||
virtual ~OSGShapeNode();
|
||||
|
||||
ShapeType::Enum shapeType() const;
|
||||
void setShapeType(ShapeType::Enum);
|
||||
|
||||
signals:
|
||||
void shapeTypeChanged(ShapeType::Enum);
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
@ -45,4 +58,4 @@ private:
|
||||
};
|
||||
} // namespace osgQtQuick
|
||||
|
||||
#endif // _H_OSGQTQUICK_CUBENODE_H_
|
||||
#endif // _H_OSGQTQUICK_SHAPENODE_H_
|
@ -183,20 +183,18 @@ public:
|
||||
return true;
|
||||
}
|
||||
|
||||
bool attach(osgViewer::View *view)
|
||||
void attachSkyNode(osgViewer::View *view)
|
||||
{
|
||||
if (!skyNode.valid()) {
|
||||
qWarning() << "OSGSkyNode::attach - invalid sky node" << skyNode;
|
||||
return false;
|
||||
return;
|
||||
}
|
||||
skyNode->attach(view, 0);
|
||||
return true;
|
||||
}
|
||||
|
||||
bool detach(osgViewer::View *view)
|
||||
void detachSkyNode(osgViewer::View *view)
|
||||
{
|
||||
qWarning() << "OSGSkyNode::detach - not implemented";
|
||||
return true;
|
||||
// TODO find a way to detach the skyNode (?)
|
||||
}
|
||||
|
||||
OSGSkyNode *const self;
|
||||
@ -275,14 +273,22 @@ void OSGSkyNode::setMinimumAmbientLight(double arg)
|
||||
}
|
||||
}
|
||||
|
||||
bool OSGSkyNode::attach(osgViewer::View *view)
|
||||
void OSGSkyNode::attach(osgViewer::View *view)
|
||||
{
|
||||
return h->attach(view);
|
||||
// qDebug() << "OSGSkyNode::attach " << view;
|
||||
if (h->sceneData) {
|
||||
h->sceneData->attach(view);
|
||||
}
|
||||
h->attachSkyNode(view);
|
||||
}
|
||||
|
||||
bool OSGSkyNode::detach(osgViewer::View *view)
|
||||
void OSGSkyNode::detach(osgViewer::View *view)
|
||||
{
|
||||
return h->detach(view);
|
||||
// qDebug() << "OSGSkyNode::detach " << view;
|
||||
h->detachSkyNode(view);
|
||||
if (h->sceneData) {
|
||||
h->sceneData->detach(view);
|
||||
}
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
||||
|
@ -66,8 +66,8 @@ public:
|
||||
double minimumAmbientLight();
|
||||
void setMinimumAmbientLight(double arg);
|
||||
|
||||
virtual bool attach(osgViewer::View *view);
|
||||
virtual bool detach(osgViewer::View *view);
|
||||
virtual void attach(osgViewer::View *view);
|
||||
virtual void detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void sceneDataChanged(OSGNode *node);
|
||||
|
@ -85,17 +85,12 @@ public:
|
||||
}
|
||||
|
||||
osg::Transform *transform = getOrCreateTransform();
|
||||
if (!transform) {
|
||||
qWarning() << "OSGTransformNode::acceptNode - transform is null";
|
||||
return false;
|
||||
}
|
||||
|
||||
transform->addChild(node);
|
||||
|
||||
self->setNode(transform);
|
||||
|
||||
dirty = true;
|
||||
updateNode();
|
||||
|
||||
return true;
|
||||
}
|
||||
@ -127,15 +122,18 @@ public:
|
||||
transform->getOrCreateStateSet()->setMode(GL_RESCALE_NORMAL, osg::StateAttribute::ON);
|
||||
}
|
||||
|
||||
// rotate
|
||||
osg::Quat q = osg::Quat(
|
||||
osg::DegreesToRadians(rotate.x()), osg::Vec3d(1, 0, 0),
|
||||
osg::DegreesToRadians(rotate.y()), osg::Vec3d(0, 1, 0),
|
||||
osg::DegreesToRadians(rotate.z()), osg::Vec3d(0, 0, 1));
|
||||
// attitude
|
||||
double roll = osg::DegreesToRadians(attitude.x());
|
||||
double pitch = osg::DegreesToRadians(attitude.y());
|
||||
double yaw = osg::DegreesToRadians(attitude.z());
|
||||
osg::Quat q = osg::Quat(
|
||||
roll, osg::Vec3d(0, 1, 0),
|
||||
pitch, osg::Vec3d(1, 0, 0),
|
||||
yaw, osg::Vec3d(0, 0, -1));
|
||||
transform->setAttitude(q);
|
||||
|
||||
// translate
|
||||
transform->setPosition(osg::Vec3d(translate.x(), translate.y(), translate.z()));
|
||||
// position
|
||||
transform->setPosition(osg::Vec3d(position.x(), position.y(), position.z()));
|
||||
}
|
||||
|
||||
OSGTransformNode *const self;
|
||||
@ -147,8 +145,8 @@ public:
|
||||
bool dirty;
|
||||
|
||||
QVector3D scale;
|
||||
QVector3D rotate;
|
||||
QVector3D translate;
|
||||
QVector3D attitude;
|
||||
QVector3D position;
|
||||
|
||||
private slots:
|
||||
|
||||
@ -164,7 +162,6 @@ private slots:
|
||||
void OSGTransformNode::Hidden::NodeUpdateCallback::operator()(osg::Node *node, osg::NodeVisitor *nv)
|
||||
{
|
||||
h->updateNode();
|
||||
traverse(node, nv);
|
||||
}
|
||||
|
||||
OSGTransformNode::OSGTransformNode(QObject *parent) : OSGNode(parent), h(new Hidden(this))
|
||||
@ -203,31 +200,48 @@ void OSGTransformNode::setScale(QVector3D arg)
|
||||
}
|
||||
}
|
||||
|
||||
QVector3D OSGTransformNode::rotate() const
|
||||
QVector3D OSGTransformNode::attitude() const
|
||||
{
|
||||
return h->rotate;
|
||||
return h->attitude;
|
||||
}
|
||||
|
||||
void OSGTransformNode::setRotate(QVector3D arg)
|
||||
void OSGTransformNode::setAttitude(QVector3D arg)
|
||||
{
|
||||
if (h->rotate != arg) {
|
||||
h->rotate = arg;
|
||||
h->dirty = true;
|
||||
emit rotateChanged(rotate());
|
||||
if (h->attitude != arg) {
|
||||
h->attitude = arg;
|
||||
h->dirty = true;
|
||||
emit attitudeChanged(attitude());
|
||||
}
|
||||
}
|
||||
|
||||
QVector3D OSGTransformNode::translate() const
|
||||
QVector3D OSGTransformNode::position() const
|
||||
{
|
||||
return h->translate;
|
||||
return h->position;
|
||||
}
|
||||
|
||||
void OSGTransformNode::setTranslate(QVector3D arg)
|
||||
void OSGTransformNode::setPosition(QVector3D arg)
|
||||
{
|
||||
if (h->translate != arg) {
|
||||
h->translate = arg;
|
||||
h->dirty = true;
|
||||
emit translateChanged(translate());
|
||||
if (h->position != arg) {
|
||||
h->position = arg;
|
||||
h->dirty = true;
|
||||
emit positionChanged(position());
|
||||
}
|
||||
}
|
||||
|
||||
void OSGTransformNode::attach(osgViewer::View *view)
|
||||
{
|
||||
// qDebug() << "OSGTransformNode::attach " << view;
|
||||
if (h->modelData) {
|
||||
h->modelData->attach(view);
|
||||
}
|
||||
h->updateNode();
|
||||
}
|
||||
|
||||
void OSGTransformNode::detach(osgViewer::View *view)
|
||||
{
|
||||
// qDebug() << "OSGTransformNode::detach " << view;
|
||||
if (h->modelData) {
|
||||
h->modelData->detach(view);
|
||||
}
|
||||
}
|
||||
} // namespace osgQtQuick
|
||||
|
@ -41,8 +41,8 @@ class OSGQTQUICK_EXPORT OSGTransformNode : public OSGNode {
|
||||
Q_PROPERTY(osgQtQuick::OSGNode *modelData READ modelData WRITE setModelData NOTIFY modelDataChanged)
|
||||
|
||||
Q_PROPERTY(QVector3D scale READ scale WRITE setScale NOTIFY scaleChanged)
|
||||
Q_PROPERTY(QVector3D rotate READ rotate WRITE setRotate NOTIFY rotateChanged)
|
||||
Q_PROPERTY(QVector3D translate READ translate WRITE setTranslate NOTIFY translateChanged)
|
||||
Q_PROPERTY(QVector3D attitude READ attitude WRITE setAttitude NOTIFY attitudeChanged)
|
||||
Q_PROPERTY(QVector3D position READ position WRITE setPosition NOTIFY positionChanged)
|
||||
|
||||
public:
|
||||
OSGTransformNode(QObject *parent = 0);
|
||||
@ -54,18 +54,21 @@ public:
|
||||
QVector3D scale() const;
|
||||
void setScale(QVector3D arg);
|
||||
|
||||
QVector3D rotate() const;
|
||||
void setRotate(QVector3D arg);
|
||||
QVector3D attitude() const;
|
||||
void setAttitude(QVector3D arg);
|
||||
|
||||
QVector3D translate() const;
|
||||
void setTranslate(QVector3D arg);
|
||||
QVector3D position() const;
|
||||
void setPosition(QVector3D arg);
|
||||
|
||||
virtual void attach(osgViewer::View *view);
|
||||
virtual void detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void modelDataChanged(OSGNode *node);
|
||||
|
||||
void scaleChanged(QVector3D arg);
|
||||
void rotateChanged(QVector3D arg);
|
||||
void translateChanged(QVector3D arg);
|
||||
void attitudeChanged(QVector3D arg);
|
||||
void positionChanged(QVector3D arg);
|
||||
|
||||
private:
|
||||
struct Hidden;
|
||||
|
@ -48,6 +48,7 @@
|
||||
|
||||
#include <QOpenGLContext>
|
||||
#include <QQuickWindow>
|
||||
#include <QQuickFramebufferObject>
|
||||
#include <QOpenGLFramebufferObject>
|
||||
#include <QSGSimpleTextureNode>
|
||||
#include <QOpenGLFunctions>
|
||||
@ -151,37 +152,32 @@ public:
|
||||
return true;
|
||||
}
|
||||
|
||||
bool attach(osgViewer::View *view)
|
||||
void attach(osgViewer::View *view)
|
||||
{
|
||||
if (!sceneData) {
|
||||
qWarning() << "OSGViewport::attach - invalid scene!";
|
||||
return false;
|
||||
return;
|
||||
}
|
||||
// attach scene
|
||||
attach(view, sceneData->node());
|
||||
// attach camera
|
||||
if (camera) {
|
||||
camera->attach(view);
|
||||
} else {
|
||||
qWarning() << "OSGViewport::attach - no camera!";
|
||||
}
|
||||
// attach scene
|
||||
if (!attach(view, sceneData->node())) {
|
||||
qWarning() << "OSGViewport::attach - failed to attach node!";
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool attach(osgViewer::View *view, osg::Node *node)
|
||||
void attach(osgViewer::View *view, osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGViewport::attach" << node;
|
||||
if (!view) {
|
||||
qWarning() << "OSGViewport::attach - view is null";
|
||||
return false;
|
||||
return;
|
||||
}
|
||||
if (!node) {
|
||||
qWarning() << "OSGViewport::attach - node is null";
|
||||
view->setSceneData(NULL);
|
||||
return true;
|
||||
return;
|
||||
}
|
||||
|
||||
#ifdef USE_OSGEARTH
|
||||
@ -192,23 +188,22 @@ public:
|
||||
|
||||
// remove light to prevent unnecessary state changes in SceneView
|
||||
// scene will get light from sky
|
||||
view->setLightingMode(osg::View::NO_LIGHT);
|
||||
// view->setLightingMode(osg::View::NO_LIGHT);
|
||||
}
|
||||
#endif
|
||||
|
||||
qDebug() << "OSGViewport::attach - set scene" << node;
|
||||
view->setSceneData(node);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool detach(osgViewer::View *view)
|
||||
void detach(osgViewer::View *view)
|
||||
{
|
||||
qDebug() << "OSGViewport::detach" << view;
|
||||
// detach camera
|
||||
if (camera) {
|
||||
camera->detach(view);
|
||||
}
|
||||
return true;
|
||||
// detach scene
|
||||
view->setSceneData(NULL);
|
||||
}
|
||||
|
||||
void onSceneGraphInitialized()
|
||||
@ -237,8 +232,8 @@ public:
|
||||
return;
|
||||
}
|
||||
view = createView();
|
||||
self->attach(view.get());
|
||||
viewer->addView(view);
|
||||
self->attach(view.get());
|
||||
start();
|
||||
}
|
||||
|
||||
@ -290,10 +285,8 @@ public:
|
||||
|
||||
int frameTimer;
|
||||
|
||||
osg::ref_ptr<osgViewer::CompositeViewer> viewer;
|
||||
osg::ref_ptr<osgViewer::View> view;
|
||||
|
||||
static osg::ref_ptr<osg::GraphicsContext> dummy;
|
||||
osg::ref_ptr<osgViewer::CompositeViewer> viewer;
|
||||
osg::ref_ptr<osgViewer::View> view;
|
||||
|
||||
static QtKeyboardMap keyMap;
|
||||
|
||||
@ -359,10 +352,11 @@ public:
|
||||
// view->addEventHandler(new osgViewer::ScreenCaptureHandler);
|
||||
|
||||
// setup graphics context and camera
|
||||
osg::Camera *camera = view->getCamera();
|
||||
osg::GraphicsContext *gc = createGraphicsContext();
|
||||
|
||||
osg::Camera *camera = view->getCamera();
|
||||
camera->setGraphicsContext(gc);
|
||||
camera->setViewport(new osg::Viewport(0, 0, gc->getTraits()->width, gc->getTraits()->height));
|
||||
camera->setViewport(0, 0, gc->getTraits()->width, gc->getTraits()->height);
|
||||
|
||||
return view;
|
||||
}
|
||||
@ -504,6 +498,11 @@ public:
|
||||
}
|
||||
firstFrame = false;
|
||||
}
|
||||
osg::Viewport *viewport = h->view->getCamera()->getViewport();
|
||||
if ((viewport->width() != item->width()) || (viewport->height() != item->height())) {
|
||||
h->view->getCamera()->getGraphicsContext()->resized(0, 0, item->width(), item->height());
|
||||
}
|
||||
|
||||
h->viewer->advance();
|
||||
h->viewer->eventTraversal();
|
||||
h->viewer->updateTraversal();
|
||||
@ -522,7 +521,6 @@ public:
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
if (needToDoFrame) {
|
||||
// needed to properly render models without terrain (Qt bug?)
|
||||
QOpenGLContext::currentContext()->functions()->glUseProgram(0);
|
||||
@ -538,13 +536,8 @@ public:
|
||||
|
||||
QOpenGLFramebufferObject *createFramebufferObject(const QSize &size)
|
||||
{
|
||||
// qDebug() << "ViewportRenderer::createFramebufferObject" << size;
|
||||
if (h->view.valid()) {
|
||||
h->view->getCamera()->getGraphicsContext()->resized(0, 0, size.width(), size.height());
|
||||
h->view->getEventQueue()->windowResize(0, 0, size.width(), size.height());
|
||||
}
|
||||
|
||||
QOpenGLFramebufferObjectFormat format;
|
||||
|
||||
format.setAttachment(QOpenGLFramebufferObject::CombinedDepthStencil);
|
||||
// format.setSamples(4);
|
||||
|
||||
@ -565,7 +558,6 @@ private:
|
||||
bool needToDoFrame;
|
||||
};
|
||||
|
||||
osg::ref_ptr<osg::GraphicsContext> OSGViewport::Hidden::dummy;
|
||||
QtKeyboardMap OSGViewport::Hidden::keyMap = QtKeyboardMap();
|
||||
|
||||
/* class OSGViewport */
|
||||
@ -643,41 +635,22 @@ QQuickFramebufferObject::Renderer *OSGViewport::createRenderer() const
|
||||
return new ViewportRenderer(h);
|
||||
}
|
||||
|
||||
bool OSGViewport::attach(osgViewer::View *view)
|
||||
void OSGViewport::attach(osgViewer::View *view)
|
||||
{
|
||||
qDebug() << "OSGViewport::attach" << view;
|
||||
|
||||
h->attach(view);
|
||||
|
||||
QListIterator<QObject *> i(children());
|
||||
while (i.hasNext()) {
|
||||
QObject *object = i.next();
|
||||
OSGNode *node = qobject_cast<OSGNode *>(object);
|
||||
if (node) {
|
||||
qDebug() << "OSGViewport::attach - child" << node;
|
||||
node->attach(view);
|
||||
}
|
||||
// qDebug() << "OSGViewport::attach" << view;
|
||||
if (h->sceneData) {
|
||||
h->sceneData->attach(view);
|
||||
}
|
||||
|
||||
return true;
|
||||
h->attach(view);
|
||||
}
|
||||
|
||||
bool OSGViewport::detach(osgViewer::View *view)
|
||||
void OSGViewport::detach(osgViewer::View *view)
|
||||
{
|
||||
qDebug() << "OSGViewport::detach" << view;
|
||||
|
||||
QListIterator<QObject *> i(children());
|
||||
while (i.hasNext()) {
|
||||
QObject *object = i.next();
|
||||
OSGNode *node = qobject_cast<OSGNode *>(object);
|
||||
if (node) {
|
||||
node->detach(view);
|
||||
}
|
||||
}
|
||||
|
||||
h->detach(view);
|
||||
|
||||
return true;
|
||||
if (h->sceneData) {
|
||||
h->sceneData->detach(view);
|
||||
}
|
||||
}
|
||||
|
||||
void OSGViewport::releaseResources()
|
||||
@ -705,10 +678,8 @@ QSGNode *OSGViewport::updatePaintNode(QSGNode *node, QQuickItem::UpdatePaintNode
|
||||
|
||||
QPointF OSGViewport::mousePoint(QMouseEvent *event)
|
||||
{
|
||||
// qreal x = 2.0 * (event->x() - width() / 2) / width();
|
||||
// qreal y = 2.0 * (event->y() - height() / 2) / height();
|
||||
qreal x = event->x();
|
||||
qreal y = event->y();
|
||||
qreal x = 2.0 * (event->x() - width() / 2) / width();
|
||||
qreal y = 2.0 * (event->y() - height() / 2) / height();
|
||||
|
||||
return QPointF(x, y);
|
||||
}
|
||||
|
@ -75,8 +75,8 @@ public:
|
||||
virtual Renderer *createRenderer() const;
|
||||
virtual void releaseResources();
|
||||
|
||||
virtual bool attach(osgViewer::View *view);
|
||||
virtual bool detach(osgViewer::View *view);
|
||||
virtual void attach(osgViewer::View *view);
|
||||
virtual void detach(osgViewer::View *view);
|
||||
|
||||
signals:
|
||||
void updateModeChanged(UpdateMode::Enum mode);
|
||||
|
@ -147,7 +147,7 @@ void OsgEarth::initializeCache()
|
||||
} else {
|
||||
qWarning() << "OsgEarth::initializeCache - Failed to initialize cache";
|
||||
}
|
||||
#endif
|
||||
#endif // ifdef USE_OSGEARTH
|
||||
}
|
||||
|
||||
void OsgEarth::displayInfo()
|
||||
|
@ -36,11 +36,13 @@ QMAKE_CXXFLAGS += -Wno-unused-parameter
|
||||
HEADERS += \
|
||||
osgearth_global.h \
|
||||
utility.h \
|
||||
shapeutils.h \
|
||||
qtwindowingsystem.h \
|
||||
osgearth.h
|
||||
|
||||
SOURCES += \
|
||||
utility.cpp \
|
||||
shapeutils.cpp \
|
||||
qtwindowingsystem.cpp \
|
||||
osgearth.cpp
|
||||
|
||||
@ -49,7 +51,7 @@ HEADERS += \
|
||||
osgQtQuick/OSGNode.hpp \
|
||||
osgQtQuick/OSGGroup.hpp \
|
||||
osgQtQuick/OSGTransformNode.hpp \
|
||||
osgQtQuick/OSGCubeNode.hpp \
|
||||
osgQtQuick/OSGShapeNode.hpp \
|
||||
osgQtQuick/OSGTextNode.hpp \
|
||||
osgQtQuick/OSGFileNode.hpp \
|
||||
osgQtQuick/OSGBackgroundNode.hpp \
|
||||
@ -60,7 +62,7 @@ SOURCES += \
|
||||
osgQtQuick/OSGNode.cpp \
|
||||
osgQtQuick/OSGGroup.cpp \
|
||||
osgQtQuick/OSGTransformNode.cpp \
|
||||
osgQtQuick/OSGCubeNode.cpp \
|
||||
osgQtQuick/OSGShapeNode.cpp \
|
||||
osgQtQuick/OSGTextNode.cpp \
|
||||
osgQtQuick/OSGFileNode.cpp \
|
||||
osgQtQuick/OSGBackgroundNode.cpp \
|
||||
|
261
ground/gcs/src/libs/osgearth/shapeutils.cpp
Normal file
261
ground/gcs/src/libs/osgearth/shapeutils.cpp
Normal file
@ -0,0 +1,261 @@
|
||||
#include "shapeutils.h"
|
||||
|
||||
#include <math.h>
|
||||
|
||||
#include <osg/Geode>
|
||||
#include <osg/Group>
|
||||
#include <osg/PositionAttitudeTransform>
|
||||
#include <osg/Geometry>
|
||||
#include <osg/Shape>
|
||||
#include <osg/ShapeDrawable>
|
||||
#include <osg/Vec3>
|
||||
#include <osg/Vec4>
|
||||
#include <osg/ShadeModel>
|
||||
|
||||
namespace ShapeUtils {
|
||||
osg::Geode *createSphere(const osg::Vec4 &color, float radius)
|
||||
{
|
||||
osg::TessellationHints *sphereHints = new osg::TessellationHints;
|
||||
// sphereHints->setDetailRatio(0.1f);
|
||||
// sphereHints->setCreateBody(true);
|
||||
osg::Sphere *sphere = new osg::Sphere(osg::Vec3(0, 0, 0), radius);
|
||||
osg::ShapeDrawable *sphereDrawable = new osg::ShapeDrawable(sphere, sphereHints);
|
||||
|
||||
sphereDrawable->setColor(color);
|
||||
|
||||
osg::Geode *geode = new osg::Geode;
|
||||
geode->addDrawable(sphereDrawable);
|
||||
|
||||
return geode;
|
||||
}
|
||||
|
||||
osg::Geode *createCube()
|
||||
{
|
||||
// Declare a group to act as root node of a scene:
|
||||
// osg::Group* root = new osg::Group();
|
||||
|
||||
// Declare a box class (derived from shape class) instance
|
||||
// This constructor takes an osg::Vec3 to define the center
|
||||
// and a float to define the height, width and depth.
|
||||
// (an overloaded constructor allows you to specify unique
|
||||
// height, width and height values.)
|
||||
osg::Box *unitCube = new osg::Box(osg::Vec3(0, 0, 0), 1.0f);
|
||||
|
||||
// Declare an instance of the shape drawable class and initialize
|
||||
// it with the unitCube shape we created above.
|
||||
// This class is derived from 'drawable' so instances of this
|
||||
// class can be added to Geode instances.
|
||||
osg::ShapeDrawable *unitCubeDrawable = new osg::ShapeDrawable(unitCube);
|
||||
|
||||
// Declare a instance of the geode class:
|
||||
osg::Geode *geode = new osg::Geode();
|
||||
|
||||
|
||||
// Add the unit cube drawable to the geode:
|
||||
geode->addDrawable(unitCubeDrawable);
|
||||
|
||||
// osg::PolygonMode *pm = new osg::PolygonMode();
|
||||
// pm->setMode( osg::PolygonMode::FRONT_AND_BACK, osg::PolygonMode::LINE );
|
||||
//
|
||||
// osg::StateSet *stateSet = new osg::StateSet();
|
||||
// stateSet->setAttributeAndModes( pm,
|
||||
// osg::StateAttribute::OVERRIDE | osg::StateAttribute::ON );
|
||||
// geode->setStateSet(stateSet);
|
||||
|
||||
// Add the geode to the scene:
|
||||
return geode;
|
||||
}
|
||||
|
||||
osg::PositionAttitudeTransform *createArrow(const osg::Vec4 &color)
|
||||
{
|
||||
osg::ref_ptr<osg::Geode> geode = new osg::Geode;
|
||||
|
||||
double radius = 0.04;
|
||||
|
||||
osg::TessellationHints *cylinderHints = new osg::TessellationHints;
|
||||
|
||||
cylinderHints->setDetailRatio(0.1f);
|
||||
cylinderHints->setCreateBody(true);
|
||||
// cylinderHints->setCreateFrontFace(false);
|
||||
// cylinderHints->setCreateBackFace(false);
|
||||
osg::Cylinder *cylinder = new osg::Cylinder(osg::Vec3(0, 0, 0.4), radius, 0.8);
|
||||
// cylinder->setRotation(quat);
|
||||
osg::ShapeDrawable *cylinderDrawable = new osg::ShapeDrawable(cylinder, cylinderHints);
|
||||
cylinderDrawable->setColor(color);
|
||||
geode->addDrawable(cylinderDrawable);
|
||||
|
||||
osg::TessellationHints *coneHints = new osg::TessellationHints;
|
||||
coneHints->setDetailRatio(0.5f);
|
||||
coneHints->setCreateBottom(true);
|
||||
osg::Cone *cone = new osg::Cone(osg::Vec3(0, 0, 0.8), radius * 2, 0.2);
|
||||
// cone->setRotation(quat);
|
||||
osg::ShapeDrawable *coneDrawable = new osg::ShapeDrawable(cone, coneHints);
|
||||
coneDrawable->setColor(color);
|
||||
geode->addDrawable(coneDrawable);
|
||||
|
||||
osg::PositionAttitudeTransform *transform = new osg::PositionAttitudeTransform();
|
||||
transform->addChild(geode);
|
||||
|
||||
return transform;
|
||||
}
|
||||
|
||||
osg::Node *create3DAxis()
|
||||
{
|
||||
osg::PositionAttitudeTransform *xAxis = createArrow(osg::Vec4(1, 0, 0, 1));
|
||||
|
||||
xAxis->setAttitude(osg::Quat(M_PI / 2.0, osg::Vec3(0, 1, 0)));
|
||||
|
||||
osg::PositionAttitudeTransform *yAxis = createArrow(osg::Vec4(0, 1, 0, 1));
|
||||
yAxis->setAttitude(osg::Quat(-M_PI / 2.0, osg::Vec3(1, 0, 0)));
|
||||
|
||||
osg::PositionAttitudeTransform *zAxis = createArrow(osg::Vec4(0, 0, 1, 1));
|
||||
|
||||
osg::Node *center = createSphere(osg::Vec4(0.7, 0.7, .7, 1), 0.08);
|
||||
|
||||
osg::Group *group = new osg::Group();
|
||||
group->addChild(xAxis);
|
||||
group->addChild(yAxis);
|
||||
group->addChild(zAxis);
|
||||
group->addChild(center);
|
||||
return group;
|
||||
}
|
||||
|
||||
osg::Node *createOrientatedTorus(float innerRadius, float outerRadius)
|
||||
{
|
||||
osg::Node *node = createTorus(innerRadius, outerRadius, 64, 32);
|
||||
|
||||
osg::PositionAttitudeTransform *transform = new osg::PositionAttitudeTransform();
|
||||
|
||||
transform->addChild(node);
|
||||
|
||||
osg::Quat q = osg::Quat(
|
||||
M_PI / 2, osg::Vec3d(1, 0, 0),
|
||||
0, osg::Vec3d(0, 1, 0),
|
||||
0, osg::Vec3d(0, 0, 1));
|
||||
transform->setAttitude(q);
|
||||
|
||||
// transform->getOrCreateStateSet()->setMode(GL_NORMALIZE, osg::StateAttribute::ON);
|
||||
// node->getOrCreateStateSet()->setMode(GL_RESCALE_NORMAL, osg::StateAttribute::ON);
|
||||
|
||||
return transform;
|
||||
}
|
||||
|
||||
osg::Geode *createTorus(float innerRadius, float outerRadius, float sweepCuts, float sphereCuts)
|
||||
{
|
||||
osg::ref_ptr<osg::Geode> geode = new osg::Geode;
|
||||
|
||||
bool create_body = true;
|
||||
|
||||
if (create_body) {
|
||||
float inner = innerRadius;
|
||||
float outer = outerRadius;
|
||||
float tube_radius = (outer - inner) * 0.5;
|
||||
float avg_center = (inner + outer) * 0.5;
|
||||
|
||||
float start_sweep = 0; // this->getStartSweep();
|
||||
float end_sweep = osg::DegreesToRadians(360.0); // this->getEndSweep();
|
||||
|
||||
int torus_sweeps = sweepCuts;
|
||||
int sphere_sweeps = sphereCuts;
|
||||
|
||||
float dsweep = (end_sweep - start_sweep) / (float)torus_sweeps;
|
||||
float dphi = osg::DegreesToRadians(360.0) / (float)sphere_sweeps;
|
||||
|
||||
for (int j = 0; j < sphere_sweeps; j++) {
|
||||
osg::Vec3Array *vertices = new osg::Vec3Array;
|
||||
osg::Vec3Array *normals = new osg::Vec3Array;
|
||||
|
||||
float phi = dphi * (float)j;
|
||||
float cosPhi = cosf(phi);
|
||||
float sinPhi = sinf(phi);
|
||||
float next_cosPhi = cosf(phi + dphi);
|
||||
float next_sinPhi = sinf(phi + dphi);
|
||||
|
||||
float z = tube_radius * sinPhi;
|
||||
float yPrime = avg_center + tube_radius * cosPhi;
|
||||
|
||||
float next_z = tube_radius * next_sinPhi;
|
||||
float next_yPrime = avg_center + tube_radius * next_cosPhi;
|
||||
|
||||
float old_x = yPrime * cosf(-dsweep);
|
||||
float old_y = yPrime * sinf(-dsweep);
|
||||
float old_z = z;
|
||||
|
||||
for (int i = 0; i < torus_sweeps; ++i) {
|
||||
float sweep = start_sweep + dsweep * i;
|
||||
float cosSweep = cosf(sweep);
|
||||
float sinSweep = sinf(sweep);
|
||||
|
||||
float x = yPrime * cosSweep;
|
||||
float y = yPrime * sinSweep;
|
||||
|
||||
float next_x = next_yPrime * cosSweep;
|
||||
float next_y = next_yPrime * sinSweep;
|
||||
|
||||
vertices->push_back(osg::Vec3(next_x, next_y, next_z));
|
||||
vertices->push_back(osg::Vec3(x, y, z));
|
||||
|
||||
// calculate normals
|
||||
osg::Vec3 lateral(next_x - x, next_y - y, next_z - z);
|
||||
osg::Vec3 longitudinal(x - old_x, y - old_y, z - old_z);
|
||||
osg::Vec3 normal = longitudinal ^ lateral; // cross product
|
||||
normal.normalize();
|
||||
|
||||
normals->push_back(normal);
|
||||
normals->push_back(normal);
|
||||
|
||||
old_x = x;
|
||||
old_y = y;
|
||||
old_z = z;
|
||||
} // end torus loop
|
||||
|
||||
// the last point
|
||||
float last_sweep = start_sweep + end_sweep;
|
||||
float cosLastSweep = cosf(last_sweep);
|
||||
float sinLastSweep = sinf(last_sweep);
|
||||
|
||||
float x = yPrime * cosLastSweep;
|
||||
float y = yPrime * sinLastSweep;
|
||||
|
||||
float next_x = next_yPrime * cosLastSweep;
|
||||
float next_y = next_yPrime * sinLastSweep;
|
||||
|
||||
vertices->push_back(osg::Vec3(next_x, next_y, next_z));
|
||||
vertices->push_back(osg::Vec3(x, y, z));
|
||||
|
||||
osg::Vec3 lateral(next_x - x, next_y - y, next_z - z);
|
||||
osg::Vec3 longitudinal(x - old_x, y - old_y, z - old_z);
|
||||
osg::Vec3 norm = longitudinal ^ lateral;
|
||||
norm.normalize();
|
||||
|
||||
normals->push_back(norm);
|
||||
normals->push_back(norm);
|
||||
|
||||
osg::ShadeModel *shademodel = new osg::ShadeModel;
|
||||
shademodel->setMode(osg::ShadeModel::SMOOTH);
|
||||
|
||||
osg::StateSet *stateset = new osg::StateSet;
|
||||
stateset->setAttribute(shademodel);
|
||||
|
||||
osg::ref_ptr<osg::Geometry> geometry = new osg::Geometry;
|
||||
geometry->setStateSet(stateset);
|
||||
geometry->setVertexArray(vertices);
|
||||
|
||||
osg::Vec4Array *colors = new osg::Vec4Array;
|
||||
colors->push_back(osg::Vec4(1.0, 1.0, 0.0, 1.0)); // this->getColor());
|
||||
geometry->setColorArray(colors);
|
||||
geometry->setColorBinding(osg::Geometry::BIND_OVERALL);
|
||||
|
||||
geometry->setNormalArray(normals);
|
||||
geometry->setNormalBinding(osg::Geometry::BIND_PER_VERTEX);
|
||||
|
||||
geometry->addPrimitiveSet(
|
||||
new osg::DrawArrays(osg::PrimitiveSet::QUAD_STRIP, 0,
|
||||
vertices->size()));
|
||||
geode->addDrawable(geometry.get());
|
||||
} // end cirle loop
|
||||
} // endif create_body
|
||||
|
||||
return geode.release();
|
||||
}
|
||||
}
|
21
ground/gcs/src/libs/osgearth/shapeutils.h
Normal file
21
ground/gcs/src/libs/osgearth/shapeutils.h
Normal file
@ -0,0 +1,21 @@
|
||||
#ifndef SHAPE_UTILS_H
|
||||
#define SHAPE_UTILS_H
|
||||
|
||||
#include <osg/Vec4>
|
||||
|
||||
namespace osg {
|
||||
class Node;
|
||||
class Geode;
|
||||
class PositionAttitudeTransform;
|
||||
}
|
||||
|
||||
namespace ShapeUtils {
|
||||
osg::Geode *createCube();
|
||||
osg::Geode *createSphere(const osg::Vec4 &color, float radius);
|
||||
osg::PositionAttitudeTransform *createArrow(const osg::Vec4 &color);
|
||||
osg::Node *create3DAxis();
|
||||
osg::Node *createOrientatedTorus(float innerRadius, float outerRadius);
|
||||
osg::Geode *createTorus(float innerRadius, float outerRadius, float sweepCuts, float sphereCuts);
|
||||
}
|
||||
|
||||
#endif /* SHAPE_UTILS_H */
|
@ -32,7 +32,7 @@
|
||||
#include "osgQtQuick/OSGGroup.hpp"
|
||||
#include "osgQtQuick/OSGFileNode.hpp"
|
||||
#include "osgQtQuick/OSGTransformNode.hpp"
|
||||
#include "osgQtQuick/OSGCubeNode.hpp"
|
||||
#include "osgQtQuick/OSGShapeNode.hpp"
|
||||
#include "osgQtQuick/OSGTextNode.hpp"
|
||||
#include "osgQtQuick/OSGModelNode.hpp"
|
||||
#include "osgQtQuick/OSGBackgroundNode.hpp"
|
||||
@ -529,7 +529,8 @@ void registerTypes()
|
||||
|
||||
qmlRegisterType<osgQtQuick::OSGTextNode>("OsgQtQuick", maj, min, "OSGTextNode");
|
||||
|
||||
qmlRegisterType<osgQtQuick::OSGCubeNode>("OsgQtQuick", maj, min, "OSGCubeNode");
|
||||
qmlRegisterType<osgQtQuick::OSGShapeNode>("OsgQtQuick", maj, min, "OSGShapeNode");
|
||||
qmlRegisterType<osgQtQuick::ShapeType>("OsgQtQuick", maj, min, "ShapeType");
|
||||
|
||||
qmlRegisterType<osgQtQuick::OSGBackgroundNode>("OsgQtQuick", maj, min, "OSGBackgroundNode");
|
||||
|
||||
|
@ -61,9 +61,9 @@ OSGViewport {
|
||||
|
||||
OSGTransformNode {
|
||||
id: modelTransformNode
|
||||
modelData: modelFileNode
|
||||
// model dimensions are in mm, scale to meters
|
||||
scale: Qt.vector3d(0.001, 0.001, 0.001)
|
||||
modelData: modelFileNode
|
||||
}
|
||||
|
||||
OSGFileNode {
|
||||
|
@ -47,8 +47,7 @@ Item {
|
||||
OSGTransformNode {
|
||||
id: transformNode
|
||||
modelData: fileNode
|
||||
rotate: Qt.vector3d(UAV.attitudePitch(), UAV.attitudeRoll(), -UAV.attitudeYaw())
|
||||
//scale: Qt.vector3d(0.001, 0.001, 0.001)
|
||||
attitude: UAV.attitude()
|
||||
}
|
||||
|
||||
OSGFileNode {
|
||||
|
@ -81,7 +81,7 @@ Qt.include("common.js")
|
||||
*/
|
||||
|
||||
function attitude() {
|
||||
return Qt.vector3d(attitudeState.pitch, attitudeState.roll, -attitudeState.yaw);
|
||||
return Qt.vector3d(attitudeState.roll, attitudeState.pitch, attitudeState.yaw);
|
||||
}
|
||||
|
||||
function attitudeRoll() {
|
||||
|
Loading…
x
Reference in New Issue
Block a user