From Jan Perciva with changes from Robert Osfield, "I am submitting improved osgGA camera manipulators.

Changes:
- new mouse wheel zoom/movement/center functionality
- ability to fix vertical axis (important for CAD)
- possibility to specify values as absolute values or relative to model size
- kind of backward compatibility by flags passed to constructor
- and much more
- restructuring classes to use kind of hierarchy and standard way of event processing (handle methods). This way, there is much more code reusability and it is more easy to develop new kinds of manipulators.

Briefly, the new architecture keeps MatrixManipulator as base abstract class. StandardManipulator is the feature-rich standard manipulator with two main descendant classes: OrbitManipulator and FirstPersonManipulator. OrbitManipulator is base class for all trackball style manipulators, based on center, rotation and distance from center. FirstPersonManipulator is base for walk or fly style manipulators, using position and rotation for camera manipulation.
"

Changes by Robert: Replaced osg::Vec3 by osg::Vec3d, introduced DEFAULT_SETTINGS enum and usage.  Added frame time member variables in prep for improving throw animation when vysync is off.
This commit is contained in:
Robert Osfield 2010-05-25 12:05:13 +00:00
parent fce49ae02a
commit d0f48a2712
24 changed files with 2944 additions and 2187 deletions

View File

@ -0,0 +1,112 @@
/* -*-c++-*- OpenSceneGraph - Copyright (C) 1998-2006 Robert Osfield
*
* This library is open source and may be redistributed and/or modified under
* the terms of the OpenSceneGraph Public License (OSGPL) version 0.0 or
* (at your option) any later version. The full license is in LICENSE file
* included with this distribution, and on the openscenegraph.org website.
*
* This library 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
* OpenSceneGraph Public License for more details.
*
* FirstPersonManipulator code Copyright (C) 2010 PCJohn (Jan Peciva)
* while some pieces of code were reused from OSG.
* Thanks to company Cadwork (www.cadwork.ch) and
* Brno University of Technology (www.fit.vutbr.cz) for open-sourcing this work.
*/
#ifndef OSGGA_FIRST_PERSON_MANIPULATOR
#define OSGGA_FIRST_PERSON_MANIPULATOR 1
#include <osgGA/StandardManipulator>
namespace osgGA {
/** FirstPersonManipulator is base class for camera control based on position
and orientation of camera, like walk, drive, and flight manipulators. */
class OSGGA_EXPORT FirstPersonManipulator : public StandardManipulator
{
typedef StandardManipulator inherited;
public:
FirstPersonManipulator( int flags = DEFAULT_SETTINGS );
FirstPersonManipulator( const FirstPersonManipulator& fpm,
const osg::CopyOp& copyOp = osg::CopyOp::SHALLOW_COPY );
META_Object( osgGA, FirstPersonManipulator );
virtual void setByMatrix( const osg::Matrixd& matrix );
virtual void setByInverseMatrix( const osg::Matrixd& matrix );
virtual osg::Matrixd getMatrix() const;
virtual osg::Matrixd getInverseMatrix() const;
virtual void setTransformation( const osg::Vec3d& eye, const osg::Quat& rotation );
virtual void setTransformation( const osg::Vec3d& center, const osg::Vec3d& eye, const osg::Vec3d& up );
virtual void getTransformation( osg::Vec3d& eye, osg::Quat& rotation ) const;
virtual void getTransformation( osg::Vec3d& center, osg::Vec3d& eye, osg::Vec3d& up ) const;
virtual void setVelocity( const double& velocity );
inline double getVelocity() const;
virtual void setAcceleration( const double& acceleration, bool relativeToModelSize = false );
double getAcceleration( bool *relativeToModelSize = NULL ) const;
virtual void setMaxVelocity( const double& maxVelocity, bool relativeToModelSize = false );
double getMaxVelocity( bool *relativeToModelSize = NULL ) const;
virtual void setWheelMovement( const double& wheelMovement, bool relativeToModelSize = false );
double getWheelMovement( bool *relativeToModelSize = NULL ) const;
virtual void home( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual void home( double );
virtual void init( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
protected:
virtual bool handleMouseWheel( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool performMovementLeftMouseButton( const double dt, const double dx, const double dy );
virtual bool performMouseDeltaMovement( const float dx, const float dy );
virtual void applyAnimationStep( const double currentProgress, const double prevProgress );
virtual bool startAnimationByMousePointerIntersection( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
void moveForward( const double distance );
void moveForward( const osg::Quat& rotation, const double distance );
void moveRight( const double distance );
void moveUp( const double distance );
osg::Vec3d _eye;
osg::Quat _rotation;
double _velocity;
double _acceleration;
static int _accelerationFlagIndex;
double _maxVelocity;
static int _maxVelocityFlagIndex;
double _wheelMovement;
static int _wheelMovementFlagIndex;
class FirstPersonAnimationData : public AnimationData {
public:
osg::Quat _startRot;
osg::Quat _targetRot;
void start( const osg::Quat& startRotation, const osg::Quat& targetRotation, const double startTime );
};
virtual void allocAnimationData() { _animationData = new FirstPersonAnimationData(); }
};
//
// inline methods
//
/// Returns velocity.
double FirstPersonManipulator::getVelocity() const { return _velocity; }
}
#endif /* OSGGA_FIRST_PERSON_MANIPULATOR */

View File

@ -11,109 +11,72 @@
* OpenSceneGraph Public License for more details.
*/
#ifndef OSGGA_FLIGHTMANIPULATOR
#define OSGGA_FLIGHTMANIPULATOR 1
#ifndef OSGGA_FLIGHT_MANIPULATOR
#define OSGGA_FLIGHT_MANIPULATOR 1
#include <osgGA/MatrixManipulator>
#include <osg/Quat>
#include <osgGA/FirstPersonManipulator>
namespace osgGA{
/**
FlightManipulator is a MatrixManipulator which provides flight simulator-like
updating of the camera position & orientation. By default, the left mouse
button accelerates, the right mouse button decelerates, and the middle mouse
button (or left and right simultaneously) stops dead.
*/
namespace osgGA {
class OSGGA_EXPORT FlightManipulator : public MatrixManipulator
/** FlightManipulator is a MatrixManipulator which provides flight simulator-like
* updating of the camera position & orientation. By default, the left mouse
* button accelerates, the right mouse button decelerates, and the middle mouse
* button (or left and right simultaneously) stops dead.
*/
class OSGGA_EXPORT FlightManipulator : public FirstPersonManipulator
{
public:
typedef FirstPersonManipulator inherited;
FlightManipulator();
public:
virtual const char* className() const { return "Flight"; }
enum YawControlMode {
YAW_AUTOMATICALLY_WHEN_BANKED,
NO_AUTOMATIC_YAW
};
/** set the position of the matrix manipulator using a 4x4 Matrix.*/
virtual void setByMatrix(const osg::Matrixd& matrix);
FlightManipulator( int flags = UPDATE_MODEL_SIZE | COMPUTE_HOME_USING_BBOX );
FlightManipulator( const FlightManipulator& fpm,
const osg::CopyOp& copyOp = osg::CopyOp::SHALLOW_COPY );
/** set the position of the matrix manipulator using a 4x4 Matrix.*/
virtual void setByInverseMatrix(const osg::Matrixd& matrix) { setByMatrix(osg::Matrixd::inverse(matrix)); }
META_Object( osgGA, FlightManipulator );
/** get the position of the manipulator as 4x4 Matrix.*/
virtual osg::Matrixd getMatrix() const;
virtual void setYawControlMode( YawControlMode ycm );
inline YawControlMode getYawControlMode() const;
/** get the position of the manipulator as a inverse matrix of the manipulator, typically used as a model view matrix.*/
virtual osg::Matrixd getInverseMatrix() const;
virtual void home( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual void init( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual void getUsage( osg::ApplicationUsage& usage ) const;
protected:
virtual void setNode(osg::Node*);
virtual bool handleFrame( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleMouseMove( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleMouseDrag( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleMousePush( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleMouseRelease( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleKeyDown( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool flightHandleEvent( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual const osg::Node* getNode() const;
virtual bool performMovement();
virtual bool performMovementLeftMouseButton( const double dt, const double dx, const double dy );
virtual bool performMovementMiddleMouseButton( const double dt, const double dx, const double dy );
virtual bool performMovementRightMouseButton( const double dt, const double dx, const double dy );
virtual osg::Node* getNode();
virtual void home(const GUIEventAdapter& ea,GUIActionAdapter& us);
virtual void init(const GUIEventAdapter& ea,GUIActionAdapter& us);
virtual bool handle(const GUIEventAdapter& ea,GUIActionAdapter& us);
/** Get the keyboard and mouse usage of this manipulator.*/
virtual void getUsage(osg::ApplicationUsage& usage) const;
enum YawControlMode {
YAW_AUTOMATICALLY_WHEN_BANKED,
NO_AUTOMATIC_YAW
};
/** Configure the Yaw control for the flight model. */
void setYawControlMode(YawControlMode ycm) { _yawMode = ycm; }
void setModelScale(double in_ms) { _modelScale = in_ms; }
double getModelScale() const { return _modelScale; }
void setAcceleration(double in_acc) { _acceleration = in_acc; }
double getAcceleration() const { return _acceleration; }
void setVelocity(double in_vel) { _velocity = in_vel; }
double getVelocity() const { return _velocity; }
protected:
virtual ~FlightManipulator();
/** Reset the internal GUIEvent stack.*/
void flushMouseEventStack();
/** Add the current mouse GUIEvent to internal stack.*/
void addMouseEvent(const GUIEventAdapter& ea);
void computePosition(const osg::Vec3& eye,const osg::Vec3& lv,const osg::Vec3& up);
/** For the give mouse movement calculate the movement of the camera.
Return true is camera has moved and a redraw is required.*/
bool calcMovement();
// Internal event stack comprising last two mouse events.
osg::ref_ptr<const GUIEventAdapter> _ga_t1;
osg::ref_ptr<const GUIEventAdapter> _ga_t0;
osg::observer_ptr<osg::Node> _node;
double _modelScale;
double _acceleration;
double _velocity;
YawControlMode _yawMode;
osg::Vec3d _eye;
osg::Quat _rotation;
double _distance;
YawControlMode _yawMode;
};
//
// inline methods
//
/// Returns the Yaw control for the flight model.
inline FlightManipulator::YawControlMode FlightManipulator::getYawControlMode() const { return _yawMode; }
}
#endif
#endif /* OSGGA_FLIGHT_MANIPULATOR */

View File

@ -81,10 +81,6 @@ public:
// Overrides from MatrixManipulator...
/** set the minimum distance (as ratio) the eye point can be zoomed in towards the
center before the center is pushed forward.*/
virtual void setMinimumDistance(float minimumDistance);
/** set the coordinate frame which callback tells the manipulator which way is up, east and north.*/
virtual void setCoordinateFrameCallback(CoordinateFrameCallback* cb);
@ -106,12 +102,6 @@ public:
/** Get the FusionDistanceValue. Used by SceneView for setting up stereo convergence.*/
virtual float getFusionDistanceValue() const { return _current->getFusionDistanceValue(); }
/** Set the distance property. */
void setDistance(double distance);
/** Get the distance property. */
double getDistance() const;
virtual void setNode(osg::Node* n);
@ -125,7 +115,7 @@ public:
virtual void computeHomePosition();
virtual void home(const GUIEventAdapter& ee,GUIActionAdapter& aa) { if (_current.valid()) _current->home(ee,aa); }
virtual void home(const GUIEventAdapter& ee,GUIActionAdapter& aa);
virtual void init(const GUIEventAdapter& ee,GUIActionAdapter& aa) { if (_current.valid()) _current->init(ee,aa); }

View File

@ -36,11 +36,14 @@ amount of default functionality, for classes which wish to control OSG cameras
in response to GUI events.
*/
class OSGGA_EXPORT MatrixManipulator : public GUIEventHandler
{
class OSGGA_EXPORT MatrixManipulator : public GUIEventHandler {
typedef GUIEventHandler inherited;
public:
// We are not using META_Object as this is abstract class.
// Use META_Object(osgGA,YourManipulator); in your descendant non-abstract classes.
virtual const char* className() const { return "MatrixManipulator"; }
/** callback class to use to allow matrix manipulators to query the application for the local coordinate frame.*/
@ -52,16 +55,6 @@ public:
virtual ~CoordinateFrameCallback() {}
};
/** set the minimum distance (as ratio) the eye point can be zoomed in towards the
center before the center is pushed forward.*/
virtual void setMinimumDistance(float minimumDistance) { _minimumDistance=minimumDistance; }
/** get the minimum distance (as ratio) the eye point can be zoomed in */
float getMinimumDistance() const { return _minimumDistance; }
/** set the coordinate frame which callback tells the manipulator which way is up, east and north.*/
virtual void setCoordinateFrameCallback(CoordinateFrameCallback* cb) { _coordinateFrameCallback = cb; }
@ -100,12 +93,6 @@ public:
/** Get the FusionDistanceValue. Used by SceneView for setting up stereo convergence.*/
virtual float getFusionDistanceValue() const { return 1.0f; }
/** Set the distance parameter (used by TrackballManipulator etc.) */
void setDistance(double /*distance*/) {}
/** Get the distance parameter. */
virtual double getDistance() const { return 1.0; }
/** Set the mask to use when set up intersection traversal such as used in manipulators that follow terrain or have collision detection.
* The intersection traversal mask is useful for controlling what parts of the scene graph should be used for intersection purposes.*/
void setIntersectTraversalMask(unsigned int mask) { _intersectTraversalMask = mask; }
@ -150,20 +137,7 @@ public:
bool getAutoComputeHomePosition() const { return _autoComputeHomePosition; }
/** Compute the home position.*/
virtual void computeHomePosition()
{
if(getNode())
{
const osg::BoundingSphere& boundingSphere=getNode()->getBound();
setHomePosition(boundingSphere._center+osg::Vec3( 0.0,-3.5f * boundingSphere._radius,0.0f),
boundingSphere._center,
//osg::Vec3(0.0f,0.0f,1.0f),
_homeUp,
_autoComputeHomePosition);
}
}
virtual void computeHomePosition(const osg::Camera *camera = NULL, bool useBoundingBox = false);
/**
Move the camera to the default position.
@ -191,9 +165,11 @@ public:
protected:
MatrixManipulator();
MatrixManipulator(const MatrixManipulator& mm, const osg::CopyOp& copyOp = osg::CopyOp::SHALLOW_COPY);
virtual ~MatrixManipulator();
double _minimumDistance;
std::string getManipulatorName() const;
unsigned int _intersectTraversalMask;

View File

@ -11,30 +11,37 @@
* OpenSceneGraph Public License for more details.
*/
#ifndef OSGGA_NODETRACKERMANIPULATOR
#define OSGGA_NODETRACKERMANIPULATOR 1
#ifndef OSGGA_NODE_TRACKER_MANIPULATOR
#define OSGGA_NODE_TRACKER_MANIPULATOR 1
#include <osgGA/MatrixManipulator>
#include <osg/ObserverNodePath>
#include <osg/Quat>
#include <osgGA/OrbitManipulator>
namespace osgGA{
class OSGGA_EXPORT NodeTrackerManipulator : public MatrixManipulator
namespace osgGA {
class OSGGA_EXPORT NodeTrackerManipulator : public OrbitManipulator
{
typedef OrbitManipulator inherited;
public:
NodeTrackerManipulator();
NodeTrackerManipulator( int flags = DEFAULT_SETTINGS );
virtual const char* className() const { return "NodeTrackerManipulator"; }
NodeTrackerManipulator( const NodeTrackerManipulator& om,
const osg::CopyOp& copyOp = osg::CopyOp::SHALLOW_COPY );
void setTrackNodePath(const osg::NodePath& nodePath) { _trackNodePath.setNodePath(nodePath); }
void setTrackNodePath(const osg::ObserverNodePath& nodePath) { _trackNodePath = nodePath; }
osg::ObserverNodePath& getTrackNodePath() { return _trackNodePath; }
META_Object( osgGA, NodeTrackerManipulator );
typedef std::vector< osg::observer_ptr<osg::Node> > ObserverNodePath;
void setTrackNodePath(const osg::NodePath& nodePath);
void setTrackNodePath(const ObserverNodePath& nodePath) { _trackNodePath = nodePath; }
ObserverNodePath& getTrackNodePath() { return _trackNodePath; }
void setTrackNode(osg::Node* node);
osg::Node* getTrackNode();
const osg::Node* getTrackNode() const;
osg::Node* getTrackNode() { return _trackNodePath.empty() ? 0 : _trackNodePath.back().get(); }
const osg::Node* getTrackNode() const { return _trackNodePath.empty() ? 0 : _trackNodePath.back().get(); }
enum TrackerMode
{
@ -66,104 +73,41 @@ class OSGGA_EXPORT NodeTrackerManipulator : public MatrixManipulator
};
void setRotationMode(RotationMode mode);
RotationMode getRotationMode() const { return _rotationMode; }
RotationMode getRotationMode() const;
/** set the position of the matrix manipulator using a 4x4 Matrix.*/
virtual void setByMatrix(const osg::Matrixd& matrix);
/** set the position of the matrix manipulator using a 4x4 Matrix.*/
virtual void setByInverseMatrix(const osg::Matrixd& matrix) { setByMatrix(osg::Matrixd::inverse(matrix)); }
/** get the position of the manipulator as 4x4 Matrix.*/
virtual osg::Matrixd getMatrix() const;
/** get the position of the manipulator as a inverse matrix of the manipulator, typically used as a model view matrix.*/
virtual osg::Matrixd getInverseMatrix() const;
/** Get the FusionDistanceMode. Used by SceneView for setting up stereo convergence.*/
virtual osgUtil::SceneView::FusionDistanceMode getFusionDistanceMode() const { return osgUtil::SceneView::USE_FUSION_DISTANCE_VALUE; }
/** Get the FusionDistanceValue. Used by SceneView for setting up stereo convergence.*/
virtual float getFusionDistanceValue() const { return _distance; }
/** Attach a node to the manipulator.
Automatically detaches previously attached node.
setNode(NULL) detaches previously nodes.
Is ignored by manipulators which do not require a reference model.*/
virtual void setNode(osg::Node*);
/** Return node if attached.*/
virtual const osg::Node* getNode() const;
/** Return node if attached.*/
virtual osg::Node* getNode();
virtual void computeHomePosition();
/** Move the camera to the default position.
May be ignored by manipulators if home functionality is not appropriate.*/
virtual void home(const GUIEventAdapter& ea,GUIActionAdapter& us);
/** Start/restart the manipulator.*/
virtual void init(const GUIEventAdapter& ea,GUIActionAdapter& us);
/** handle events, return true if handled, false otherwise.*/
virtual bool handle(const GUIEventAdapter& ea,GUIActionAdapter& us);
/** Get the keyboard and mouse usage of this manipulator.*/
virtual void getUsage(osg::ApplicationUsage& usage) const;
protected:
virtual ~NodeTrackerManipulator();
virtual bool performMovementLeftMouseButton(const double dt, const double dx, const double dy);
virtual bool performMovementMiddleMouseButton(const double dt, const double dx, const double dy);
virtual bool performMovementRightMouseButton(const double dt, const double dx, const double dy);
/** Reset the internal GUIEvent stack.*/
void flushMouseEventStack();
osg::NodePath getNodePath() const;
/** Add the current mouse GUIEvent to internal stack.*/
void addMouseEvent(const GUIEventAdapter& ea);
bool validateNodePath() const;
void computeNodeWorldToLocal(osg::Matrixd& worldToLocal) const;
void computeNodeLocalToWorld(osg::Matrixd& localToWorld) const;
void computeNodeCenterAndRotation(osg::Vec3d& center, osg::Quat& rotation) const;
void computePosition(const osg::Vec3d& eye,const osg::Vec3d& lv,const osg::Vec3d& up);
/** For the give mouse movement calculate the movement of the camera.
Return true is camera has moved and a redraw is required.*/
bool calcMovement();
void trackball(osg::Vec3& axis,double& angle, double p1x, double p1y, double p2x, double p2y);
double tb_project_to_sphere(double r, double x, double y);
/** Check the speed at which the mouse is moving.
If speed is below a threshold then return false, otherwise return true.*/
bool isMouseMoving();
void clampOrientation();
// Internal event stack comprising last two mouse events.
osg::ref_ptr<const GUIEventAdapter> _ga_t1;
osg::ref_ptr<const GUIEventAdapter> _ga_t0;
osg::observer_ptr<osg::Node> _node;
osg::ObserverNodePath _trackNodePath;
ObserverNodePath _trackNodePath;
TrackerMode _trackerMode;
RotationMode _rotationMode;
bool _thrown;
osg::Quat _nodeRotation;
osg::Quat _rotation;
float _distance;
};
}
#endif
#endif /* OSGGA_NODE_TRACKER_MANIPULATOR */

View File

@ -0,0 +1,116 @@
/* -*-c++-*- OpenSceneGraph - Copyright (C) 1998-2006 Robert Osfield
*
* This library is open source and may be redistributed and/or modified under
* the terms of the OpenSceneGraph Public License (OSGPL) version 0.0 or
* (at your option) any later version. The full license is in LICENSE file
* included with this distribution, and on the openscenegraph.org website.
*
* This library 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
* OpenSceneGraph Public License for more details.
*/
#ifndef OSGGA_ORBIT_MANIPULATOR
#define OSGGA_ORBIT_MANIPULATOR 1
#include <osgGA/StandardManipulator>
namespace osgGA {
/** OrbitManipulator is base class for camera control based on focal center,
distance from the center, and orientation of distance vector to the eye.
This is the base class for trackball style manipulators.*/
class OSGGA_EXPORT OrbitManipulator : public StandardManipulator
{
typedef StandardManipulator inherited;
public:
OrbitManipulator( int flags = DEFAULT_SETTINGS );
OrbitManipulator( const OrbitManipulator& om,
const osg::CopyOp& copyOp = osg::CopyOp::SHALLOW_COPY );
META_Object( osgGA, OrbitManipulator );
virtual void setByMatrix( const osg::Matrixd& matrix );
virtual void setByInverseMatrix( const osg::Matrixd& matrix );
virtual osg::Matrixd getMatrix() const;
virtual osg::Matrixd getInverseMatrix() const;
virtual void setTransformation( const osg::Vec3d& eye, const osg::Quat& rotation );
virtual void setTransformation( const osg::Vec3d& center, const osg::Vec3d& eye, const osg::Vec3d& up );
virtual void getTransformation( osg::Vec3d& eye, osg::Quat& rotation ) const;
virtual void getTransformation( osg::Vec3d& center, osg::Vec3d& eye, osg::Vec3d& up ) const;
virtual void setCenter( const osg::Vec3d& center );
const osg::Vec3d& getCenter() const;
virtual void setRotation( const osg::Quat& rotation );
const osg::Quat& getRotation() const;
virtual void setDistance( double distance );
double getDistance() const;
virtual void setTrackballSize( const double& size );
inline double getTrackballSize() const;
virtual void setWheelZoomFactor( double wheelZoomFactor );
inline double getWheelZoomFactor() const;
virtual void setMinimumDistance( const double& minimumDistance, bool relativeToModelSize = NULL );
double getMinimumDistance( bool *relativeToModelSize = NULL ) const;
virtual osgUtil::SceneView::FusionDistanceMode getFusionDistanceMode() const;
virtual float getFusionDistanceValue() const;
protected:
virtual bool handleMouseWheel( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool performMovementLeftMouseButton( const double dt, const double dx, const double dy );
virtual bool performMovementMiddleMouseButton( const double dt, const double dx, const double dy );
virtual bool performMovementRightMouseButton( const double dt, const double dx, const double dy );
virtual bool performMouseDeltaMovement( const float dx, const float dy );
virtual void applyAnimationStep( const double currentProgress, const double prevProgress );
virtual void rotateTrackball( const float px0, const float py0, const float px1, const float py1 );
virtual void rotateWithFixedVertical( const float dx, const float dy );
virtual void rotateWithFixedVertical( const float dx, const float dy, const osg::Vec3f& up );
virtual void panModel( const float dx, const float dy, const float dz = 0.f );
virtual void zoomModel( const float dy, bool pushForwardIfNeeded = true );
void trackball( osg::Vec3d& axis, float& angle, float p1x, float p1y, float p2x, float p2y );
float tb_project_to_sphere( float r, float x, float y );
virtual bool startAnimationByMousePointerIntersection( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
osg::Vec3d _center;
osg::Quat _rotation;
double _distance;
double _trackballSize;
double _wheelZoomFactor;
double _minimumDistance;
static int _minimumDistanceFlagIndex;
class OrbitAnimationData : public AnimationData {
public:
osg::Vec3d _movement;
void start( const osg::Vec3d& movement, const double startTime );
};
virtual void allocAnimationData() { _animationData = new OrbitAnimationData(); }
};
//
// inline functions
//
/** Get the size of the trackball relative to the model size. */
inline double OrbitManipulator::getTrackballSize() const { return _trackballSize; }
/** Get the mouse wheel zoom factor.*/
inline double OrbitManipulator::getWheelZoomFactor() const { return _wheelZoomFactor; }
}
#endif /* OSGGA_ORBIT_MANIPULATOR */

View File

@ -0,0 +1,186 @@
/* -*-c++-*- OpenSceneGraph - Copyright (C) 1998-2006 Robert Osfield
*
* This library is open source and may be redistributed and/or modified under
* the terms of the OpenSceneGraph Public License (OSGPL) version 0.0 or
* (at your option) any later version. The full license is in LICENSE file
* included with this distribution, and on the openscenegraph.org website.
*
* This library 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
* OpenSceneGraph Public License for more details.
*
* StandardManipulator code Copyright (C) 2010 PCJohn (Jan Peciva)
* while some pieces of code were reused from OSG.
* Thanks to company Cadwork (www.cadwork.ch) and
* Brno University of Technology (www.fit.vutbr.cz) for open-sourcing this work.
*/
#ifndef OSGGA_CAMERA_MANIPULATOR
#define OSGGA_CAMERA_MANIPULATOR 1
#include <osgGA/MatrixManipulator>
namespace osgGA {
/** StandardManipulator class provides basic functionality
for user controlled manipulation.*/
class OSGGA_EXPORT StandardManipulator : public MatrixManipulator
{
typedef MatrixManipulator inherited;
public:
// flags
enum {
UPDATE_MODEL_SIZE = 0x01,
COMPUTE_HOME_USING_BBOX = 0x02,
PROCESS_MOUSE_WHEEL = 0x04,
SET_CENTER_ON_WHEEL_UP = 0x08,
DEFAULT_SETTINGS = UPDATE_MODEL_SIZE | COMPUTE_HOME_USING_BBOX | PROCESS_MOUSE_WHEEL
};
StandardManipulator( int flags = DEFAULT_SETTINGS );
StandardManipulator( const StandardManipulator& m,
const osg::CopyOp& copyOp = osg::CopyOp::SHALLOW_COPY );
// We are not using META_Object as this is abstract class.
// Use META_Object(osgGA,YourManipulator); in your descendant non-abstract classes.
virtual const char* className() const { return "StandardManipulator"; }
virtual void setTransformation( const osg::Vec3d& eye, const osg::Quat& rotation ) = 0;
virtual void setTransformation( const osg::Vec3d& center, const osg::Vec3d& eye, const osg::Vec3d& up ) = 0;
virtual void getTransformation( osg::Vec3d& eye, osg::Quat& rotation ) const = 0;
virtual void getTransformation( osg::Vec3d& center, osg::Vec3d& eye, osg::Vec3d& up ) const = 0;
virtual void setNode( osg::Node* );
virtual const osg::Node* getNode() const;
virtual osg::Node* getNode();
virtual void setVerticalAxisFixed( bool value );
inline bool getVerticalAxisFixed() const;
virtual void setAnimationTime( const double t );
double getAnimationTime() const;
bool isAnimating() const;
virtual void finishAnimation();
virtual void home( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual void home( double );
virtual void init( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handle( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual void getUsage( osg::ApplicationUsage& usage ) const;
protected:
virtual bool handleFrame( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleResize( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleMouseMove( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleMouseDrag( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleMousePush( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleMouseRelease( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleKeyDown( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleKeyUp( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleMouseWheel( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool handleMouseDeltaMovement( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool performMovement();
virtual bool performMovementLeftMouseButton( const double dt, const double dx, const double dy );
virtual bool performMovementMiddleMouseButton( const double dt, const double dx, const double dy );
virtual bool performMovementRightMouseButton( const double dt, const double dx, const double dy );
virtual bool performMouseDeltaMovement( const float dx, const float dy );
virtual bool performAnimationMovement( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual void applyAnimationStep( const double currentProgress, const double prevProgress );
void addMouseEvent( const osgGA::GUIEventAdapter& ea );
void flushMouseEventStack();
virtual bool isMouseMoving() const;
virtual void centerMousePointer( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
static void rotateYawPitch( osg::Quat& rotation, const double yaw, const double pitch,
const osg::Vec3d& localUp = osg::Vec3d( 0.,0.,0.) );
static void fixVerticalAxis( osg::Quat& rotation, const osg::Vec3d& localUp, bool disallowFlipOver );
void fixVerticalAxis( osg::Vec3d& eye, osg::Quat& rotation, bool disallowFlipOver );
static void fixVerticalAxis( const osg::Vec3d& forward, const osg::Vec3d& up, osg::Vec3d& newUp,
const osg::Vec3d& localUp, bool disallowFlipOver );
virtual bool setCenterByMousePointerIntersection( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
virtual bool startAnimationByMousePointerIntersection( const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us );
// mouse state
bool _thrown;
float _mouseCenterX, _mouseCenterY;
// internal event stack comprising last two mouse events.
osg::ref_ptr< const osgGA::GUIEventAdapter > _ga_t1;
osg::ref_ptr< const osgGA::GUIEventAdapter > _ga_t0;
/** The approximate amount of time it is currently taking to draw a frame.
* This is used to compute the delta in translation/rotation during a thrown display update.
* It allows us to match an delta in position/rotation independent of the rendering frame rate.
*/
double _delta_frame_time;
/** The time the last frame started.
* Used when _rate_sensitive is true so that we can match display update rate to rotation/translation rate.
*/
double _last_frame_time;
// scene data
osg::ref_ptr< osg::Node > _node;
double _modelSize;
bool _verticalAxisFixed;
// animation stuff
class AnimationData : public osg::Referenced {
public:
double _animationTime;
bool _isAnimating;
double _startTime;
double _phase;
AnimationData();
void start( const double startTime );
};
osg::ref_ptr< AnimationData > _animationData;
virtual void allocAnimationData() { _animationData = new AnimationData(); }
// flags
int _flags;
// flags indicating that a value is relative to model size
int _relativeFlags;
inline bool getRelativeFlag( int index ) const;
inline void setRelativeFlag( int index, bool value );
static int numRelativeFlagsAllocated;
static int allocateRelativeFlag();
};
//
// inline methods
//
inline bool StandardManipulator::getRelativeFlag( int index ) const
{
return ( _relativeFlags & (0x01 << index) ) != 0;
}
inline void StandardManipulator::setRelativeFlag( int index, bool value )
{
if( value ) _relativeFlags |= (0x01 << index);
else _relativeFlags &= (~0x01 << index);
}
/// Returns whether manipulator preserves camera's "UP" vector.
inline bool StandardManipulator::getVerticalAxisFixed() const
{
return _verticalAxisFixed;
}
}
#endif /* OSGGA_CAMERA_MANIPULATOR */

View File

@ -11,130 +11,54 @@
* OpenSceneGraph Public License for more details.
*/
#ifndef OSGGA_TERRAINMANIPULATOR
#define OSGGA_TERRAINMANIPULATOR 1
#ifndef OSGGA_TERRAIN_MANIPULATOR
#define OSGGA_TERRAIN_MANIPULATOR 1
#include <osgGA/MatrixManipulator>
#include <osg/Quat>
#include <osgGA/OrbitManipulator>
namespace osgGA{
class OSGGA_EXPORT TerrainManipulator : public MatrixManipulator
namespace osgGA {
class OSGGA_EXPORT TerrainManipulator : public OrbitManipulator
{
public:
typedef OrbitManipulator inherited;
TerrainManipulator();
public:
virtual const char* className() const { return "Terrain"; }
TerrainManipulator( int flags = DEFAULT_SETTINGS );
TerrainManipulator( const TerrainManipulator& tm,
const osg::CopyOp& copyOp = osg::CopyOp::SHALLOW_COPY );
META_Object( osgGA, TerrainManipulator );
enum RotationMode
{
ELEVATION_HEADING_ROLL,
ELEVATION_HEADING
};
enum RotationMode
{
ELEVATION_AZIM_ROLL,
ELEVATION_AZIM
};
void setRotationMode(RotationMode mode);
RotationMode getRotationMode() const { return _rotationMode; }
virtual void setRotationMode(RotationMode mode);
RotationMode getRotationMode() const;
virtual void setByMatrix( const osg::Matrixd& matrix );
/** set the position of the matrix manipulator using a 4x4 Matrix.*/
virtual void setByMatrix(const osg::Matrixd& matrix);
virtual void setTransformation( const osg::Vec3d& eye, const osg::Vec3d& center, const osg::Vec3d& up );
/** set the position of the matrix manipulator using a 4x4 Matrix.*/
virtual void setByInverseMatrix(const osg::Matrixd& matrix) { setByMatrix(osg::Matrixd::inverse(matrix)); }
virtual void setNode( osg::Node* node );
/** get the position of the manipulator as 4x4 Matrix.*/
virtual osg::Matrixd getMatrix() const;
protected:
/** get the position of the manipulator as a inverse matrix of the manipulator, typically used as a model view matrix.*/
virtual osg::Matrixd getInverseMatrix() const;
virtual bool performMovementMiddleMouseButton( const double dt, const double dx, const double dy );
virtual bool performMovementRightMouseButton( const double dt, const double dx, const double dy );
/** Get the FusionDistanceMode. Used by SceneView for setting up stereo convergence.*/
virtual osgUtil::SceneView::FusionDistanceMode getFusionDistanceMode() const { return osgUtil::SceneView::USE_FUSION_DISTANCE_VALUE; }
/** Get the FusionDistanceValue. Used by SceneView for setting up stereo convergence.*/
virtual float getFusionDistanceValue() const { return _distance; }
/** Set the distance of the trackball. */
void setDistance(double distance) { _distance = distance; }
/** Get the distance of the trackball. */
double getDistance() const { return _distance; }
/** Attach a node to the manipulator.
Automatically detaches previously attached node.
setNode(NULL) detaches previously nodes.
Is ignored by manipulators which do not require a reference model.*/
virtual void setNode(osg::Node*);
/** Return node if attached.*/
virtual const osg::Node* getNode() const;
/** Return node if attached.*/
virtual osg::Node* getNode();
/** Move the camera to the default position.
May be ignored by manipulators if home functionality is not appropriate.*/
virtual void home(const GUIEventAdapter& ea,GUIActionAdapter& us);
/** Start/restart the manipulator.*/
virtual void init(const GUIEventAdapter& ea,GUIActionAdapter& us);
/** handle events, return true if handled, false otherwise.*/
virtual bool handle(const GUIEventAdapter& ea,GUIActionAdapter& us);
/** Get the keyboard and mouse usage of this manipulator.*/
virtual void getUsage(osg::ApplicationUsage& usage) const;
protected:
virtual ~TerrainManipulator();
bool intersect(const osg::Vec3d& start, const osg::Vec3d& end, osg::Vec3d& intersection) const;
/** Reset the internal GUIEvent stack.*/
void flushMouseEventStack();
/** Add the current mouse GUIEvent to internal stack.*/
void addMouseEvent(const GUIEventAdapter& ea);
void computePosition(const osg::Vec3d& eye,const osg::Vec3d& lv,const osg::Vec3d& up);
/** For the give mouse movement calculate the movement of the camera.
Return true is camera has moved and a redraw is required.*/
bool calcMovement();
void trackball(osg::Vec3& axis,double& angle, double p1x, double p1y, double p2x, double p2y);
double tb_project_to_sphere(double r, double x, double y);
/** Check the speed at which the mouse is moving.
If speed is below a threshold then return false, otherwise return true.*/
bool isMouseMoving();
void clampOrientation();
// Internal event stack comprising last two mouse events.
osg::ref_ptr<const GUIEventAdapter> _ga_t1;
osg::ref_ptr<const GUIEventAdapter> _ga_t0;
osg::observer_ptr<osg::Node> _node;
RotationMode _rotationMode;
bool _thrown;
osg::Vec3d _center;
osg::Quat _rotation;
double _distance;
osg::Vec3d _previousUp;
bool intersect( const osg::Vec3d& start, const osg::Vec3d& end, osg::Vec3d& intersection ) const;
void clampOrientation();
osg::Vec3d _previousUp;
};
}
#endif
#endif /* OSGGA_TERRAIN_MANIPULATOR */

View File

@ -11,164 +11,30 @@
* OpenSceneGraph Public License for more details.
*/
#ifndef OSGGA_TRACKBALLMANIPULATOR
#define OSGGA_TRACKBALLMANIPULATOR 1
#ifndef OSGGA_TRACKBALL_MANIPULATOR
#define OSGGA_TRACKBALL_MANIPULATOR 1
#include <osgGA/MatrixManipulator>
#include <osg/Quat>
#include <osgGA/OrbitManipulator>
namespace osgGA{
class OSGGA_EXPORT TrackballManipulator : public MatrixManipulator
namespace osgGA {
class OSGGA_EXPORT TrackballManipulator : public OrbitManipulator
{
public:
TrackballManipulator();
typedef OrbitManipulator inherited;
virtual const char* className() const { return "Trackball"; }
public:
/** set the position of the matrix manipulator using a 4x4 Matrix.*/
virtual void setByMatrix(const osg::Matrixd& matrix);
TrackballManipulator( int flags = DEFAULT_SETTINGS );
TrackballManipulator( const TrackballManipulator& tm,
const osg::CopyOp& copyOp = osg::CopyOp::SHALLOW_COPY );
/** set the position of the matrix manipulator using a 4x4 Matrix.*/
virtual void setByInverseMatrix(const osg::Matrixd& matrix) { setByMatrix(osg::Matrixd::inverse(matrix)); }
/** get the position of the manipulator as 4x4 Matrix.*/
virtual osg::Matrixd getMatrix() const;
/** get the position of the manipulator as a inverse matrix of the manipulator, typically used as a model view matrix.*/
virtual osg::Matrixd getInverseMatrix() const;
/** Get the FusionDistanceMode. Used by SceneView for setting up stereo convergence.*/
virtual osgUtil::SceneView::FusionDistanceMode getFusionDistanceMode() const { return osgUtil::SceneView::USE_FUSION_DISTANCE_VALUE; }
/** Get the FusionDistanceValue. Used by SceneView for setting up stereo convergence.*/
virtual float getFusionDistanceValue() const { return _distance; }
/** Attach a node to the manipulator.
Automatically detaches previously attached node.
setNode(NULL) detaches previously nodes.
Is ignored by manipulators which do not require a reference model.*/
virtual void setNode(osg::Node*);
/** Return node if attached.*/
virtual const osg::Node* getNode() const;
/** Return node if attached.*/
virtual osg::Node* getNode();
/** Move the camera to the default position.
May be ignored by manipulators if home functionality is not appropriate.*/
virtual void home(const GUIEventAdapter& ea,GUIActionAdapter& us);
virtual void home(double);
/** Start/restart the manipulator.*/
virtual void init(const GUIEventAdapter& ea,GUIActionAdapter& us);
/** handle events, return true if handled, false otherwise.*/
virtual bool handle(const GUIEventAdapter& ea,GUIActionAdapter& us);
/** Get the keyboard and mouse usage of this manipulator.*/
virtual void getUsage(osg::ApplicationUsage& usage) const;
/** set the minimum distance (as ratio) the eye point can be zoomed in towards the
center before the center is pushed forward.*/
void setMinimumZoomScale(double minimumZoomScale) { _minimumZoomScale=minimumZoomScale; }
/** get the minimum distance (as ratio) the eye point can be zoomed in */
double getMinimumZoomScale() const { return _minimumZoomScale; }
/** set the mouse scroll wheel zoom delta.
* Range -1.0 to +1.0, -ve value inverts wheel direction and zero switches off scroll wheel. */
void setScroolWheelZoomDelta(double zoomDelta) { _zoomDelta = zoomDelta; }
/** get the mouse scroll wheel zoom delta. */
double getScroolWheelZoomDelta() const { return _zoomDelta; }
/** Set the center of the trackball. */
void setCenter(const osg::Vec3d& center) { _center = center; }
/** Get the center of the trackball. */
const osg::Vec3d& getCenter() const { return _center; }
/** Set the rotation of the trackball. */
void setRotation(const osg::Quat& rotation) { _rotation = rotation; }
/** Get the rotation of the trackball. */
const osg::Quat& getRotation() const { return _rotation; }
/** Set the distance of the trackball. */
void setDistance(double distance) { _distance = distance; }
/** Get the distance of the trackball. */
double getDistance() const { return _distance; }
/** Set the size of the trackball. */
void setTrackballSize(float size);
/** Get the size of the trackball. */
float getTrackballSize() const { return _trackballSize; }
/** Set the 'allow throw' flag. Releasing the mouse button while moving the camera results in a throw. */
void setAllowThrow(bool allowThrow) { _allowThrow = allowThrow; }
/** Returns true if the camera can be thrown, false otherwise. This defaults to true. */
bool getAllowThrow() const { return _allowThrow; }
protected:
virtual ~TrackballManipulator();
/** Reset the internal GUIEvent stack.*/
void flushMouseEventStack();
/** Add the current mouse GUIEvent to internal stack.*/
void addMouseEvent(const GUIEventAdapter& ea);
void computePosition(const osg::Vec3& eye,const osg::Vec3& lv,const osg::Vec3& up);
/** For the give mouse movement calculate the movement of the camera.
Return true is camera has moved and a redraw is required.*/
bool calcMovement();
void trackball(osg::Vec3& axis,float& angle, float p1x, float p1y, float p2x, float p2y);
float tb_project_to_sphere(float r, float x, float y);
/** Check the speed at which the mouse is moving.
If speed is below a threshold then return false, otherwise return true.*/
bool isMouseMoving();
// Internal event stack comprising last two mouse events.
osg::ref_ptr<const GUIEventAdapter> _ga_t1;
osg::ref_ptr<const GUIEventAdapter> _ga_t0;
osg::observer_ptr<osg::Node> _node;
double _modelScale;
double _minimumZoomScale;
bool _allowThrow;
bool _thrown;
/** The approximate amount of time it is currently taking to draw a frame.
* This is used to compute the delta in translation/rotation during a thrown display update.
* It allows us to match an delta in position/rotation independent of the rendering frame rate.
*/
double _delta_frame_time;
/** The time the last frame started.
* Used when _rate_sensitive is true so that we can match display update rate to rotation/translation rate.
*/
double _last_frame_time;
osg::Vec3d _center;
osg::Quat _rotation;
double _distance;
float _trackballSize;
float _zoomDelta;
META_Object( osgGA, TrackballManipulator );
};
}
#endif
#endif /* OSGGA_TRACKBALL_MANIPULATOR */

View File

@ -109,7 +109,7 @@ class OSGGA_EXPORT UFOManipulator : public osgGA::MatrixManipulator
void getUsage(osg::ApplicationUsage& usage) const;
/** Report the current position as LookAt vectors */
void getCurrentPositionAsLookAt( osg::Vec3 &eye, osg::Vec3 &center, osg::Vec3 &up );
void getCurrentPositionAsLookAt( osg::Vec3d& eye, osg::Vec3d& center, osg::Vec3d& up );
void setMinHeight( double in_min_height ) { _minHeightAboveGround = in_min_height; }

View File

@ -103,7 +103,7 @@ bool ObserverNodePath::getRefNodePath(RefNodePath& refNodePath) const
refNodePath[i] = _nodePath[i].lock();
if (!refNodePath[i].valid())
{
OSG_NOTICE<<"ObserverNodePath::getRefNodePath() node has been invalidated"<<std::endl;
OSG_INFO<<"ObserverNodePath::getRefNodePath() node has been invalidated"<<std::endl;
refNodePath.clear();
return false;
}

View File

@ -1,9 +1,9 @@
IF(DYNAMIC_OPENSCENEGRAPH)
IF (DYNAMIC_OPENSCENEGRAPH)
ADD_DEFINITIONS(-DOSGGA_LIBRARY)
ELSE()
ELSE (DYNAMIC_OPENSCENEGRAPH)
ADD_DEFINITIONS(-DOSG_LIBRARY_STATIC)
ENDIF()
ENDIF(DYNAMIC_OPENSCENEGRAPH)
SET(LIB_NAME osgGA)
SET(HEADER_PATH ${OpenSceneGraph_SOURCE_DIR}/include/${LIB_NAME})
@ -13,6 +13,7 @@ SET(LIB_PUBLIC_HEADERS
${HEADER_PATH}/EventQueue
${HEADER_PATH}/EventVisitor
${HEADER_PATH}/Export
${HEADER_PATH}/FirstPersonManipulator
${HEADER_PATH}/FlightManipulator
${HEADER_PATH}/GUIActionAdapter
${HEADER_PATH}/GUIEventAdapter
@ -20,10 +21,12 @@ SET(LIB_PUBLIC_HEADERS
${HEADER_PATH}/KeySwitchMatrixManipulator
${HEADER_PATH}/MatrixManipulator
${HEADER_PATH}/NodeTrackerManipulator
${HEADER_PATH}/OrbitManipulator
${HEADER_PATH}/StandardManipulator
${HEADER_PATH}/SphericalManipulator
${HEADER_PATH}/StateSetManipulator
${HEADER_PATH}/TerrainManipulator
${HEADER_PATH}/TrackballManipulator
${HEADER_PATH}/SphericalManipulator
${HEADER_PATH}/UFOManipulator
${HEADER_PATH}/Version
${HEADER_PATH}/CameraViewSwitchManipulator
@ -37,20 +40,22 @@ ADD_LIBRARY(${LIB_NAME}
DriveManipulator.cpp
EventQueue.cpp
EventVisitor.cpp
FirstPersonManipulator.cpp
FlightManipulator.cpp
GUIEventAdapter.cpp
GUIEventHandler.cpp
KeySwitchMatrixManipulator.cpp
MatrixManipulator.cpp
NodeTrackerManipulator.cpp
OrbitManipulator.cpp
StandardManipulator.cpp
SphericalManipulator.cpp
StateSetManipulator.cpp
TerrainManipulator.cpp
TrackballManipulator.cpp
SphericalManipulator.cpp
UFOManipulator.cpp
Version.cpp
CameraViewSwitchManipulator.cpp
${OPENSCENEGRAPH_VERSIONINFO_RC}
)
LINK_INTERNAL(${LIB_NAME}

View File

@ -137,7 +137,7 @@ void DriveManipulator::computeHomePosition()
ep = ip;
ep += getUpVector(cf)*_height;
osg::Vec3 lv = uv^osg::Vec3d(1.0,0.0,0.0);
osg::Vec3d lv = uv^osg::Vec3d(1.0,0.0,0.0);
setHomePosition(ep,ep+lv,uv);
@ -160,7 +160,7 @@ void DriveManipulator::computeHomePosition()
ep = ip;
ep += getUpVector(cf)*_height;
osg::Vec3 lv = uv^osg::Vec3d(1.0,0.0,0.0);
osg::Vec3d lv = uv^osg::Vec3d(1.0,0.0,0.0);
setHomePosition(ep,ep+lv,uv);
positionSet = true;
@ -245,7 +245,7 @@ void DriveManipulator::init(const GUIEventAdapter& ea,GUIActionAdapter& us)
else uv = -np;
ep = ip+uv*_height;
osg::Vec3 lv = uv^sv;
osg::Vec3d lv = uv^sv;
computePosition(ep,ep+lv,uv);

View File

@ -0,0 +1,388 @@
/* -*-c++-*- OpenSceneGraph - Copyright (C) 1998-2006 Robert Osfield
*
* This library is open source and may be redistributed and/or modified under
* the terms of the OpenSceneGraph Public License (OSGPL) version 0.0 or
* (at your option) any later version. The full license is in LICENSE file
* included with this distribution, and on the openscenegraph.org website.
*
* This library 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
* OpenSceneGraph Public License for more details.
*
* FirstPersonManipulator code Copyright (C) 2010 PCJohn (Jan Peciva)
* while some pieces of code were reused from OSG.
* Thanks to company Cadwork (www.cadwork.ch) and
* Brno University of Technology (www.fit.vutbr.cz) for open-sourcing this work.
*/
#include <osgGA/FirstPersonManipulator>
#include <cassert>
using namespace osg;
using namespace osgGA;
int FirstPersonManipulator::_accelerationFlagIndex = allocateRelativeFlag();
int FirstPersonManipulator::_maxVelocityFlagIndex = allocateRelativeFlag();
int FirstPersonManipulator::_wheelMovementFlagIndex = allocateRelativeFlag();
/// Constructor.
FirstPersonManipulator::FirstPersonManipulator( int flags )
: inherited( flags ),
_velocity( 0. )
{
setAcceleration( 0.25, true );
setMaxVelocity( 0.25, true );
setWheelMovement( 0.05, true );
if( _flags & SET_CENTER_ON_WHEEL_UP )
setAnimationTime( 0.2 );
}
/// Constructor.
FirstPersonManipulator::FirstPersonManipulator( const FirstPersonManipulator& fpm, const CopyOp& copyOp )
: inherited( fpm, copyOp ),
_eye( fpm._eye ),
_rotation( fpm._rotation ),
_velocity( fpm._velocity ),
_acceleration( fpm._acceleration ),
_maxVelocity( fpm._maxVelocity ),
_wheelMovement( fpm._wheelMovement )
{
}
/** Set the position of the manipulator using a 4x4 matrix.*/
void FirstPersonManipulator::setByMatrix( const Matrixd& matrix )
{
// set variables
_eye = matrix.getTrans();
_rotation = matrix.getRotate();
// fix current rotation
if( getVerticalAxisFixed() )
fixVerticalAxis( _eye, _rotation, true );
}
/** Set the position of the manipulator using a 4x4 matrix.*/
void FirstPersonManipulator::setByInverseMatrix( const Matrixd& matrix )
{
setByMatrix( Matrixd::inverse( matrix ) );
}
/** Get the position of the manipulator as 4x4 matrix.*/
Matrixd FirstPersonManipulator::getMatrix() const
{
return Matrixd::rotate( _rotation ) * Matrixd::translate( _eye );
}
/** Get the position of the manipulator as a inverse matrix of the manipulator,
typically used as a model view matrix.*/
Matrixd FirstPersonManipulator::getInverseMatrix() const
{
return Matrixd::translate( -_eye ) * Matrixd::rotate( _rotation.inverse() );
}
// doc in parent
void FirstPersonManipulator::setTransformation( const osg::Vec3d& eye, const osg::Quat& rotation )
{
// set variables
_eye = eye;
_rotation = rotation;
// fix current rotation
if( getVerticalAxisFixed() )
fixVerticalAxis( _eye, _rotation, true );
}
// doc in parent
void FirstPersonManipulator::getTransformation( osg::Vec3d& eye, osg::Quat& rotation ) const
{
eye = _eye;
rotation = _rotation;
}
// doc in parent
void FirstPersonManipulator::setTransformation( const osg::Vec3d& center, const osg::Vec3d& eye, const osg::Vec3d& up )
{
// set variables
osg::Matrixd m( osg::Matrixd::lookAt( eye, center, up ) );
_eye = eye;
_rotation = m.getRotate().inverse();
// fix current rotation
if( getVerticalAxisFixed() )
fixVerticalAxis( _eye, _rotation, true );
}
// doc in parent
void FirstPersonManipulator::getTransformation( osg::Vec3d& center, osg::Vec3d& eye, osg::Vec3d& up ) const
{
center = _eye + _rotation * osg::Vec3d( 0.,0.,-1. );
eye = _eye;
up = _rotation * osg::Vec3d( 0.,1.,0. );
}
/** Sets velocity.
*
* There are no checks for maximum velocity applied.
*/
void FirstPersonManipulator::setVelocity( const double& velocity )
{
_velocity = velocity;
}
/** Sets acceleration.
*
* If acceleration effect is unwanted, it can be set to DBL_MAX.
* Then, there will be no acceleration and object will reach its
* maximum velocity immediately.
*/
void FirstPersonManipulator::setAcceleration( const double& acceleration, bool relativeToModelSize )
{
_acceleration = acceleration;
setRelativeFlag( _accelerationFlagIndex, relativeToModelSize );
}
/// Returns acceleration speed.
double FirstPersonManipulator::getAcceleration( bool *relativeToModelSize ) const
{
if( relativeToModelSize )
*relativeToModelSize = getRelativeFlag( _accelerationFlagIndex );
return _acceleration;
}
/** Sets maximum velocity.
*
* If acceleration is set to DBL_MAX, there is no speeding up.
* Instead, maximum velocity is used for velocity at once without acceleration.
*/
void FirstPersonManipulator::setMaxVelocity( const double& maxVelocity, bool relativeToModelSize )
{
_maxVelocity = maxVelocity;
setRelativeFlag( _maxVelocityFlagIndex, relativeToModelSize );
}
/// Returns maximum velocity.
double FirstPersonManipulator::getMaxVelocity( bool *relativeToModelSize ) const
{
if( relativeToModelSize )
*relativeToModelSize = getRelativeFlag( _maxVelocityFlagIndex );
return _maxVelocity;
}
/// Sets movement size on single wheel step.
void FirstPersonManipulator::setWheelMovement( const double& wheelMovement, bool relativeToModelSize )
{
_wheelMovement = wheelMovement;
setRelativeFlag( _wheelMovementFlagIndex, relativeToModelSize );
}
/// Returns movement size on single wheel step.
double FirstPersonManipulator::getWheelMovement( bool *relativeToModelSize ) const
{
if( relativeToModelSize )
*relativeToModelSize = getRelativeFlag( _wheelMovementFlagIndex );
return _wheelMovement;
}
void FirstPersonManipulator::home( double currentTime )
{
inherited::home( currentTime );
_velocity = 0.;
}
void FirstPersonManipulator::home( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
inherited::home( ea, us );
_velocity = 0.;
}
void FirstPersonManipulator::init( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
inherited::init( ea, us );
// stop movement
_velocity = 0.;
}
// doc in parent
bool FirstPersonManipulator::handleMouseWheel( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
switch( ea.getScrollingMotion() ) {
// mouse scroll up event
case GUIEventAdapter::SCROLL_UP: {
if( _flags & SET_CENTER_ON_WHEEL_UP ) {
// stop thrown animation
_thrown = false;
if( getAnimationTime() <= 0. )
// center by mouse intersection (no animation)
setCenterByMousePointerIntersection( ea, us );
else {
// start new animation only if there is no animation in progress
if( !isAnimating() )
startAnimationByMousePointerIntersection( ea, us );
}
}
// move forward
moveForward( isAnimating() ? dynamic_cast< FirstPersonAnimationData* >( _animationData.get() )->_targetRot : _rotation,
_wheelMovement * (getRelativeFlag( _wheelMovementFlagIndex ) ? _modelSize : 1. ));
us.requestRedraw();
us.requestContinuousUpdate( isAnimating() || _thrown );
return true;
}
// mouse scroll down event
case GUIEventAdapter::SCROLL_DOWN:
moveForward( -_wheelMovement * (getRelativeFlag( _wheelMovementFlagIndex ) ? _modelSize : 1. ));
_thrown = false;
us.requestRedraw();
us.requestContinuousUpdate( isAnimating() || _thrown );
return true;
// unhandled mouse scrolling motion
default:
return false;
}
}
// doc in parent
bool FirstPersonManipulator::performMovementLeftMouseButton( const double dt, const double dx, const double dy )
{
// world up vector
CoordinateFrame coordinateFrame = getCoordinateFrame( _eye );
Vec3d localUp = getUpVector( coordinateFrame );
rotateYawPitch( _rotation, dx, dy, localUp );
return true;
}
bool FirstPersonManipulator::performMouseDeltaMovement( const float dx, const float dy )
{
// rotate camera
if( getVerticalAxisFixed() ) {
// world up vector
CoordinateFrame coordinateFrame = getCoordinateFrame( _eye );
Vec3d localUp = getUpVector( coordinateFrame );
rotateYawPitch( _rotation, dx, dy, localUp );
} else
rotateYawPitch( _rotation, dx, dy );
return true;
}
/// Move camera forward by distance parameter.
void FirstPersonManipulator::moveForward( const double distance )
{
moveForward( _rotation, distance );
}
/// Move camera forward by distance parameter.
void FirstPersonManipulator::moveForward( const Quat& rotation, const double distance )
{
_eye += rotation * Vec3d( 0., 0., -distance );
}
/// Move camera right by distance parameter.
void FirstPersonManipulator::moveRight( const double distance )
{
assert( 0 && "Not implemented yet." );
}
/// Move camera up by distance parameter.
void FirstPersonManipulator::moveUp( const double distance )
{
assert( 0 && "Not implemented yet." );
}
void FirstPersonManipulator::applyAnimationStep( const double currentProgress, const double prevProgress )
{
FirstPersonAnimationData *ad = dynamic_cast< FirstPersonAnimationData* >( _animationData.get() );
assert( ad );
// compute new rotation
_rotation.slerp( currentProgress, ad->_startRot, ad->_targetRot );
// fix vertical axis
if( getVerticalAxisFixed() )
fixVerticalAxis( _eye, _rotation, false );
}
// doc in parent
bool FirstPersonManipulator::startAnimationByMousePointerIntersection(
const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us )
{
// get current transformation
osg::Vec3d prevEye;
osg::Quat prevRot;
getTransformation( prevEye, prevRot );
// center by mouse intersection
if( !setCenterByMousePointerIntersection( ea, us ) )
return false;
FirstPersonAnimationData *ad = dynamic_cast< FirstPersonAnimationData*>( _animationData.get() );
assert( ad );
// setup animation data and restore original transformation
ad->start( prevRot, _rotation, ea.getTime() );
setTransformation( _eye, prevRot );
return true;
}
void FirstPersonManipulator::FirstPersonAnimationData::start( const Quat& startRotation, const Quat& targetRotation,
const double startTime )
{
AnimationData::start( startTime );
_startRot = startRotation;
_targetRot = targetRotation;
}

View File

@ -12,230 +12,134 @@
*/
#include <osgGA/FlightManipulator>
#include <osg/Notify>
using namespace osg;
using namespace osgGA;
FlightManipulator::FlightManipulator()
{
_modelScale = 0.01f;
_acceleration = 100.0f;
_velocity = 0.0f;
_yawMode = YAW_AUTOMATICALLY_WHEN_BANKED;
_distance = 1.0f;
}
FlightManipulator::~FlightManipulator()
/// Constructor.
FlightManipulator::FlightManipulator( int flags )
: inherited( flags ),
_yawMode( YAW_AUTOMATICALLY_WHEN_BANKED )
{
}
void FlightManipulator::setNode(osg::Node* node)
/// Constructor.
FlightManipulator::FlightManipulator( const FlightManipulator& fm, const CopyOp& copyOp )
: inherited( fm, copyOp ),
_yawMode( fm._yawMode )
{
_node = node;
if (_node.get())
{
const osg::BoundingSphere& boundingSphere=_node->getBound();
_modelScale = boundingSphere._radius;
}
if (getAutoComputeHomePosition()) computeHomePosition();
}
const osg::Node* FlightManipulator::getNode() const
void FlightManipulator::init( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
return _node.get();
inherited::init( ea, us );
// center mouse pointer
centerMousePointer( ea, us );
}
osg::Node* FlightManipulator::getNode()
void FlightManipulator::home( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
return _node.get();
}
inherited::home( ea, us );
void FlightManipulator::home(const GUIEventAdapter& ea,GUIActionAdapter& us)
{
if (getAutoComputeHomePosition()) computeHomePosition();
computePosition(_homeEye, _homeCenter, _homeUp);
_velocity = 0.0;
us.requestRedraw();
us.requestContinuousUpdate(false);
us.requestWarpPointer((ea.getXmin()+ea.getXmax())/2.0f,(ea.getYmin()+ea.getYmax())/2.0f);
flushMouseEventStack();
// center mouse pointer
centerMousePointer( ea, us );
}
void FlightManipulator::init(const GUIEventAdapter& ea,GUIActionAdapter& us)
// doc in parent
bool FlightManipulator::handleFrame( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
flushMouseEventStack();
addMouseEvent( ea );
if( performMovement() )
us.requestRedraw();
us.requestContinuousUpdate(false);
_velocity = 0.0f;
if (ea.getEventType()!=GUIEventAdapter::RESIZE)
{
us.requestWarpPointer((ea.getXmin()+ea.getXmax())/2.0f,(ea.getYmin()+ea.getYmax())/2.0f);
}
return false;
}
bool FlightManipulator::handle(const GUIEventAdapter& ea,GUIActionAdapter& us)
// doc in parent
bool FlightManipulator::handleMouseMove( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
switch(ea.getEventType())
{
case(GUIEventAdapter::FRAME):
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
return false;
case(GUIEventAdapter::RESIZE):
init(ea,us);
us.requestRedraw();
return true;
default:
break;
}
if (ea.getHandled()) return false;
switch(ea.getEventType())
{
case(GUIEventAdapter::PUSH):
{
addMouseEvent(ea);
us.requestContinuousUpdate(true);
if (calcMovement()) us.requestRedraw();
return true;
}
case(GUIEventAdapter::RELEASE):
{
addMouseEvent(ea);
us.requestContinuousUpdate(true);
if (calcMovement()) us.requestRedraw();
return true;
}
case(GUIEventAdapter::DRAG):
{
addMouseEvent(ea);
us.requestContinuousUpdate(true);
if (calcMovement()) us.requestRedraw();
return true;
}
case(GUIEventAdapter::MOVE):
{
addMouseEvent(ea);
us.requestContinuousUpdate(true);
if (calcMovement()) us.requestRedraw();
return true;
}
case(GUIEventAdapter::KEYDOWN):
{
if (ea.getKey()==GUIEventAdapter::KEY_Space)
{
flushMouseEventStack();
home(ea,us);
us.requestRedraw();
us.requestContinuousUpdate(false);
return true;
}
else if (ea.getKey()=='q')
{
_yawMode = YAW_AUTOMATICALLY_WHEN_BANKED;
return true;
}
else if (ea.getKey()=='a')
{
_yawMode = NO_AUTOMATIC_YAW;
return true;
}
return false;
}
default:
return false;
}
}
void FlightManipulator::getUsage(osg::ApplicationUsage& usage) const
{
usage.addKeyboardMouseBinding("Flight: Space","Reset the viewing position to home");
usage.addKeyboardMouseBinding("Flight: q","Automatically yaw when banked (default)");
usage.addKeyboardMouseBinding("Flight: a","No yaw when banked");
}
void FlightManipulator::flushMouseEventStack()
{
_ga_t1 = NULL;
_ga_t0 = NULL;
return flightHandleEvent( ea, us );
}
void FlightManipulator::addMouseEvent(const GUIEventAdapter& ea)
// doc in parent
bool FlightManipulator::handleMouseDrag( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
_ga_t1 = _ga_t0;
_ga_t0 = &ea;
return flightHandleEvent( ea, us );
}
void FlightManipulator::setByMatrix(const osg::Matrixd& matrix)
// doc in parent
bool FlightManipulator::handleMousePush( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
_eye = matrix.getTrans();
_rotation = matrix.getRotate();
_distance = 1.0f;
}
osg::Matrixd FlightManipulator::getMatrix() const
{
return osg::Matrixd::rotate(_rotation)*osg::Matrixd::translate(_eye);
}
osg::Matrixd FlightManipulator::getInverseMatrix() const
{
return osg::Matrixd::translate(-_eye)*osg::Matrixd::rotate(_rotation.inverse());
}
void FlightManipulator::computePosition(const osg::Vec3& eye,const osg::Vec3& center,const osg::Vec3& up)
{
osg::Vec3d lv = center-eye;
osg::Vec3 f(lv);
f.normalize();
osg::Vec3 s(f^up);
s.normalize();
osg::Vec3 u(s^f);
u.normalize();
osg::Matrixd rotation_matrix(s[0], u[0], -f[0], 0.0f,
s[1], u[1], -f[1], 0.0f,
s[2], u[2], -f[2], 0.0f,
0.0f, 0.0f, 0.0f, 1.0f);
_eye = eye;
_distance = lv.length();
_rotation = rotation_matrix.getRotate().inverse();
return flightHandleEvent( ea, us );
}
bool FlightManipulator::calcMovement()
// doc in parent
bool FlightManipulator::handleMouseRelease( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
return flightHandleEvent( ea, us );
}
bool FlightManipulator::handleKeyDown( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
if( inherited::handleKeyDown( ea, us ) )
return true;
if( ea.getKey() == 'q' ) {
_yawMode = YAW_AUTOMATICALLY_WHEN_BANKED;
return true;
}
else if (ea.getKey()=='a') {
_yawMode = NO_AUTOMATIC_YAW;
return true;
}
return false;
}
bool FlightManipulator::flightHandleEvent( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
addMouseEvent( ea );
us.requestContinuousUpdate( true );
if( performMovement() )
us.requestRedraw();
return true;
}
void FlightManipulator::getUsage( ApplicationUsage& usage ) const
{
inherited::getUsage( usage );
usage.addKeyboardMouseBinding( getManipulatorName() + ": q", "Automatically yaw when banked (default)" );
usage.addKeyboardMouseBinding( getManipulatorName() + ": a", "No yaw when banked" );
}
/** Configure the Yaw control for the flight model. */
void FlightManipulator::setYawControlMode( YawControlMode ycm )
{
_yawMode = ycm;
}
bool FlightManipulator::performMovement()
{
// return if less then two events have been added.
if (_ga_t0.get()==NULL || _ga_t1.get()==NULL) return false;
@ -245,53 +149,46 @@ bool FlightManipulator::calcMovement()
if (dt<0.0f)
{
notify(INFO) << "warning dt = "<<dt<< std::endl;
notify(WARN) << "Manipulator warning dt = " << dt << std::endl;
dt = 0.0f;
}
unsigned int buttonMask = _ga_t1->getButtonMask();
if (buttonMask==GUIEventAdapter::LEFT_MOUSE_BUTTON)
{
// pan model.
_velocity += dt*(_acceleration+_velocity);
return performMovementLeftMouseButton(dt, 0., 0.);
}
else if (buttonMask==GUIEventAdapter::MIDDLE_MOUSE_BUTTON ||
buttonMask==(GUIEventAdapter::LEFT_MOUSE_BUTTON|GUIEventAdapter::RIGHT_MOUSE_BUTTON))
{
_velocity = 0.0f;
return performMovementMiddleMouseButton(dt, 0., 0.);
}
else if (buttonMask==GUIEventAdapter::RIGHT_MOUSE_BUTTON)
{
_velocity -= dt*(_acceleration+_velocity);
return performMovementRightMouseButton(dt, 0., 0.);
}
float dx = _ga_t0->getXnormalized();
float dy = _ga_t0->getYnormalized();
osg::CoordinateFrame cf=getCoordinateFrame(_eye);
CoordinateFrame cf=getCoordinateFrame(_eye);
osg::Matrixd rotation_matrix;
Matrixd rotation_matrix;
rotation_matrix.makeRotate(_rotation);
osg::Vec3d up = osg::Vec3(0.0,1.0,0.0) * rotation_matrix;
osg::Vec3d lv = osg::Vec3(0.0,0.0,-1.0) * rotation_matrix;
Vec3d up = Vec3d(0.0,1.0,0.0) * rotation_matrix;
Vec3d lv = Vec3d(0.0,0.0,-1.0) * rotation_matrix;
osg::Vec3d sv = lv^up;
Vec3d sv = lv^up;
sv.normalize();
double pitch = -inDegrees(dy*50.0f*dt);
double roll = inDegrees(dx*50.0f*dt);
osg::Quat delta_rotate;
Quat delta_rotate;
osg::Quat roll_rotate;
osg::Quat pitch_rotate;
Quat roll_rotate;
Quat pitch_rotate;
pitch_rotate.makeRotate(pitch,sv.x(),sv.y(),sv.z());
roll_rotate.makeRotate(roll,lv.x(),lv.y(),lv.z());
@ -304,7 +201,7 @@ bool FlightManipulator::calcMovement()
double bank = asinf(sv *getUpVector(cf));
double yaw = inRadians(bank)*dt;
osg::Quat yaw_rotate;
Quat yaw_rotate;
//yaw_rotate.makeRotate(yaw,0.0f,0.0f,1.0f);
yaw_rotate.makeRotate(yaw,getUpVector(cf));
@ -320,3 +217,25 @@ bool FlightManipulator::calcMovement()
return true;
}
bool FlightManipulator::performMovementLeftMouseButton( const double dt, const double dx, const double dy )
{
// pan model
_velocity += dt * (_acceleration + _velocity);
return true;
}
bool FlightManipulator::performMovementMiddleMouseButton( const double dt, const double dx, const double dy )
{
_velocity = 0.0f;
return true;
}
bool FlightManipulator::performMovementRightMouseButton( const double dt, const double dx, const double dy )
{
_velocity -= dt * (_acceleration + _velocity);
return true;
}

View File

@ -56,26 +56,6 @@ void KeySwitchMatrixManipulator::selectMatrixManipulator(unsigned int num)
}
}
/** Set the distance parameter (used by TrackballManipulator etc.) */
void KeySwitchMatrixManipulator::setDistance(double distance)
{
for(KeyManipMap::iterator itr=_manips.begin();
itr!=_manips.end();
++itr)
{
itr->second.second->setDistance(distance);
}
}
double KeySwitchMatrixManipulator::getDistance() const
{
if(_current)
{
return _current->getDistance();
}
else return 1.0;
}
void KeySwitchMatrixManipulator::setNode(osg::Node* node)
{
for(KeyManipMap::iterator itr=_manips.begin();
@ -108,17 +88,6 @@ void KeySwitchMatrixManipulator::setAutoComputeHomePosition(bool flag)
}
}
void KeySwitchMatrixManipulator::setMinimumDistance(float minimumDistance)
{
_minimumDistance = minimumDistance;
for(KeyManipMap::iterator itr=_manips.begin();
itr!=_manips.end();
++itr)
{
itr->second.second->setMinimumDistance(minimumDistance);
}
}
void KeySwitchMatrixManipulator::computeHomePosition()
{
for(KeyManipMap::iterator itr=_manips.begin();
@ -129,6 +98,23 @@ void KeySwitchMatrixManipulator::computeHomePosition()
}
}
void KeySwitchMatrixManipulator::home(const GUIEventAdapter& ee,GUIActionAdapter& aa)
{
// call home for all child manipulators
// (this can not be done just for current manipulator,
// because it is not possible to transfer some manipulator
// settings across manipulators using just MatrixManipulator interface
// (one problematic variable is for example OrbitManipulator::distance
// that can not be passed by setByMatrix method),
// thus we have to call home on all of them)
for(KeyManipMap::iterator itr=_manips.begin();
itr!=_manips.end();
++itr)
{
itr->second.second->home(ee,aa);
}
}
void KeySwitchMatrixManipulator::setCoordinateFrameCallback(CoordinateFrameCallback* cb)
{
_coordinateFrameCallback = cb;

View File

@ -1,14 +1,14 @@
#include <osg/GL>
#include <osg/Matrix>
#include <osg/ComputeBoundsVisitor>
#include <osgGA/MatrixManipulator>
#include <string.h>
using namespace osg;
using namespace osgGA;
MatrixManipulator::MatrixManipulator()
{
_minimumDistance = 0.001;
_intersectTraversalMask = 0xffffffff;
_autoComputeHomePosition = true;
@ -19,13 +19,101 @@ MatrixManipulator::MatrixManipulator()
}
MatrixManipulator::MatrixManipulator(const MatrixManipulator& mm, const CopyOp& copyOp)
: inherited(mm, copyOp),
_intersectTraversalMask(mm._intersectTraversalMask),
_autoComputeHomePosition(mm._autoComputeHomePosition),
_homeEye(mm._homeEye),
_homeCenter(mm._homeCenter),
_homeUp(mm._homeUp),
_coordinateFrameCallback(dynamic_cast<CoordinateFrameCallback*>(copyOp(mm._coordinateFrameCallback.get())))
{
}
MatrixManipulator::~MatrixManipulator()
{
}
std::string MatrixManipulator::getManipulatorName() const
{
const char* className = this->className();
const char* manipString = strstr(className, "Manipulator");
if (!manipString)
return std::string(className);
else
return std::string(className, manipString-className);
}
bool MatrixManipulator::handle(const GUIEventAdapter&,GUIActionAdapter&)
{
return false;
}
/** Compute the home position.
*
* The computation considers camera's fov (field of view) and model size and
* positions camera far enough to fit the model to the screen.
*
* camera parameter enables computations of camera's fov. If camera is NULL,
* scene to camera distance can not be computed and default value is used,
* based on model size only.
*
* useBoundingBox parameter enables to use bounding box instead of bounding sphere
* for scene bounds. Bounding box provide more precise scene center that may be
* important for many applications.*/
void MatrixManipulator::computeHomePosition(const osg::Camera *camera, bool useBoundingBox)
{
if (getNode())
{
osg::BoundingSphere boundingSphere;
if (useBoundingBox) {
// compute bounding box
// (bounding box computes model center more precisely than bounding sphere)
osg::ComputeBoundsVisitor cbVisitor;
getNode()->accept(cbVisitor);
osg::BoundingBox &bb = cbVisitor.getBoundingBox();
boundingSphere.expandBy(bb);
}
else
{
// compute bounding sphere
boundingSphere = getNode()->getBound();
}
// set dist to default
double dist = 3.5f * boundingSphere.radius();
if (camera) {
// try to compute dist from frustrum
double left,right,bottom,top,zNear,zFar;
if (camera->getProjectionMatrixAsFrustum(left,right,bottom,top,zNear,zFar))
{
double vertical2 = fabs(right - left) / zNear / 2.;
double horizontal2 = fabs(top - bottom) / zNear / 2.;
double dim = horizontal2 < vertical2 ? horizontal2 : vertical2;
double viewAngle = atan2(dim,1.);
dist = boundingSphere.radius() / sin(viewAngle);
}
else
// try to compute dist from ortho
if (camera->getProjectionMatrixAsOrtho(left,right,bottom,top,zNear,zFar))
{
dist = fabs(zFar - zNear) / 2.;
}
}
// set home position
setHomePosition(boundingSphere.center() + osg::Vec3d(0.0,-dist,0.0f),
boundingSphere.center(),
osg::Vec3d(0.0f,0.0f,1.0f),
_autoComputeHomePosition);
}
}

View File

@ -20,22 +20,91 @@ using namespace osg;
using namespace osgGA;
NodeTrackerManipulator::NodeTrackerManipulator()
NodeTrackerManipulator::NodeTrackerManipulator( int flags )
: inherited( flags ),
_trackerMode(NODE_CENTER_AND_ROTATION)
{
_trackerMode = NODE_CENTER_AND_ROTATION;
_rotationMode = TRACKBALL;
_distance = 1.0;
_thrown = false;
setVerticalAxisFixed(false);
}
NodeTrackerManipulator::~NodeTrackerManipulator()
NodeTrackerManipulator::NodeTrackerManipulator( const NodeTrackerManipulator& m, const CopyOp& copyOp )
: inherited( m, copyOp ),
_trackNodePath( m._trackNodePath ),
_trackerMode( m._trackerMode )
{
}
void NodeTrackerManipulator::setTrackNodePath(const osg::NodePath& nodePath)
{
_trackNodePath.clear();
_trackNodePath.reserve(nodePath.size());
std::copy(nodePath.begin(), nodePath.end(), std::back_inserter(_trackNodePath));
}
osg::NodePath NodeTrackerManipulator::getNodePath() const
{
osg::NodePath nodePath;
for(ObserverNodePath::const_iterator itr = _trackNodePath.begin();
itr != _trackNodePath.end();
++itr)
{
nodePath.push_back(const_cast<osg::Node*>(itr->get()));
}
return nodePath;
}
bool NodeTrackerManipulator::validateNodePath() const
{
for(ObserverNodePath::const_iterator itr = _trackNodePath.begin();
itr != _trackNodePath.begin();
++itr)
{
if (*itr==0)
{
osg::notify(osg::NOTICE)<<"Warning: tracked node path has been invalidated by changes in the scene graph."<<std::endl;
const_cast<ObserverNodePath&>(_trackNodePath).clear();
return false;
}
}
return true;
}
void NodeTrackerManipulator::setTrackerMode(TrackerMode mode)
{
_trackerMode = mode;
}
/// Sets rotation mode. \sa setVerticalAxisFixed
void NodeTrackerManipulator::setRotationMode(RotationMode mode)
{
setVerticalAxisFixed(mode!=TRACKBALL);
if (getAutoComputeHomePosition())
computeHomePosition();
}
/// Gets rotation mode. \sa getVerticalAxisFixed
NodeTrackerManipulator::RotationMode NodeTrackerManipulator::getRotationMode() const
{
return getVerticalAxisFixed() ? ELEVATION_AZIM : TRACKBALL;
}
void NodeTrackerManipulator::setNode(Node* node)
{
inherited::setNode( node );
// update model size
if (_flags & UPDATE_MODEL_SIZE)
if (_node.get()) {
setMinimumDistance(clampBetween(_modelSize*0.001, 0.00001, 1.0));
notify(INFO) << "NodeTrackerManipulator: setting minimum distance to "
<< _minimumDistance << std::endl;
}
}
void NodeTrackerManipulator::setTrackNode(osg::Node* node)
{
if (!node)
@ -44,231 +113,48 @@ void NodeTrackerManipulator::setTrackNode(osg::Node* node)
return;
}
osg::NodePathList parentNodePaths = node->getParentalNodePaths();
if (!parentNodePaths.empty())
osg::NodePathList nodePaths = node->getParentalNodePaths();
if (!nodePaths.empty())
{
osg::notify(osg::INFO)<<"NodeTrackerManipulator::setTrackNode(Node*): Path set"<<std::endl;
setTrackNodePath(parentNodePaths[0]);
if (nodePaths.size()>1)
{
osg::notify(osg::NOTICE)<<"osgGA::NodeTrackerManipualtor::setTrackNode(..) taking first parent path, ignoring others."<<std::endl;
}
osg::notify(osg::INFO)<<"NodeTrackerManipulator::setTrackNode(Node*"<<node<<" "<<node->getName()<<"): Path set"<<std::endl;
_trackNodePath.clear();
setTrackNodePath( nodePaths.front() );
}
else
{
osg::notify(osg::NOTICE)<<"NodeTrackerManipulator::setTrackNode(Node*): Unable to set tracked node due to empty parental path."<<std::endl;
}
}
osg::Node* NodeTrackerManipulator::getTrackNode()
{
osg::NodePath nodePath;
if (_trackNodePath.getNodePath(nodePath)) return nodePath.back();
else return 0;
}
const osg::Node* NodeTrackerManipulator::getTrackNode() const
{
osg::NodePath nodePath;
if (_trackNodePath.getNodePath(nodePath)) return nodePath.back();
else return 0;
}
void NodeTrackerManipulator::setTrackerMode(TrackerMode mode)
{
_trackerMode = mode;
}
void NodeTrackerManipulator::setRotationMode(RotationMode mode)
{
_rotationMode = mode;
if (getAutoComputeHomePosition()) computeHomePosition();
}
void NodeTrackerManipulator::setNode(osg::Node* node)
{
_node = node;
if (_node.get())
osg::notify(osg::INFO)<<"setTrackNode("<<node->getName()<<")"<<std::endl;
for(unsigned int i=0; i<_trackNodePath.size(); ++i)
{
const osg::BoundingSphere& boundingSphere=_node->getBound();
const float minimumDistanceScale = 0.001f;
_minimumDistance = osg::clampBetween(
float(boundingSphere._radius) * minimumDistanceScale,
0.00001f,1.0f);
osg::notify(osg::INFO)<<"Setting Tracker manipulator _minimumDistance to "<<_minimumDistance<<std::endl;
osg::notify(osg::INFO)<<" "<<_trackNodePath[i]->className()<<" '"<<_trackNodePath[i]->getName()<<"'"<<std::endl;
}
if (getAutoComputeHomePosition()) computeHomePosition();
}
const osg::Node* NodeTrackerManipulator::getNode() const
{
return _node.get();
}
osg::Node* NodeTrackerManipulator::getNode()
{
return _node.get();
}
void NodeTrackerManipulator::home(const GUIEventAdapter& ,GUIActionAdapter& us)
{
if (getAutoComputeHomePosition()) computeHomePosition();
computePosition(_homeEye, _homeCenter, _homeUp);
us.requestRedraw();
}
void NodeTrackerManipulator::computeHomePosition()
{
osg::NodePath nodePath;
_trackNodePath.getNodePath(nodePath);
osg::Node* node = nodePath.empty() ? getNode() : nodePath.back();
osg::Node* node = _trackNodePath.empty() ? getNode() : _trackNodePath.back().get();
if(node)
{
const osg::BoundingSphere& boundingSphere=node->getBound();
setHomePosition(boundingSphere._center+osg::Vec3( 0.0,-3.5f * boundingSphere._radius,0.0f),
setHomePosition(boundingSphere._center+osg::Vec3d( 0.0,-3.5f * boundingSphere._radius,0.0f),
boundingSphere._center,
osg::Vec3(0.0f,0.0f,1.0f),
osg::Vec3d(0.0f,0.0f,1.0f),
_autoComputeHomePosition);
}
}
void NodeTrackerManipulator::init(const GUIEventAdapter& ,GUIActionAdapter& )
{
flushMouseEventStack();
}
void NodeTrackerManipulator::getUsage(osg::ApplicationUsage& usage) const
{
usage.addKeyboardMouseBinding("NodeTracker: Space","Reset the viewing position to home");
usage.addKeyboardMouseBinding("NodeTracker: +","When in stereo, increase the fusion distance");
usage.addKeyboardMouseBinding("NodeTracker: -","When in stereo, reduce the fusion distance");
}
bool NodeTrackerManipulator::handle(const GUIEventAdapter& ea,GUIActionAdapter& us)
{
switch(ea.getEventType())
{
case(GUIEventAdapter::PUSH):
{
flushMouseEventStack();
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
return true;
}
case(GUIEventAdapter::RELEASE):
{
if (ea.getButtonMask()==0)
{
double timeSinceLastRecordEvent = _ga_t0.valid() ? (ea.getTime() - _ga_t0->getTime()) : DBL_MAX;
if (timeSinceLastRecordEvent>0.02) flushMouseEventStack();
if (isMouseMoving())
{
if (calcMovement())
{
us.requestRedraw();
us.requestContinuousUpdate(true);
_thrown = true;
}
}
else
{
flushMouseEventStack();
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
}
}
else
{
flushMouseEventStack();
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
}
return true;
}
case(GUIEventAdapter::DRAG):
{
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
return true;
}
case(GUIEventAdapter::MOVE):
{
return false;
}
case(GUIEventAdapter::KEYDOWN):
if (ea.getKey()==' ')
{
flushMouseEventStack();
_thrown = false;
home(ea,us);
us.requestRedraw();
us.requestContinuousUpdate(false);
return true;
}
return false;
case(GUIEventAdapter::FRAME):
if (_thrown)
{
if (calcMovement()) us.requestRedraw();
}
return false;
default:
return false;
}
}
bool NodeTrackerManipulator::isMouseMoving()
{
if (_ga_t0.get()==NULL || _ga_t1.get()==NULL) return false;
static const float velocity = 0.1f;
float dx = _ga_t0->getXnormalized()-_ga_t1->getXnormalized();
float dy = _ga_t0->getYnormalized()-_ga_t1->getYnormalized();
float len = sqrtf(dx*dx+dy*dy);
float dt = _ga_t0->getTime()-_ga_t1->getTime();
return (len>dt*velocity);
}
void NodeTrackerManipulator::flushMouseEventStack()
{
_ga_t1 = NULL;
_ga_t0 = NULL;
}
void NodeTrackerManipulator::addMouseEvent(const GUIEventAdapter& ea)
{
_ga_t1 = _ga_t0;
_ga_t0 = &ea;
}
void NodeTrackerManipulator::setByMatrix(const osg::Matrixd& matrix)
{
osg::Vec3d eye,center,up;
@ -276,20 +162,33 @@ void NodeTrackerManipulator::setByMatrix(const osg::Matrixd& matrix)
computePosition(eye,center,up);
}
void NodeTrackerManipulator::computeNodeWorldToLocal(osg::Matrixd& worldToLocal) const
{
if (validateNodePath())
{
worldToLocal = osg::computeWorldToLocal(getNodePath());
}
}
void NodeTrackerManipulator::computeNodeLocalToWorld(osg::Matrixd& localToWorld) const
{
if (validateNodePath())
{
localToWorld = osg::computeLocalToWorld(getNodePath());
}
}
void NodeTrackerManipulator::computeNodeCenterAndRotation(osg::Vec3d& nodeCenter, osg::Quat& nodeRotation) const
{
osg::Matrixd localToWorld, worldToLocal;
osg::NodePath nodePath;
if (_trackNodePath.getNodePath(nodePath))
{
worldToLocal = osg::computeWorldToLocal(nodePath);
localToWorld = osg::computeLocalToWorld(nodePath);
nodeCenter = osg::Vec3d(nodePath.back()->getBound().center())*localToWorld;
}
computeNodeLocalToWorld(localToWorld);
computeNodeWorldToLocal(worldToLocal);
if (validateNodePath())
nodeCenter = osg::Vec3d(_trackNodePath.back()->getBound().center())*localToWorld;
else
{
nodeCenter = osg::Vec3d(0.0f,0.0f,0.0f)*localToWorld;
}
switch(_trackerMode)
@ -350,7 +249,7 @@ void NodeTrackerManipulator::computePosition(const osg::Vec3d& eye,const osg::Ve
if (!_node) return;
// compute rotation matrix
osg::Vec3 lv(center-eye);
osg::Vec3d lv(center-eye);
_distance = lv.length();
osg::Matrixd lookat;
@ -359,206 +258,65 @@ void NodeTrackerManipulator::computePosition(const osg::Vec3d& eye,const osg::Ve
_rotation = lookat.getRotate().inverse();
}
bool NodeTrackerManipulator::calcMovement()
// doc in parent
bool NodeTrackerManipulator::performMovementLeftMouseButton( const double dt, const double dx, const double dy )
{
// return if less then two events have been added.
if (_ga_t0.get()==NULL || _ga_t1.get()==NULL) return false;
double dx = _ga_t0->getXnormalized()-_ga_t1->getXnormalized();
double dy = _ga_t0->getYnormalized()-_ga_t1->getYnormalized();
float distance = sqrtf(dx*dx + dy*dy);
// return if movement is too fast, indicating an error in event values or change in screen.
if (distance>0.5)
{
return false;
}
// return if there is no movement.
if (distance==0.0f)
{
return false;
}
osg::Vec3d nodeCenter;
osg::Quat nodeRotation;
computeNodeCenterAndRotation(nodeCenter, nodeRotation);
unsigned int buttonMask = _ga_t1->getButtonMask();
// rotate camera
if( getVerticalAxisFixed() ) {
if (buttonMask==GUIEventAdapter::LEFT_MOUSE_BUTTON)
{
osg::Matrix rotation_matrix;
rotation_matrix.makeRotate(_rotation);
if (_rotationMode==TRACKBALL)
{
osg::Vec3d lookVector = -getUpVector(rotation_matrix);
osg::Vec3d sideVector = getSideVector(rotation_matrix);
osg::Vec3d upVector = getFrontVector(rotation_matrix);
// rotate camera.
osg::Vec3 axis;
double angle;
osg::Vec3d localUp(0.0f,0.0f,1.0f);
double px0 = _ga_t0->getXnormalized();
double py0 = _ga_t0->getYnormalized();
osg::Vec3d forwardVector = localUp^sideVector;
sideVector = forwardVector^localUp;
double px1 = _ga_t1->getXnormalized();
double py1 = _ga_t1->getYnormalized();
forwardVector.normalize();
sideVector.normalize();
osg::Quat rotate_elevation;
rotate_elevation.makeRotate(dy,sideVector);
trackball(axis,angle,px1,py1,px0,py0);
osg::Quat rotate_azim;
rotate_azim.makeRotate(-dx,localUp);
osg::Quat new_rotate;
new_rotate.makeRotate(angle,axis);
_rotation = _rotation * rotate_elevation * rotate_azim;
_rotation = _rotation*new_rotate;
}
else
{
osg::Matrix rotation_matrix;
rotation_matrix.makeRotate(_rotation);
} else
rotateTrackball( _ga_t0->getXnormalized(), _ga_t0->getYnormalized(),
_ga_t1->getXnormalized(), _ga_t1->getYnormalized() );
osg::Vec3d lookVector = -getUpVector(rotation_matrix);
osg::Vec3d sideVector = getSideVector(rotation_matrix);
osg::Vec3d upVector = getFrontVector(rotation_matrix);
osg::Vec3d localUp(0.0f,0.0f,1.0f);
osg::Vec3d forwardVector = localUp^sideVector;
sideVector = forwardVector^localUp;
forwardVector.normalize();
sideVector.normalize();
osg::Quat rotate_elevation;
rotate_elevation.makeRotate(dy,sideVector);
osg::Quat rotate_azim;
rotate_azim.makeRotate(-dx,localUp);
_rotation = _rotation * rotate_elevation * rotate_azim;
}
return true;
}
else if (buttonMask==GUIEventAdapter::MIDDLE_MOUSE_BUTTON ||
buttonMask==(GUIEventAdapter::LEFT_MOUSE_BUTTON|GUIEventAdapter::RIGHT_MOUSE_BUTTON))
{
return true;
}
else if (buttonMask==GUIEventAdapter::RIGHT_MOUSE_BUTTON)
{
// zoom model.
double fd = _distance;
double scale = 1.0f+dy;
if (fd*scale>_minimumDistance)
{
_distance *= scale;
} else
{
_distance = _minimumDistance;
}
return true;
}
return false;
return true;
}
void NodeTrackerManipulator::clampOrientation()
// doc in parent
bool NodeTrackerManipulator::performMovementMiddleMouseButton( const double dt, const double dx, const double dy )
{
osg::Vec3d nodeCenter;
osg::Quat nodeRotation;
computeNodeCenterAndRotation(nodeCenter, nodeRotation);
return true;
}
/*
* This size should really be based on the distance from the center of
* rotation to the point on the object underneath the mouse. That
* point would then track the mouse as closely as possible. This is a
* simple example, though, so that is left as an Exercise for the
* Programmer.
*/
const float TRACKBALLSIZE = 0.8f;
/*
* Ok, simulate a track-ball. Project the points onto the virtual
* trackball, then figure out the axis of rotation, which is the cross
* product of P1 P2 and O P1 (O is the center of the ball, 0,0,0)
* Note: This is a deformed trackball-- is a trackball in the center,
* but is deformed into a hyperbolic sheet of rotation away from the
* center. This particular function was chosen after trying out
* several variations.
*
* It is assumed that the arguments to this routine are in the range
* (-1.0 ... 1.0)
*/
void NodeTrackerManipulator::trackball(osg::Vec3& axis,double & angle, double p1x, double p1y, double p2x, double p2y)
// doc in parent
bool NodeTrackerManipulator::performMovementRightMouseButton( const double dt, const double dx, const double dy )
{
/*
* First, figure out z-coordinates for projection of P1 and P2 to
* deformed sphere
*/
osg::Matrix rotation_matrix(_rotation);
osg::Vec3d uv = osg::Vec3d(0.0,1.0,0.0)*rotation_matrix;
osg::Vec3d sv = osg::Vec3d(1.0,0.0,0.0)*rotation_matrix;
osg::Vec3d lv = osg::Vec3d(0.0,0.0,-1.0)*rotation_matrix;
osg::Vec3d p1 = sv*p1x+uv*p1y-lv*tb_project_to_sphere(TRACKBALLSIZE,p1x,p1y);
osg::Vec3d p2 = sv*p2x+uv*p2y-lv*tb_project_to_sphere(TRACKBALLSIZE,p2x,p2y);
/*
* Now, we want the cross product of P1 and P2
*/
// Robert,
//
// This was the quick 'n' dirty fix to get the trackball doing the right
// thing after fixing the Quat rotations to be right-handed. You may want
// to do something more elegant.
// axis = p1^p2;
axis = p2^p1;
axis.normalize();
/*
* Figure out how much to rotate around that axis.
*/
double t = (p2-p1).length() / (2.0*TRACKBALLSIZE);
/*
* Avoid problems with out-of-control values...
*/
if (t > 1.0) t = 1.0;
if (t < -1.0) t = -1.0;
angle = inRadians(asin(t));
osg::Vec3d nodeCenter;
osg::Quat nodeRotation;
computeNodeCenterAndRotation(nodeCenter, nodeRotation);
}
/*
* Project an x,y pair onto a sphere of radius r OR a hyperbolic sheet
* if we are away from the center of the sphere.
*/
double NodeTrackerManipulator::tb_project_to_sphere(double r, double x, double y)
{
float d, t, z;
d = sqrt(x*x + y*y);
/* Inside sphere */
if (d < r * 0.70710678118654752440)
{
z = sqrt(r*r - d*d);
} /* On hyperbola */
else
{
t = r / 1.41421356237309504880;
z = t*t / d;
}
return z;
return inherited::performMovementRightMouseButton(dt, dx, dy);
}

View File

@ -0,0 +1,553 @@
/* -*-c++-*- OpenSceneGraph - Copyright (C) 1998-2006 Robert Osfield
*
* This library is open source and may be redistributed and/or modified under
* the terms of the OpenSceneGraph Public License (OSGPL) version 0.0 or
* (at your option) any later version. The full license is in LICENSE file
* included with this distribution, and on the openscenegraph.org website.
*
* This library 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
* OpenSceneGraph Public License for more details.
*/
#include <osgGA/OrbitManipulator>
#include <osg/BoundsChecking>
#include <cassert>
using namespace osg;
using namespace osgGA;
int OrbitManipulator::_minimumDistanceFlagIndex = allocateRelativeFlag();
/// Constructor.
OrbitManipulator::OrbitManipulator( int flags )
: inherited( flags ),
_distance( 1. ),
_trackballSize( 0.8 )
{
setMinimumDistance( 0.05, true );
setWheelZoomFactor( 0.1 );
if( _flags & SET_CENTER_ON_WHEEL_UP )
setAnimationTime( 0.2 );
}
/// Constructor.
OrbitManipulator::OrbitManipulator( const OrbitManipulator& om, const CopyOp& copyOp )
: inherited( om, copyOp ),
_center( om._center ),
_rotation( om._rotation ),
_distance( om._distance ),
_trackballSize( om._trackballSize ),
_wheelZoomFactor( om._wheelZoomFactor ),
_minimumDistance( om._minimumDistance )
{
}
/** Set the position of the manipulator using a 4x4 matrix.*/
void OrbitManipulator::setByMatrix( const osg::Matrixd& matrix )
{
_center = osg::Vec3d( 0., 0., -_distance ) * matrix;
_rotation = matrix.getRotate();
// fix current rotation
if( getVerticalAxisFixed() )
fixVerticalAxis( _center, _rotation, true );
}
/** Set the position of the manipulator using a 4x4 matrix.*/
void OrbitManipulator::setByInverseMatrix( const osg::Matrixd& matrix )
{
setByMatrix( osg::Matrixd::inverse( matrix ) );
}
/** Get the position of the manipulator as 4x4 matrix.*/
osg::Matrixd OrbitManipulator::getMatrix() const
{
return osg::Matrixd::translate( 0., 0., _distance ) *
osg::Matrixd::rotate( _rotation ) *
osg::Matrixd::translate( _center );
}
/** Get the position of the manipulator as a inverse matrix of the manipulator,
typically used as a model view matrix.*/
osg::Matrixd OrbitManipulator::getInverseMatrix() const
{
return osg::Matrixd::translate( -_center ) *
osg::Matrixd::rotate( _rotation.inverse() ) *
osg::Matrixd::translate( 0.0, 0.0, -_distance );
}
// doc in parent
void OrbitManipulator::setTransformation( const osg::Vec3d& eye, const osg::Quat& rotation )
{
_center = eye + rotation * osg::Vec3d( 0., 0., -_distance );
_rotation = rotation;
// fix current rotation
if( getVerticalAxisFixed() )
fixVerticalAxis( _center, _rotation, true );
}
// doc in parent
void OrbitManipulator::getTransformation( osg::Vec3d& eye, osg::Quat& rotation ) const
{
eye = _center - _rotation * osg::Vec3d( 0., 0., -_distance );
rotation = _rotation;
}
// doc in parent
void OrbitManipulator::setTransformation( const osg::Vec3d& center, const osg::Vec3d& eye, const osg::Vec3d& up )
{
Vec3d lv( center - eye );
Vec3d f( lv );
f.normalize();
Vec3d s( f^up );
s.normalize();
Vec3d u( s^f );
u.normalize();
osg::Matrixd rotation_matrix( s[0], u[0], -f[0], 0.0f,
s[1], u[1], -f[1], 0.0f,
s[2], u[2], -f[2], 0.0f,
0.0f, 0.0f, 0.0f, 1.0f );
_center = center;
_distance = lv.length();
_rotation = rotation_matrix.getRotate().inverse();
// fix current rotation
if( getVerticalAxisFixed() )
fixVerticalAxis( _center, _rotation, true );
}
// doc in parent
void OrbitManipulator::getTransformation( osg::Vec3d& center, osg::Vec3d& eye, osg::Vec3d& up ) const
{
center = _center;
eye = _center + _rotation * osg::Vec3d( 0., 0., _distance );
up = _rotation * osg::Vec3d( 0., 1., 0. );
}
// doc in parent
bool OrbitManipulator::handleMouseWheel( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
switch( ea.getScrollingMotion() ) {
// mouse scroll up event
case GUIEventAdapter::SCROLL_UP: {
if( _flags & SET_CENTER_ON_WHEEL_UP ) {
if( getAnimationTime() <= 0. )
// center by mouse intersection (no animation)
setCenterByMousePointerIntersection( ea, us );
else {
// start new animation only if there is no animation in progress
if( !isAnimating() )
startAnimationByMousePointerIntersection( ea, us );
}
}
// perform zoom
zoomModel( -_wheelZoomFactor, true );
us.requestRedraw();
us.requestContinuousUpdate( isAnimating() || _thrown );
return true;
}
// mouse scroll down event
case GUIEventAdapter::SCROLL_DOWN:
zoomModel( _wheelZoomFactor, true );
us.requestRedraw();
us.requestContinuousUpdate( false );
return true;
// unhandled mouse scrolling motion
default:
return false;
}
}
// doc in parent
bool OrbitManipulator::performMovementLeftMouseButton( const double dt, const double dx, const double dy )
{
// rotate camera
if( getVerticalAxisFixed() )
rotateWithFixedVertical( dx, dy );
else
rotateTrackball( _ga_t0->getXnormalized(), _ga_t0->getYnormalized(),
_ga_t1->getXnormalized(), _ga_t1->getYnormalized() );
return true;
}
// doc in parent
bool OrbitManipulator::performMovementMiddleMouseButton( const double dt, const double dx, const double dy )
{
// pan model
float scale = -0.3f * _distance;
panModel( dx*scale, dy*scale );
return true;
}
// doc in parent
bool OrbitManipulator::performMovementRightMouseButton( const double dt, const double dx, const double dy )
{
// zoom model
zoomModel( dy, true );
return true;
}
bool OrbitManipulator::performMouseDeltaMovement( const float dx, const float dy )
{
// rotate camera
if( getVerticalAxisFixed() )
rotateWithFixedVertical( dx, dy );
else
rotateTrackball( 0.f, 0.f, dx, dy );
return true;
}
void OrbitManipulator::applyAnimationStep( const double currentProgress, const double prevProgress )
{
OrbitAnimationData *ad = dynamic_cast< OrbitAnimationData* >( _animationData.get() );
assert( ad );
// compute new center
osg::Vec3d prevCenter, prevEye, prevUp;
getTransformation( prevCenter, prevEye, prevUp );
osg::Vec3d newCenter = osg::Vec3d(prevCenter) + (ad->_movement * (currentProgress - prevProgress));
// fix vertical axis
if( getVerticalAxisFixed() ) {
CoordinateFrame coordinateFrame = getCoordinateFrame( newCenter );
Vec3d localUp = getUpVector( coordinateFrame );
fixVerticalAxis( newCenter - prevEye, prevUp, prevUp, localUp, false );
}
// apply new transformation
setTransformation( newCenter, prevEye, prevUp );
}
bool OrbitManipulator::startAnimationByMousePointerIntersection(
const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us )
{
// get current transformation
osg::Vec3d prevCenter, prevEye, prevUp;
getTransformation( prevCenter, prevEye, prevUp );
// center by mouse intersection
if( !setCenterByMousePointerIntersection( ea, us ) )
return false;
OrbitAnimationData *ad = dynamic_cast< OrbitAnimationData*>( _animationData.get() );
assert( ad );
// setup animation data and restore original transformation
ad->start( osg::Vec3d(_center) - prevCenter, ea.getTime() );
setTransformation( prevCenter, prevEye, prevUp );
return true;
}
void OrbitManipulator::OrbitAnimationData::start( const osg::Vec3d& movement, const double startTime )
{
AnimationData::start( startTime );
_movement = movement;
}
/** Performs trackball rotation based on two points given, for example,
by mouse pointer on the screen.*/
void OrbitManipulator::rotateTrackball( const float px0, const float py0, const float px1, const float py1 )
{
osg::Vec3d axis;
float angle;
trackball( axis, angle, px1, py1, px0, py0 );
Quat new_rotate;
new_rotate.makeRotate( angle, axis );
_rotation = _rotation * new_rotate;
}
/** Performs rotation horizontally by dx parameter and vertically by dy parameter,
while keeping UP vector.*/
void OrbitManipulator::rotateWithFixedVertical( const float dx, const float dy )
{
CoordinateFrame coordinateFrame = getCoordinateFrame( _center );
Vec3d localUp = getUpVector( coordinateFrame );
rotateYawPitch( _rotation, dx, dy, localUp );
}
/** Performs rotation horizontally by dx parameter and vertically by dy parameter,
while keeping UP vector given by up parameter.*/
void OrbitManipulator::rotateWithFixedVertical( const float dx, const float dy, const Vec3f& up )
{
rotateYawPitch( _rotation, dx, dy, up );
}
/** Moves camera in x,y,z directions given in camera local coordinates.*/
void OrbitManipulator::panModel( const float dx, const float dy, const float dz )
{
Matrix rotation_matrix;
rotation_matrix.makeRotate( _rotation );
Vec3d dv( dx, dy, dz );
_center += dv * rotation_matrix;
}
/** Changes the distance of camera to the focal center.
If pushForwardIfNeeded is true and minimumDistance is reached,
the focal center is moved forward. Otherwise, distance is limited
to its minimum value.
\sa OrbitManipulator::setMinimumDistance
*/
void OrbitManipulator::zoomModel( const float dy, bool pushForwardIfNeeded )
{
// scale
float scale = 1.0f + dy;
// minimum distance
float minDist = _minimumDistance;
if( getRelativeFlag( _minimumDistanceFlagIndex ) )
minDist *= _modelSize;
if( _distance*scale > minDist )
{
// regular zoom
_distance *= scale;
}
else
{
if( pushForwardIfNeeded )
{
// push the camera forward
float scale = -_distance;
Matrixd rotation_matrix( _rotation );
Vec3d dv = (Vec3d( 0.0f, 0.0f, -1.0f ) * rotation_matrix) * (dy * scale);
_center += dv;
}
else
{
// set distance on its minimum value
_distance = minDist;
}
}
}
/**
* Simulate a track-ball. Project the points onto the virtual
* trackball, then figure out the axis of rotation, which is the cross
* product of P1 P2 and O P1 (O is the center of the ball, 0,0,0)
* Note: This is a deformed trackball-- is a trackball in the center,
* but is deformed into a hyperbolic sheet of rotation away from the
* center. This particular function was chosen after trying out
* several variations.
*
* It is assumed that the arguments to this routine are in the range
* (-1.0 ... 1.0)
*/
void OrbitManipulator::trackball( osg::Vec3d& axis, float& angle, float p1x, float p1y, float p2x, float p2y )
{
/*
* First, figure out z-coordinates for projection of P1 and P2 to
* deformed sphere
*/
osg::Matrixd rotation_matrix(_rotation);
osg::Vec3d uv = Vec3d(0.0f,1.0f,0.0f)*rotation_matrix;
osg::Vec3d sv = Vec3d(1.0f,0.0f,0.0f)*rotation_matrix;
osg::Vec3d lv = Vec3d(0.0f,0.0f,-1.0f)*rotation_matrix;
osg::Vec3d p1 = sv * p1x + uv * p1y - lv * tb_project_to_sphere(_trackballSize, p1x, p1y);
osg::Vec3d p2 = sv * p2x + uv * p2y - lv * tb_project_to_sphere(_trackballSize, p2x, p2y);
/*
* Now, we want the cross product of P1 and P2
*/
axis = p2^p1;
axis.normalize();
/*
* Figure out how much to rotate around that axis.
*/
float t = (p2 - p1).length() / (2.0 * _trackballSize);
/*
* Avoid problems with out-of-control values...
*/
if (t > 1.0) t = 1.0;
if (t < -1.0) t = -1.0;
angle = inRadians(asin(t));
}
/**
* Helper trackball method that projects an x,y pair onto a sphere of radius r OR
* a hyperbolic sheet if we are away from the center of the sphere.
*/
float OrbitManipulator::tb_project_to_sphere( float r, float x, float y )
{
float d, t, z;
d = sqrt(x*x + y*y);
/* Inside sphere */
if (d < r * 0.70710678118654752440)
{
z = sqrt(r*r - d*d);
} /* On hyperbola */
else
{
t = r / 1.41421356237309504880;
z = t*t / d;
}
return z;
}
/** Get the FusionDistanceMode. Used by SceneView for setting up stereo convergence.*/
osgUtil::SceneView::FusionDistanceMode OrbitManipulator::getFusionDistanceMode() const
{
return osgUtil::SceneView::USE_FUSION_DISTANCE_VALUE;
}
/** Get the FusionDistanceValue. Used by SceneView for setting up stereo convergence.*/
float OrbitManipulator::getFusionDistanceValue() const
{
return _distance;
}
/** Set the center of the manipulator. */
void OrbitManipulator::setCenter( const Vec3d& center )
{
_center = center;
}
/** Get the center of the manipulator. */
const Vec3d& OrbitManipulator::getCenter() const
{
return _center;
}
/** Set the rotation of the manipulator. */
void OrbitManipulator::setRotation( const Quat& rotation )
{
_rotation = rotation;
}
/** Get the rotation of the manipulator. */
const Quat& OrbitManipulator::getRotation() const
{
return _rotation;
}
/** Set the distance of camera to the center. */
void OrbitManipulator::setDistance( double distance )
{
_distance = distance;
}
/** Get the distance of the camera to the center. */
double OrbitManipulator::getDistance() const
{
return _distance;
}
/** Set the size of the trackball. Value is relative to the model size. */
void OrbitManipulator::setTrackballSize( const double& size )
{
/*
* This size should really be based on the distance from the center of
* rotation to the point on the object underneath the mouse. That
* point would then track the mouse as closely as possible. This is a
* simple example, though, so that is left as an Exercise for the
* Programmer.
*/
_trackballSize = size;
clampBetweenRange( _trackballSize, 0.1, 1.0, "TrackballManipulator::setTrackballSize(float)" );
}
/** Set the mouse wheel zoom factor.
The amount of camera movement on each mouse wheel event
is computed as the current distance to the center multiplied by this factor.
For example, value of 0.1 will short distance to center by 10% on each wheel up event.*/
void OrbitManipulator::setWheelZoomFactor( double wheelZoomFactor )
{
_wheelZoomFactor = wheelZoomFactor;
}
/** Set the minimum distance of the eye point from the center
before the center is pushed forward.*/
void OrbitManipulator::setMinimumDistance( const double& minimumDistance, bool relativeToModelSize )
{
_minimumDistance = minimumDistance;
setRelativeFlag( _minimumDistanceFlagIndex, relativeToModelSize );
}
/** Get the minimum distance of the eye point from the center
before the center is pushed forward.*/
double OrbitManipulator::getMinimumDistance( bool *relativeToModelSize ) const
{
if( relativeToModelSize )
*relativeToModelSize = getRelativeFlag( _minimumDistanceFlagIndex );
return _minimumDistance;
}

View File

@ -247,7 +247,7 @@ void SphericalManipulator::addMouseEvent(const GUIEventAdapter& ea)
//--------------------------------------------------------------------------------------------------
void SphericalManipulator::setByMatrix(const osg::Matrixd& matrix)
{
_center=osg::Vec3(0,0,-_distance)*matrix;
_center=osg::Vec3d(0,0,-_distance)*matrix;
_heading=atan2(-matrix(0,0),matrix(0,1));
@ -373,7 +373,7 @@ bool SphericalManipulator::calcMovement()
osg::Matrix rotation_matrix;
rotation_matrix=osg::Matrixd::rotate(_elevation,-1,0,0)*osg::Matrixd::rotate(PI_2+_heading,0,0,1);
osg::Vec3 dv(throwScale*dx*scale,0,throwScale*dy*scale);
osg::Vec3d dv(throwScale*dx*scale,0,throwScale*dy*scale);
_center += dv*rotation_matrix;
return true;

View File

@ -0,0 +1,792 @@
/* -*-c++-*- OpenSceneGraph - Copyright (C) 1998-2006 Robert Osfield
*
* This library is open source and may be redistributed and/or modified under
* the terms of the OpenSceneGraph Public License (OSGPL) version 0.0 or
* (at your option) any later version. The full license is in LICENSE file
* included with this distribution, and on the openscenegraph.org website.
*
* This library 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
* OpenSceneGraph Public License for more details.
*/
#include <osgGA/StandardManipulator>
#include <osgViewer/View>
#include <cassert>
using namespace osg;
using namespace osgGA;
using namespace osgUtil;
/** \fn void StandardManipulator::setTransformation( const osg::Vec3d& eye, const osg::Quat& rotation );
Sets manipulator by eye position and eye orientation.*/
/** \fn void StandardManipulator::setTransformation( const osg::Vec3d& center, const osg::Vec3d& eye, const osg::Vec3d& up );
Sets manipulator by focal center, eye position, and up vector.*/
/** \fn void StandardManipulator::getTransformation( osg::Vec3d& eye, osg::Quat& rotation );
Gets manipulator's eye position and eye orientation.*/
/** \fn void StandardManipulator::getTransformation( osg::Vec3d& center, osg::Vec3d& eye, osg::Vec3d& up );
Gets manipulator's focal center, eye position, and up vector.*/
int StandardManipulator::numRelativeFlagsAllocated = 0;
int StandardManipulator::allocateRelativeFlag()
{
return numRelativeFlagsAllocated++;
}
/// Constructor.
StandardManipulator::StandardManipulator( int flags )
: inherited(),
_thrown( false ),
_mouseCenterX(0.0f), _mouseCenterY(0.0f),
_delta_frame_time(0.01), _last_frame_time(0.0),
_modelSize( 0. ),
_verticalAxisFixed( true ),
_flags( flags ),
_relativeFlags( 0 )
{
}
/// Constructor.
StandardManipulator::StandardManipulator( const StandardManipulator& uim, const CopyOp& copyOp )
: inherited( uim, copyOp ),
_thrown( uim._thrown ),
_mouseCenterX(0.0f), _mouseCenterY(0.0f),
_ga_t1( dynamic_cast< GUIEventAdapter* >( copyOp( uim._ga_t1.get() ) ) ),
_ga_t0( dynamic_cast< GUIEventAdapter* >( copyOp( uim._ga_t0.get() ) ) ),
_delta_frame_time(0.01), _last_frame_time(0.0),
_modelSize( uim._modelSize ),
_verticalAxisFixed( uim._verticalAxisFixed ),
_flags( uim._flags ),
_relativeFlags( uim._relativeFlags )
{
}
/** Attach a node to the manipulator.
Automatically detaches previously attached node.
setNode(NULL) detaches previously attached nodes.
Is ignored by manipulators which do not require a reference model.*/
void StandardManipulator::setNode( Node* node )
{
_node = node;
// update model size
if( _node.get() ) {
const BoundingSphere& boundingSphere = _node->getBound();
_modelSize = boundingSphere.radius();
} else
_modelSize = 0.;
// compute home position
if( getAutoComputeHomePosition() )
computeHomePosition( NULL, ( _flags & COMPUTE_HOME_USING_BBOX ) != 0 );
}
/** Return node if attached.*/
const Node* StandardManipulator::getNode() const
{
return _node.get();
}
/** Return node if attached.*/
Node* StandardManipulator::getNode()
{
return _node.get();
}
/** Makes manipulator to keep camera's "UP" vector.
*
* In general, fixed up vector makes camera control more user friendly.
*
* To change up vector, use MatrixManipulator::setCoordinateFrameCallback.*/
void StandardManipulator::setVerticalAxisFixed( bool value )
{
_verticalAxisFixed = value;
}
/// Sets manipulator animation time when centering on mouse wheel up is enabled.
void StandardManipulator::setAnimationTime( const double t )
{
if( t <= 0. ) {
finishAnimation();
_animationData = NULL;
return;
}
if( !_animationData )
allocAnimationData();
_animationData->_animationTime = t;
}
/// Returns manipulator animation time when centering on mouse wheel up is enabled.
double StandardManipulator::getAnimationTime() const
{
if( _animationData )
return _animationData->_animationTime;
else
return 0.;
}
/// Returns whether manipulator is performing animation at the moment.
bool StandardManipulator::isAnimating() const
{
if( _animationData )
return _animationData->_isAnimating;
else
return false;
}
void StandardManipulator::finishAnimation()
{
if( !isAnimating() )
return;
applyAnimationStep( 1., _animationData->_phase );
}
/** Move the camera to the default position.
The user should probably want to use home(GUIEventAdapter&, GUIActionAdapter&)
instead to set manipulator to the home position. This method does not trigger
any redraw processing or updates continuous update processing.
StandardManipulator implementation only updates its internal structures and
recomputes its home position if autoComputeHomePosition is set.
Descendant classes are expected to update camera position.*/
void StandardManipulator::home( double /*currentTime*/ )
{
if( getAutoComputeHomePosition() )
computeHomePosition( NULL, ( _flags & COMPUTE_HOME_USING_BBOX ) != 0 );
_thrown = false;
setTransformation( _homeCenter, _homeEye, _homeUp );
flushMouseEventStack();
}
/** Move the camera to the default position.
If autoComputeHomePosition is on, home position is computed.
The computation considers camera fov and model size and
positions camera far enough to fit the model to the screen.
StandardManipulator implementation only updates its internal data.
If home position is expected to be supported by the descendant manipulator,
it has to reimplement the method to update manipulator transformation.*/
void StandardManipulator::home( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
if( getAutoComputeHomePosition() ) {
const Camera *camera = us.asView() ? us.asView()->getCamera() : NULL;
computeHomePosition( camera, ( _flags & COMPUTE_HOME_USING_BBOX ) != 0 );
}
_thrown = false;
setTransformation( _homeCenter, _homeEye, _homeUp );
us.requestRedraw();
us.requestContinuousUpdate( false );
flushMouseEventStack();
}
/** Start/restart the manipulator.*/
void StandardManipulator::init( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
flushMouseEventStack();
// stop animation
_thrown = false;
us.requestContinuousUpdate(false);
}
/** Handles events. Returns true if handled, false otherwise.*/
bool StandardManipulator::handle( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
switch( ea.getEventType() ) {
case GUIEventAdapter::FRAME:
return handleFrame( ea, us );
case GUIEventAdapter::RESIZE:
return handleResize( ea, us );
default:
break;
}
if( ea.getHandled() )
return false;
switch( ea.getEventType() ) {
case GUIEventAdapter::MOVE:
return handleMouseMove( ea, us );
case GUIEventAdapter::DRAG:
return handleMouseDrag( ea, us );
case GUIEventAdapter::PUSH:
return handleMousePush( ea, us );
case GUIEventAdapter::RELEASE:
return handleMouseRelease( ea, us );
case GUIEventAdapter::KEYDOWN:
return handleKeyDown( ea, us );
case GUIEventAdapter::KEYUP:
return handleKeyUp( ea, us );
case GUIEventAdapter::SCROLL:
if( _flags & PROCESS_MOUSE_WHEEL )
return handleMouseWheel( ea, us );
else
return false;
default:
return false;
}
}
/// Handles GUIEventAdapter::FRAME event.
bool StandardManipulator::handleFrame( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
double current_frame_time = ea.getTime();
_delta_frame_time = current_frame_time - _last_frame_time;
_last_frame_time = current_frame_time;
if( _thrown && performMovement() )
{
us.requestRedraw();
}
if( _animationData && _animationData->_isAnimating )
{
performAnimationMovement( ea, us );
}
return false;
}
/// Handles GUIEventAdapter::RESIZE event.
bool StandardManipulator::handleResize( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
init( ea, us );
us.requestRedraw();
return true;
}
/// Handles GUIEventAdapter::MOVE event.
bool StandardManipulator::handleMouseMove( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
return false;
}
/// Handles GUIEventAdapter::DRAG event.
bool StandardManipulator::handleMouseDrag( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
addMouseEvent( ea );
if( performMovement() )
us.requestRedraw();
us.requestContinuousUpdate( false );
_thrown = false;
return true;
}
/// Handles GUIEventAdapter::PUSH event.
bool StandardManipulator::handleMousePush( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
flushMouseEventStack();
addMouseEvent( ea );
if( performMovement() )
us.requestRedraw();
us.requestContinuousUpdate( false );
_thrown = false;
return true;
}
/// Handles GUIEventAdapter::RELEASE event.
bool StandardManipulator::handleMouseRelease( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
if( ea.getButtonMask() == 0 ) {
double timeSinceLastRecordEvent = _ga_t0.valid() ? (ea.getTime() - _ga_t0->getTime()) : DBL_MAX;
if( timeSinceLastRecordEvent > 0.02 )
flushMouseEventStack();
if( isMouseMoving() ) {
if( performMovement() ) {
us.requestRedraw();
us.requestContinuousUpdate( true );
_thrown = true;
}
return true;
}
}
flushMouseEventStack();
addMouseEvent( ea );
if( performMovement() )
us.requestRedraw();
us.requestContinuousUpdate( false );
_thrown = false;
return true;
}
/// Handles GUIEventAdapter::KEYDOWN event.
bool StandardManipulator::handleKeyDown( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
if( ea.getKey() == GUIEventAdapter::KEY_Space ) {
flushMouseEventStack();
_thrown = false;
home(ea,us);
return true;
}
return false;
}
/// Handles GUIEventAdapter::KEYUP event.
bool StandardManipulator::handleKeyUp( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
return false;
}
/// Handles GUIEventAdapter::SCROLL event.
bool StandardManipulator::handleMouseWheel( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
return false;
}
/** Get the keyboard and mouse usage of the manipulator.*/
void StandardManipulator::getUsage( ApplicationUsage& usage ) const
{
usage.addKeyboardMouseBinding( getManipulatorName() + ": Space", "Reset the viewing position to home" );
}
/// Make movement step of manipulator. Returns true if any movement was made.
bool StandardManipulator::performMovement()
{
// return if less then two events have been added
if( _ga_t0.get() == NULL || _ga_t1.get() == NULL )
return false;
// get delta time
double dt = _ga_t0->getTime() - _ga_t1->getTime();
if( dt < 0. ) {
notify( INFO ) << "Manipulator warning: dt = " << dt << std::endl;
dt = 0.;
}
// get deltaX and deltaY
float dx = _ga_t0->getXnormalized() - _ga_t1->getXnormalized();
float dy = _ga_t0->getYnormalized() - _ga_t1->getYnormalized();
// return if there is no movement.
if( dx == 0. && dy == 0. )
return false;
// call appropriate methods
unsigned int buttonMask = _ga_t1->getButtonMask();
if( buttonMask == GUIEventAdapter::LEFT_MOUSE_BUTTON )
return performMovementLeftMouseButton( dt, dx, dy );
else if( buttonMask == GUIEventAdapter::MIDDLE_MOUSE_BUTTON ||
buttonMask == (GUIEventAdapter::LEFT_MOUSE_BUTTON | GUIEventAdapter::RIGHT_MOUSE_BUTTON) )
return performMovementMiddleMouseButton( dt, dx, dy );
else if( buttonMask == GUIEventAdapter::RIGHT_MOUSE_BUTTON )
return performMovementRightMouseButton( dt, dx, dy );
return false;
}
/** Make movement step of manipulator.
This method implements movement for left mouse button.*/
bool StandardManipulator::performMovementLeftMouseButton( const double dt, const double dx, const double dy )
{
return false;
}
/** Make movement step of manipulator.
This method implements movement for middle mouse button
or combination of left and right mouse button pressed together.*/
bool StandardManipulator::performMovementMiddleMouseButton( const double dt, const double dx, const double dy )
{
return false;
}
/** Make movement step of manipulator.
This method implements movement for right mouse button.*/
bool StandardManipulator::performMovementRightMouseButton( const double dt, const double dx, const double dy )
{
return false;
}
bool StandardManipulator::handleMouseDeltaMovement( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
float dx = ea.getX() - _mouseCenterX;
float dy = ea.getY() - _mouseCenterY;
if( dx == 0.f && dy == 0.f )
return false;
addMouseEvent( ea );
centerMousePointer( ea, us );
return performMouseDeltaMovement( dx, dy );
}
bool StandardManipulator::performMouseDeltaMovement( const float dx, const float dy )
{
return false;
}
bool StandardManipulator::performAnimationMovement( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
double f = (ea.getTime() - _animationData->_startTime) / _animationData->_animationTime;
if( f >= 1. ) {
f = 1.;
_animationData->_isAnimating = false;
if( !_thrown )
us.requestContinuousUpdate( false );
}
applyAnimationStep( f, _animationData->_phase );
_animationData->_phase = f;
us.requestRedraw();
return _animationData->_isAnimating;
}
void StandardManipulator::applyAnimationStep( const double currentProgress, const double prevProgress )
{
}
void StandardManipulator::centerMousePointer( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
_mouseCenterX = (ea.getXmin() + ea.getXmax()) / 2.0f;
_mouseCenterY = (ea.getYmin() + ea.getYmax()) / 2.0f;
us.requestWarpPointer( _mouseCenterX, _mouseCenterY );
}
/** Add the current mouse GUIEvent to internal stack.*/
void StandardManipulator::addMouseEvent( const GUIEventAdapter& ea )
{
_ga_t1 = _ga_t0;
_ga_t0 = &ea;
}
/** Reset the internal GUIEvent stack.*/
void StandardManipulator::flushMouseEventStack()
{
_ga_t1 = NULL;
_ga_t0 = NULL;
}
/** Check the speed at which the mouse is moving.
If speed is below a threshold then return false, otherwise return true.*/
bool StandardManipulator::isMouseMoving() const
{
if (_ga_t0.get()==NULL || _ga_t1.get()==NULL) return false;
static const float velocity = 0.1f;
float dx = _ga_t0->getXnormalized()-_ga_t1->getXnormalized();
float dy = _ga_t0->getYnormalized()-_ga_t1->getYnormalized();
float len = sqrtf(dx*dx+dy*dy);
float dt = _ga_t0->getTime()-_ga_t1->getTime();
return (len>dt*velocity);
}
/** Update rotation by yaw and pitch.
*
* localUp parameter defines either camera's "UP" vector
* that will be preserved during rotation, or it can be zero (0,0,0) to specify
* that camera's "UP" vector will be not preserved and free rotation will be made.*/
void StandardManipulator::rotateYawPitch( Quat& rotation, const double yaw, const double pitch,
const Vec3d& localUp )
{
bool verticalAxisFixed = (localUp != Vec3d( 0.,0.,0. ));
// fix current rotation
if( verticalAxisFixed )
fixVerticalAxis( rotation, localUp, true );
// rotations
Quat rotateYaw( -yaw, verticalAxisFixed ? localUp : rotation * Vec3d( 0.,1.,0. ) );
Quat rotatePitch;
Quat newRotation;
Vec3d cameraRight( rotation * Vec3d( 1.,0.,0. ) );
double my_dy = pitch;
int i = 0;
do {
// rotations
rotatePitch.makeRotate( my_dy, cameraRight );
newRotation = rotation * rotateYaw * rotatePitch;
// update vertical axis
if( verticalAxisFixed )
fixVerticalAxis( newRotation, localUp, false );
// check for viewer's up vector to be more than 90 degrees from "up" axis
Vec3d newCameraUp = newRotation * Vec3d( 0.,1.,0. );
if( newCameraUp * localUp > 0. ) {
// apply new rotation
rotation = newRotation;
return;
}
my_dy /= 2.;
if( ++i == 20 ) {
rotation = rotation * rotateYaw;
return;
}
} while( true );
}
void StandardManipulator::fixVerticalAxis( Vec3d& eye, Quat& rotation, bool disallowFlipOver )
{
CoordinateFrame coordinateFrame = getCoordinateFrame( eye );
Vec3d localUp = getUpVector( coordinateFrame );
fixVerticalAxis( rotation, localUp, disallowFlipOver );
}
/** The method corrects the rotation to make impression of fixed up direction.
* Technically said, it makes the roll component of the rotation equal to zero.
*
* Rotation parameter is the rotation to be fixed, localUp is UP vector, and
* disallowFlipOver when set on true avoids pitch rotation component to grow
* over +/- 90 degrees. If this happens and disallowFlipOver is true,
* right and up camera vectors are negated (changing roll by 180 degrees),
* making pitch once again between -90..+90 degrees limits.*/
void StandardManipulator::fixVerticalAxis( Quat& rotation, const Vec3d& localUp, bool disallowFlipOver )
{
// camera direction vectors
Vec3d cameraUp = rotation * Vec3d( 0.,1.,0. );
Vec3d cameraRight = rotation * Vec3d( 1.,0.,0. );
Vec3d cameraForward = rotation * Vec3d( 0.,0.,-1. );
// computed directions
Vec3d newCameraRight1 = cameraForward ^ localUp;
Vec3d newCameraRight2 = cameraUp ^ localUp;
Vec3d newCameraRight = (newCameraRight1.length2() > newCameraRight2.length2()) ?
newCameraRight1 : newCameraRight2;
if( newCameraRight * cameraRight < 0. )
newCameraRight = -newCameraRight;
assert( newCameraRight.length2() > 0. );
// vertical axis correction
Quat rotationVerticalAxisCorrection;
rotationVerticalAxisCorrection.makeRotate( cameraRight, newCameraRight );
// rotate camera
rotation *= rotationVerticalAxisCorrection;
if( disallowFlipOver ) {
// make viewer's up vector to be always less than 90 degrees from "up" axis
Vec3d newCameraUp = newCameraRight ^ cameraForward;
if( newCameraUp * localUp < 0. )
rotation = Quat( PI, Vec3d( 0.,0.,1. ) ) * rotation;
}
}
/** The method corrects the rotation to make impression of fixed up direction.
* Technically said, it makes the roll component of the rotation equal to zero.
*
* forward and up parameter is the forward and up vector of the camera.
* newUp will receive corrected UP camera vector. localUp is UP vector
* that is used for vertical correction.
* disallowFlipOver when set on true avoids pitch rotation component to grow
* over +/- 90 degrees. If this happens and disallowFlipOver is true,
* right and up camera vectors are negated (changing roll by 180 degrees),
* making pitch once again between -90..+90 degrees limits.*/
void StandardManipulator::fixVerticalAxis( const osg::Vec3d& forward, const osg::Vec3d& up, osg::Vec3d& newUp,
const osg::Vec3d& localUp, bool disallowFlipOver )
{
// right direction
osg::Vec3d right1 = forward ^ localUp;
osg::Vec3d right2 = up ^ localUp;
osg::Vec3d right = (right1.length2() > right2.length2()) ? right1 : right2;
// newUp
// note: do not use up and other parameters from now as they may point
// to the same variable as newUp parameter
newUp = right ^ forward;
assert( newUp.length2() > 0. );
newUp.normalize();
}
bool StandardManipulator::setCenterByMousePointerIntersection( const GUIEventAdapter& ea, GUIActionAdapter& us )
{
osg::View* view = us.asView();
if( !view )
return false;
Camera *camera = view->getCamera();
if( !camera )
return false;
// prepare variables
float x = ( ea.getX() - ea.getXmin() ) / ( ea.getXmax() - ea.getXmin() );
float y = ( ea.getY() - ea.getYmin() ) / ( ea.getYmax() - ea.getYmin() );
LineSegmentIntersector::CoordinateFrame cf;
Viewport *vp = camera->getViewport();
if( vp ) {
cf = Intersector::WINDOW;
x *= vp->width();
y *= vp->height();
} else
cf = Intersector::PROJECTION;
// perform intersection computation
ref_ptr< LineSegmentIntersector > picker = new LineSegmentIntersector( cf, x, y );
IntersectionVisitor iv( picker.get() );
camera->accept( iv );
// return on no intersections
if( !picker->containsIntersections() )
return false;
// get all intersections
LineSegmentIntersector::Intersections& intersections = picker->getIntersections();
// get current transformation
osg::Vec3d eye, oldCenter, up;
getTransformation( oldCenter, eye, up );
// new center
osg::Vec3d newCenter = (*intersections.begin()).getWorldIntersectPoint();
// make vertical axis correction
if( getVerticalAxisFixed() ) {
CoordinateFrame coordinateFrame = getCoordinateFrame( newCenter );
Vec3d localUp = getUpVector( coordinateFrame );
fixVerticalAxis( newCenter - eye, up, up, localUp, true );
}
// set the new center
setTransformation( newCenter, eye, up );
// warp pointer
// note: this works for me on standard camera on GraphicsWindowEmbedded and Qt,
// while it was necessary to implement requestWarpPointer like follows:
//
// void QOSGWidget::requestWarpPointer( float x, float y )
// {
// osgViewer::Viewer::requestWarpPointer( x, y );
// QCursor::setPos( this->mapToGlobal( QPoint( int( x+.5f ), int( y+.5f ) ) ) );
// }
//
// Additions of .5f are just for the purpose of rounding.
centerMousePointer( ea, us );
return true;
}
/** Makes mouse pointer intersection test with the geometry bellow the pointer
and starts animation to center camera to look at the closest hit bellow the mouse pointer.
If there is a hit, animation is started and true is returned.
Otherwise, the method returns false.*/
bool StandardManipulator::startAnimationByMousePointerIntersection(
const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter& us )
{
return false;
}
StandardManipulator::AnimationData::AnimationData()
:_isAnimating( false )
{
}
void StandardManipulator::AnimationData::start( const double startTime )
{
_isAnimating = true;
_startTime = startTime;
_phase = 0.;
}

View File

@ -12,239 +12,63 @@
*/
#include <osgGA/TerrainManipulator>
#include <osg/Quat>
#include <osg/Notify>
#include <osg/io_utils>
#include <osgUtil/LineSegmentIntersector>
#include <osg/io_utils>
using namespace osg;
using namespace osgGA;
TerrainManipulator::TerrainManipulator()
{
_rotationMode =ELEVATION_HEADING;
_distance = 1.0;
_thrown = false;
}
TerrainManipulator::~TerrainManipulator()
/// Constructor.
TerrainManipulator::TerrainManipulator( int flags )
: inherited( flags )
{
}
void TerrainManipulator::setRotationMode(RotationMode mode)
/// Constructor.
TerrainManipulator::TerrainManipulator( const TerrainManipulator& tm, const CopyOp& copyOp )
: inherited( tm, copyOp ),
_previousUp( tm._previousUp )
{
_rotationMode = mode;
// need to correct rotation.
}
void TerrainManipulator::setNode(osg::Node* node)
{
_node = node;
if (_node.get())
{
const osg::BoundingSphere& boundingSphere=_node->getBound();
const float minimumDistanceScale = 0.001f;
_minimumDistance = osg::clampBetween(
float(boundingSphere._radius) * minimumDistanceScale,
0.00001f,1.0f);
OSG_NOTIFY(osg::INFO)<<"Setting terrain manipulator _minimumDistance to "<<_minimumDistance<<std::endl;
}
if (getAutoComputeHomePosition()) computeHomePosition();
}
const osg::Node* TerrainManipulator::getNode() const
void TerrainManipulator::setRotationMode( TerrainManipulator::RotationMode mode )
{
return _node.get();
setVerticalAxisFixed( mode == ELEVATION_AZIM );
}
osg::Node* TerrainManipulator::getNode()
TerrainManipulator::RotationMode TerrainManipulator::getRotationMode() const
{
return _node.get();
return getVerticalAxisFixed() ? ELEVATION_AZIM : ELEVATION_AZIM_ROLL;
}
bool TerrainManipulator::intersect(const osg::Vec3d& start, const osg::Vec3d& end, osg::Vec3d& intersection) const
void TerrainManipulator::setNode( Node* node )
{
osg::ref_ptr<osgUtil::LineSegmentIntersector> lsi = new osgUtil::LineSegmentIntersector(start,end);
inherited::setNode( node );
osgUtil::IntersectionVisitor iv(lsi.get());
iv.setTraversalMask(_intersectTraversalMask);
_node->accept(iv);
if (lsi->containsIntersections())
{
intersection = lsi->getIntersections().begin()->getWorldIntersectPoint();
return true;
}
return false;
// update model size
if( _flags & UPDATE_MODEL_SIZE )
if( _node.get() ) {
setMinimumDistance( clampBetween( _modelSize * 0.001, 0.00001, 1.0 ) );
notify( INFO ) << "TerrainManipulator: setting _minimumDistance to "
<< _minimumDistance << std::endl;
}
}
void TerrainManipulator::home(const GUIEventAdapter& ,GUIActionAdapter& us)
{
if (getAutoComputeHomePosition()) computeHomePosition();
computePosition(_homeEye, _homeCenter, _homeUp);
us.requestRedraw();
}
void TerrainManipulator::init(const GUIEventAdapter& ,GUIActionAdapter& )
{
flushMouseEventStack();
}
void TerrainManipulator::getUsage(osg::ApplicationUsage& usage) const
{
usage.addKeyboardMouseBinding("Terrain: Space","Reset the viewing position to home");
usage.addKeyboardMouseBinding("Terrain: +","When in stereo, increase the fusion distance");
usage.addKeyboardMouseBinding("Terrain: -","When in stereo, reduce the fusion distance");
}
bool TerrainManipulator::handle(const GUIEventAdapter& ea,GUIActionAdapter& us)
void TerrainManipulator::setByMatrix(const Matrixd& matrix)
{
switch(ea.getEventType())
{
case(GUIEventAdapter::FRAME):
if (_thrown)
{
if (calcMovement()) us.requestRedraw();
}
return false;
default:
break;
}
Vec3d lookVector(- matrix(2,0),-matrix(2,1),-matrix(2,2));
Vec3d eye(matrix(3,0),matrix(3,1),matrix(3,2));
if (ea.getHandled()) return false;
switch(ea.getEventType())
{
case(GUIEventAdapter::PUSH):
{
flushMouseEventStack();
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
return true;
}
case(GUIEventAdapter::RELEASE):
{
if (ea.getButtonMask()==0)
{
if (isMouseMoving())
{
if (calcMovement())
{
us.requestRedraw();
us.requestContinuousUpdate(true);
_thrown = true;
}
}
else
{
flushMouseEventStack();
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
}
}
else
{
flushMouseEventStack();
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
}
return true;
}
case(GUIEventAdapter::DRAG):
{
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
return true;
}
case(GUIEventAdapter::MOVE):
{
return false;
}
case(GUIEventAdapter::KEYDOWN):
if (ea.getKey()== GUIEventAdapter::KEY_Space)
{
flushMouseEventStack();
_thrown = false;
home(ea,us);
us.requestRedraw();
us.requestContinuousUpdate(false);
return true;
}
return false;
default:
return false;
}
}
bool TerrainManipulator::isMouseMoving()
{
if (_ga_t0.get()==NULL || _ga_t1.get()==NULL) return false;
static const float velocity = 0.1f;
float dx = _ga_t0->getXnormalized()-_ga_t1->getXnormalized();
float dy = _ga_t0->getYnormalized()-_ga_t1->getYnormalized();
float len = sqrtf(dx*dx+dy*dy);
float dt = _ga_t0->getTime()-_ga_t1->getTime();
return (len>dt*velocity);
}
void TerrainManipulator::flushMouseEventStack()
{
_ga_t1 = NULL;
_ga_t0 = NULL;
}
void TerrainManipulator::addMouseEvent(const GUIEventAdapter& ea)
{
_ga_t1 = _ga_t0;
_ga_t0 = &ea;
}
void TerrainManipulator::setByMatrix(const osg::Matrixd& matrix)
{
osg::Vec3d lookVector(- matrix(2,0),-matrix(2,1),-matrix(2,2));
osg::Vec3d eye(matrix(3,0),matrix(3,1),matrix(3,2));
OSG_NOTIFY(INFO)<<"eye point "<<eye<<std::endl;
OSG_NOTIFY(INFO)<<"lookVector "<<lookVector<<std::endl;
notify(INFO)<<"eye point "<<eye<<std::endl;
notify(INFO)<<"lookVector "<<lookVector<<std::endl;
if (!_node)
{
@ -256,12 +80,12 @@ void TerrainManipulator::setByMatrix(const osg::Matrixd& matrix)
// need to reintersect with the terrain
const osg::BoundingSphere& bs = _node->getBound();
const BoundingSphere& bs = _node->getBound();
float distance = (eye-bs.center()).length() + _node->getBound().radius();
osg::Vec3d start_segment = eye;
osg::Vec3d end_segment = eye + lookVector*distance;
Vec3d start_segment = eye;
Vec3d end_segment = eye + lookVector*distance;
osg::Vec3d ip;
Vec3d ip;
bool hitFound = false;
if (intersect(start_segment, end_segment, ip))
{
@ -270,9 +94,9 @@ void TerrainManipulator::setByMatrix(const osg::Matrixd& matrix)
_distance = (eye-ip).length();
osg::Matrixd rotation_matrix = osg::Matrixd::translate(0.0,0.0,-_distance)*
matrix*
osg::Matrixd::translate(-_center);
Matrixd rotation_matrix = Matrixd::translate(0.0,0.0,-_distance)*
matrix*
Matrixd::translate(-_center);
_rotation = rotation_matrix.getRotate();
@ -304,26 +128,17 @@ void TerrainManipulator::setByMatrix(const osg::Matrixd& matrix)
clampOrientation();
}
osg::Matrixd TerrainManipulator::getMatrix() const
{
return osg::Matrixd::translate(0.0,0.0,_distance)*osg::Matrixd::rotate(_rotation)*osg::Matrixd::translate(_center);
}
osg::Matrixd TerrainManipulator::getInverseMatrix() const
{
return osg::Matrixd::translate(-_center)*osg::Matrixd::rotate(_rotation.inverse())*osg::Matrixd::translate(0.0,0.0,-_distance);
}
void TerrainManipulator::computePosition(const osg::Vec3d& eye,const osg::Vec3d& center,const osg::Vec3d& up)
void TerrainManipulator::setTransformation( const osg::Vec3d& center, const osg::Vec3d& eye, const osg::Vec3d& up )
{
if (!_node) return;
// compute rotation matrix
osg::Vec3d lv(center-eye);
Vec3d lv(center-eye);
_distance = lv.length();
_center = center;
OSG_NOTIFY(osg::INFO) << "In compute"<< std::endl;
notify(INFO) << "In compute"<< std::endl;
if (_node.valid())
{
@ -331,15 +146,15 @@ void TerrainManipulator::computePosition(const osg::Vec3d& eye,const osg::Vec3d&
double distance = lv.length();
double maxDistance = distance+2*(eye-_node->getBound().center()).length();
osg::Vec3d farPosition = eye+lv*(maxDistance/distance);
osg::Vec3d endPoint = center;
Vec3d farPosition = eye+lv*(maxDistance/distance);
Vec3d endPoint = center;
for(int i=0;
!hitFound && i<2;
++i, endPoint = farPosition)
{
// compute the intersection with the scene.
osg::Vec3d ip;
Vec3d ip;
if (intersect(eye, endPoint, ip))
{
_center = ip;
@ -353,7 +168,7 @@ void TerrainManipulator::computePosition(const osg::Vec3d& eye,const osg::Vec3d&
// note LookAt = inv(CF)*inv(RM)*inv(T) which is equivalent to:
// inv(R) = CF*LookAt.
osg::Matrixd rotation_matrix = osg::Matrixd::lookAt(eye,center,up);
Matrixd rotation_matrix = Matrixd::lookAt(eye,center,up);
_rotation = rotation_matrix.getRotate().inverse();
@ -364,216 +179,149 @@ void TerrainManipulator::computePosition(const osg::Vec3d& eye,const osg::Vec3d&
}
bool TerrainManipulator::calcMovement()
bool TerrainManipulator::intersect( const Vec3d& start, const Vec3d& end, Vec3d& intersection ) const
{
// return if less then two events have been added.
if (_ga_t0.get()==NULL || _ga_t1.get()==NULL) return false;
ref_ptr<osgUtil::LineSegmentIntersector> lsi = new osgUtil::LineSegmentIntersector(start,end);
double dx = _ga_t0->getXnormalized()-_ga_t1->getXnormalized();
double dy = _ga_t0->getYnormalized()-_ga_t1->getYnormalized();
osgUtil::IntersectionVisitor iv(lsi.get());
iv.setTraversalMask(_intersectTraversalMask);
_node->accept(iv);
// return if there is no movement.
if (dx==0 && dy==0) return false;
unsigned int buttonMask = _ga_t1->getButtonMask();
if (buttonMask==GUIEventAdapter::LEFT_MOUSE_BUTTON)
if (lsi->containsIntersections())
{
if (_rotationMode==ELEVATION_HEADING_ROLL)
{
// rotate camera.
osg::Vec3 axis;
double angle;
double px0 = _ga_t0->getXnormalized();
double py0 = _ga_t0->getYnormalized();
double px1 = _ga_t1->getXnormalized();
double py1 = _ga_t1->getYnormalized();
trackball(axis,angle,px1,py1,px0,py0);
osg::Quat new_rotate;
new_rotate.makeRotate(angle,axis);
_rotation = _rotation*new_rotate;
}
else
{
osg::Matrix rotation_matrix;
rotation_matrix.makeRotate(_rotation);
osg::Vec3d lookVector = -getUpVector(rotation_matrix);
osg::Vec3d sideVector = getSideVector(rotation_matrix);
osg::Vec3d upVector = getFrontVector(rotation_matrix);
CoordinateFrame coordinateFrame = getCoordinateFrame(_center);
osg::Vec3d localUp = getUpVector(coordinateFrame);
//osg::Vec3d localUp = _previousUp;
osg::Vec3d forwardVector = localUp^sideVector;
sideVector = forwardVector^localUp;
forwardVector.normalize();
sideVector.normalize();
osg::Quat rotate_elevation;
rotate_elevation.makeRotate(dy,sideVector);
osg::Quat rotate_azim;
rotate_azim.makeRotate(-dx,localUp);
_rotation = _rotation * rotate_elevation * rotate_azim;
}
return true;
}
else if (buttonMask==GUIEventAdapter::MIDDLE_MOUSE_BUTTON ||
buttonMask==(GUIEventAdapter::LEFT_MOUSE_BUTTON|GUIEventAdapter::RIGHT_MOUSE_BUTTON))
{
// pan model.
double scale = -0.3f*_distance;
osg::Matrixd rotation_matrix;
rotation_matrix.makeRotate(_rotation);
// compute look vector.
osg::Vec3d lookVector = -getUpVector(rotation_matrix);
osg::Vec3d sideVector = getSideVector(rotation_matrix);
osg::Vec3d upVector = getFrontVector(rotation_matrix);
// CoordinateFrame coordinateFrame = getCoordinateFrame(_center);
// osg::Vec3d localUp = getUpVector(coordinateFrame);
osg::Vec3d localUp = _previousUp;
osg::Vec3d forwardVector =localUp^sideVector;
sideVector = forwardVector^localUp;
forwardVector.normalize();
sideVector.normalize();
osg::Vec3d dv = forwardVector * (dy*scale) + sideVector * (dx*scale);
_center += dv;
// need to recompute the intersection point along the look vector.
bool hitFound = false;
if (_node.valid())
{
// now reorientate the coordinate frame to the frame coords.
CoordinateFrame coordinateFrame = getCoordinateFrame(_center);
// need to reintersect with the terrain
double distance = _node->getBound().radius()*0.25f;
osg::Vec3d ip1;
osg::Vec3d ip2;
bool hit_ip1 = intersect(_center, _center + getUpVector(coordinateFrame) * distance, ip1);
bool hit_ip2 = intersect(_center, _center - getUpVector(coordinateFrame) * distance, ip2);
if (hit_ip1)
{
if (hit_ip2)
{
_center = (_center-ip1).length2() < (_center-ip2).length2() ?
ip1 :
ip2;
hitFound = true;
}
else
{
_center = ip1;
hitFound = true;
}
}
else if (hit_ip2)
{
_center = ip2;
hitFound = true;
}
if (!hitFound)
{
// ??
OSG_NOTIFY(INFO)<<"TerrainManipulator unable to intersect with terrain."<<std::endl;
}
coordinateFrame = getCoordinateFrame(_center);
osg::Vec3d new_localUp = getUpVector(coordinateFrame);
osg::Quat pan_rotation;
pan_rotation.makeRotate(localUp,new_localUp);
if (!pan_rotation.zeroRotation())
{
_rotation = _rotation * pan_rotation;
_previousUp = new_localUp;
//OSG_NOTIFY(osg::NOTICE)<<"Rotating from "<<localUp<<" to "<<new_localUp<<" angle = "<<acos(localUp*new_localUp/(localUp.length()*new_localUp.length()))<<std::endl;
//clampOrientation();
}
else
{
OSG_NOTIFY(osg::INFO)<<"New up orientation nearly inline - no need to rotate"<<std::endl;
}
}
intersection = lsi->getIntersections().begin()->getWorldIntersectPoint();
return true;
}
else if (buttonMask==GUIEventAdapter::RIGHT_MOUSE_BUTTON)
{
// zoom model.
double fd = _distance;
double scale = 1.0f+dy;
if (fd*scale>_minimumDistance)
{
_distance *= scale;
} else
{
_distance = _minimumDistance;
}
return true;
}
return false;
}
bool TerrainManipulator::performMovementMiddleMouseButton( const double dt, const double dx, const double dy )
{
// pan model.
double scale = -0.3f*_distance;
Matrixd rotation_matrix;
rotation_matrix.makeRotate(_rotation);
// compute look vector.
Vec3d lookVector = -getUpVector(rotation_matrix);
Vec3d sideVector = getSideVector(rotation_matrix);
Vec3d upVector = getFrontVector(rotation_matrix);
// CoordinateFrame coordinateFrame = getCoordinateFrame(_center);
// Vec3d localUp = getUpVector(coordinateFrame);
Vec3d localUp = _previousUp;
Vec3d forwardVector =localUp^sideVector;
sideVector = forwardVector^localUp;
forwardVector.normalize();
sideVector.normalize();
Vec3d dv = forwardVector * (dy*scale) + sideVector * (dx*scale);
_center += dv;
// need to recompute the intersection point along the look vector.
bool hitFound = false;
if (_node.valid())
{
// now reorientate the coordinate frame to the frame coords.
CoordinateFrame coordinateFrame = getCoordinateFrame(_center);
// need to reintersect with the terrain
double distance = _node->getBound().radius()*0.25f;
Vec3d ip1;
Vec3d ip2;
bool hit_ip1 = intersect(_center, _center + getUpVector(coordinateFrame) * distance, ip1);
bool hit_ip2 = intersect(_center, _center - getUpVector(coordinateFrame) * distance, ip2);
if (hit_ip1)
{
if (hit_ip2)
{
_center = (_center-ip1).length2() < (_center-ip2).length2() ?
ip1 :
ip2;
hitFound = true;
}
else
{
_center = ip1;
hitFound = true;
}
}
else if (hit_ip2)
{
_center = ip2;
hitFound = true;
}
if (!hitFound)
{
// ??
notify(INFO)<<"TerrainManipulator unable to intersect with terrain."<<std::endl;
}
coordinateFrame = getCoordinateFrame(_center);
Vec3d new_localUp = getUpVector(coordinateFrame);
Quat pan_rotation;
pan_rotation.makeRotate(localUp,new_localUp);
if (!pan_rotation.zeroRotation())
{
_rotation = _rotation * pan_rotation;
_previousUp = new_localUp;
//notify(NOTICE)<<"Rotating from "<<localUp<<" to "<<new_localUp<<" angle = "<<acos(localUp*new_localUp/(localUp.length()*new_localUp.length()))<<std::endl;
//clampOrientation();
}
else
{
notify(INFO)<<"New up orientation nearly inline - no need to rotate"<<std::endl;
}
}
return true;
}
bool TerrainManipulator::performMovementRightMouseButton( const double dt, const double dx, const double dy )
{
// zoom model
zoomModel( dy, false );
return true;
}
void TerrainManipulator::clampOrientation()
{
if (_rotationMode==ELEVATION_HEADING)
if (!getVerticalAxisFixed())
{
osg::Matrixd rotation_matrix;
Matrixd rotation_matrix;
rotation_matrix.makeRotate(_rotation);
osg::Vec3d lookVector = -getUpVector(rotation_matrix);
osg::Vec3d upVector = getFrontVector(rotation_matrix);
Vec3d lookVector = -getUpVector(rotation_matrix);
Vec3d upVector = getFrontVector(rotation_matrix);
CoordinateFrame coordinateFrame = getCoordinateFrame(_center);
osg::Vec3d localUp = getUpVector(coordinateFrame);
//osg::Vec3d localUp = _previousUp;
Vec3d localUp = getUpVector(coordinateFrame);
//Vec3d localUp = _previousUp;
osg::Vec3d sideVector = lookVector ^ localUp;
Vec3d sideVector = lookVector ^ localUp;
if (sideVector.length()<0.1)
{
OSG_NOTIFY(osg::INFO)<<"Side vector short "<<sideVector.length()<<std::endl;
notify(INFO)<<"Side vector short "<<sideVector.length()<<std::endl;
sideVector = upVector^localUp;
sideVector.normalize();
@ -583,7 +331,7 @@ void TerrainManipulator::clampOrientation()
Vec3d newUpVector = sideVector^lookVector;
newUpVector.normalize();
osg::Quat rotate_roll;
Quat rotate_roll;
rotate_roll.makeRotate(upVector,newUpVector);
if (!rotate_roll.zeroRotation())
@ -592,92 +340,3 @@ void TerrainManipulator::clampOrientation()
}
}
}
/*
* This size should really be based on the distance from the center of
* rotation to the point on the object underneath the mouse. That
* point would then track the mouse as closely as possible. This is a
* simple example, though, so that is left as an Exercise for the
* Programmer.
*/
const float TRACKBALLSIZE = 0.8f;
/*
* Ok, simulate a track-ball. Project the points onto the virtual
* trackball, then figure out the axis of rotation, which is the cross
* product of P1 P2 and O P1 (O is the center of the ball, 0,0,0)
* Note: This is a deformed trackball-- is a trackball in the center,
* but is deformed into a hyperbolic sheet of rotation away from the
* center. This particular function was chosen after trying out
* several variations.
*
* It is assumed that the arguments to this routine are in the range
* (-1.0 ... 1.0)
*/
void TerrainManipulator::trackball(osg::Vec3& axis,double & angle, double p1x, double p1y, double p2x, double p2y)
{
/*
* First, figure out z-coordinates for projection of P1 and P2 to
* deformed sphere
*/
osg::Matrix rotation_matrix(_rotation);
osg::Vec3d uv = osg::Vec3d(0.0,1.0,0.0)*rotation_matrix;
osg::Vec3d sv = osg::Vec3d(1.0,0.0,0.0)*rotation_matrix;
osg::Vec3d lv = osg::Vec3d(0.0,0.0,-1.0)*rotation_matrix;
osg::Vec3d p1 = sv*p1x+uv*p1y-lv*tb_project_to_sphere(TRACKBALLSIZE,p1x,p1y);
osg::Vec3d p2 = sv*p2x+uv*p2y-lv*tb_project_to_sphere(TRACKBALLSIZE,p2x,p2y);
/*
* Now, we want the cross product of P1 and P2
*/
// Robert,
//
// This was the quick 'n' dirty fix to get the trackball doing the right
// thing after fixing the Quat rotations to be right-handed. You may want
// to do something more elegant.
// axis = p1^p2;
axis = p2^p1;
axis.normalize();
/*
* Figure out how much to rotate around that axis.
*/
double t = (p2-p1).length() / (2.0*TRACKBALLSIZE);
/*
* Avoid problems with out-of-control values...
*/
if (t > 1.0) t = 1.0;
if (t < -1.0) t = -1.0;
angle = inRadians(asin(t));
}
/*
* Project an x,y pair onto a sphere of radius r OR a hyperbolic sheet
* if we are away from the center of the sphere.
*/
double TerrainManipulator::tb_project_to_sphere(double r, double x, double y)
{
float d, t, z;
d = sqrt(x*x + y*y);
/* Inside sphere */
if (d < r * 0.70710678118654752440)
{
z = sqrt(r*r - d*d);
} /* On hyperbola */
else
{
t = r / 1.41421356237309504880;
z = t*t / d;
}
return z;
}

View File

@ -1,488 +1,20 @@
#include <osgGA/TrackballManipulator>
#include <osg/Quat>
#include <osg/Notify>
#include <osg/BoundsChecking>
using namespace osg;
using namespace osgGA;
TrackballManipulator::TrackballManipulator()
{
_modelScale = 0.01f;
_minimumZoomScale = 0.05f;
_allowThrow = true;
_thrown = false;
_distance = 1.0f;
_trackballSize = 0.8f;
_zoomDelta = 0.1f;
/// Constructor.
TrackballManipulator::TrackballManipulator( int flags )
: inherited( flags )
{
setVerticalAxisFixed( false );
}
TrackballManipulator::~TrackballManipulator()
/// Constructor.
TrackballManipulator::TrackballManipulator( const TrackballManipulator& tm, const CopyOp& copyOp )
: inherited( tm, copyOp )
{
}
void TrackballManipulator::setNode(osg::Node* node)
{
_node = node;
if (_node.get())
{
const osg::BoundingSphere& boundingSphere=_node->getBound();
_modelScale = boundingSphere._radius;
}
if (getAutoComputeHomePosition()) computeHomePosition();
}
const osg::Node* TrackballManipulator::getNode() const
{
return _node.get();
}
osg::Node* TrackballManipulator::getNode()
{
return _node.get();
}
void TrackballManipulator::home(double /*currentTime*/)
{
if (getAutoComputeHomePosition()) computeHomePosition();
computePosition(_homeEye, _homeCenter, _homeUp);
_thrown = false;
}
void TrackballManipulator::home(const GUIEventAdapter& ea ,GUIActionAdapter& us)
{
home(ea.getTime());
us.requestRedraw();
us.requestContinuousUpdate(false);
}
void TrackballManipulator::init(const GUIEventAdapter& ,GUIActionAdapter& )
{
flushMouseEventStack();
}
void TrackballManipulator::getUsage(osg::ApplicationUsage& usage) const
{
usage.addKeyboardMouseBinding("Trackball: Space","Reset the viewing position to home");
usage.addKeyboardMouseBinding("Trackball: +","When in stereo, increase the fusion distance");
usage.addKeyboardMouseBinding("Trackball: -","When in stereo, reduce the fusion distance");
}
bool TrackballManipulator::handle(const GUIEventAdapter& ea,GUIActionAdapter& us)
{
switch(ea.getEventType())
{
case(GUIEventAdapter::FRAME):
{
double current_frame_time = ea.getTime();
_delta_frame_time = current_frame_time - _last_frame_time;
_last_frame_time = current_frame_time;
if (_thrown && _allowThrow)
{
if (calcMovement()) us.requestRedraw();
}
return false;
}
default:
break;
}
if (ea.getHandled()) return false;
switch(ea.getEventType())
{
case(GUIEventAdapter::PUSH):
{
flushMouseEventStack();
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
return true;
}
case(GUIEventAdapter::RELEASE):
{
if (ea.getButtonMask()==0)
{
double timeSinceLastRecordEvent = _ga_t0.valid() ? (ea.getTime() - _ga_t0->getTime()) : DBL_MAX;
if (timeSinceLastRecordEvent>0.02) flushMouseEventStack();
if (isMouseMoving())
{
if (calcMovement())
{
us.requestRedraw();
us.requestContinuousUpdate(true);
_thrown = _allowThrow;
}
}
else
{
flushMouseEventStack();
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
}
}
else
{
flushMouseEventStack();
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
}
return true;
}
case(GUIEventAdapter::DRAG):
case(GUIEventAdapter::SCROLL):
{
addMouseEvent(ea);
if (calcMovement()) us.requestRedraw();
us.requestContinuousUpdate(false);
_thrown = false;
return true;
}
case(GUIEventAdapter::MOVE):
{
return false;
}
case(GUIEventAdapter::KEYDOWN):
if (ea.getKey()== GUIEventAdapter::KEY_Space)
{
flushMouseEventStack();
_thrown = false;
home(ea,us);
return true;
}
return false;
case(GUIEventAdapter::FRAME):
if (_thrown)
{
if (calcMovement()) us.requestRedraw();
}
return false;
default:
return false;
}
}
bool TrackballManipulator::isMouseMoving()
{
if (_ga_t0.get()==NULL || _ga_t1.get()==NULL) return false;
static const float velocity = 0.1f;
float dx = _ga_t0->getXnormalized()-_ga_t1->getXnormalized();
float dy = _ga_t0->getYnormalized()-_ga_t1->getYnormalized();
float len = sqrtf(dx*dx+dy*dy);
float dt = _ga_t0->getTime()-_ga_t1->getTime();
return (len>dt*velocity);
}
void TrackballManipulator::flushMouseEventStack()
{
_ga_t1 = NULL;
_ga_t0 = NULL;
}
void TrackballManipulator::addMouseEvent(const GUIEventAdapter& ea)
{
_ga_t1 = _ga_t0;
_ga_t0 = &ea;
}
void TrackballManipulator::setByMatrix(const osg::Matrixd& matrix)
{
_center = osg::Vec3(0.0f,0.0f,-_distance)*matrix;
_rotation = matrix.getRotate();
}
osg::Matrixd TrackballManipulator::getMatrix() const
{
return osg::Matrixd::translate(0.0,0.0,_distance)*osg::Matrixd::rotate(_rotation)*osg::Matrixd::translate(_center);
}
osg::Matrixd TrackballManipulator::getInverseMatrix() const
{
return osg::Matrixd::translate(-_center)*osg::Matrixd::rotate(_rotation.inverse())*osg::Matrixd::translate(0.0,0.0,-_distance);
}
void TrackballManipulator::computePosition(const osg::Vec3& eye,const osg::Vec3& center,const osg::Vec3& up)
{
osg::Vec3 lv(center-eye);
osg::Vec3 f(lv);
f.normalize();
osg::Vec3 s(f^up);
s.normalize();
osg::Vec3 u(s^f);
u.normalize();
osg::Matrix rotation_matrix(s[0], u[0], -f[0], 0.0f,
s[1], u[1], -f[1], 0.0f,
s[2], u[2], -f[2], 0.0f,
0.0f, 0.0f, 0.0f, 1.0f);
_center = center;
_distance = lv.length();
_rotation = rotation_matrix.getRotate().inverse();
}
bool TrackballManipulator::calcMovement()
{
// mouse scroll is only a single event
if (_ga_t0.get()==NULL) return false;
float dx=0.0f;
float dy=0.0f;
unsigned int buttonMask=osgGA::GUIEventAdapter::NONE;
if (_ga_t0->getEventType()==GUIEventAdapter::SCROLL)
{
switch (_ga_t0->getScrollingMotion()) {
case osgGA::GUIEventAdapter::SCROLL_UP:
dy = _zoomDelta;
break;
case osgGA::GUIEventAdapter::SCROLL_DOWN:
dy = -_zoomDelta;
break;
case osgGA::GUIEventAdapter::SCROLL_LEFT:
case osgGA::GUIEventAdapter::SCROLL_RIGHT:
// pass
break;
case osgGA::GUIEventAdapter::SCROLL_2D:
// normalize scrolling delta
dx = _ga_t0->getScrollingDeltaX() / ((_ga_t0->getXmax()-_ga_t0->getXmin()) * 0.5f);
dy = _ga_t0->getScrollingDeltaY() / ((_ga_t0->getYmax()-_ga_t0->getYmin()) * 0.5f);
dx *= _zoomDelta;
dy *= _zoomDelta;
break;
default:
break;
}
buttonMask=GUIEventAdapter::SCROLL;
}
else
{
if (_ga_t1.get()==NULL) return false;
dx = _ga_t0->getXnormalized()-_ga_t1->getXnormalized();
dy = _ga_t0->getYnormalized()-_ga_t1->getYnormalized();
float distance = sqrtf(dx*dx + dy*dy);
// return if movement is too fast, indicating an error in event values or change in screen.
if (distance>0.5)
{
return false;
}
// return if there is no movement.
if (distance==0.0f)
{
return false;
}
buttonMask = _ga_t1->getButtonMask();
}
double throwScale = (_thrown && _ga_t0.valid() && _ga_t1.valid()) ?
_delta_frame_time / (_ga_t0->getTime() - _ga_t1->getTime()) :
1.0;
if (buttonMask==GUIEventAdapter::LEFT_MOUSE_BUTTON)
{
// rotate camera.
osg::Vec3 axis;
float angle;
float px0 = _ga_t0->getXnormalized();
float py0 = _ga_t0->getYnormalized();
float px1 = _ga_t1->getXnormalized();
float py1 = _ga_t1->getYnormalized();
trackball(axis,angle,px1,py1,px0,py0);
osg::Quat new_rotate;
new_rotate.makeRotate(angle * throwScale,axis);
_rotation = _rotation*new_rotate;
return true;
}
else if (buttonMask==GUIEventAdapter::MIDDLE_MOUSE_BUTTON ||
buttonMask==(GUIEventAdapter::LEFT_MOUSE_BUTTON|GUIEventAdapter::RIGHT_MOUSE_BUTTON))
{
// pan model.
float scale = -0.3f * _distance * throwScale;
osg::Matrix rotation_matrix;
rotation_matrix.makeRotate(_rotation);
osg::Vec3 dv(dx*scale,dy*scale,0.0f);
_center += dv*rotation_matrix;
return true;
}
else if ((buttonMask==GUIEventAdapter::RIGHT_MOUSE_BUTTON) || (buttonMask==GUIEventAdapter::SCROLL))
{
// zoom model.
float fd = _distance;
float scale = 1.0f+ dy * throwScale;
if (fd*scale>_modelScale*_minimumZoomScale)
{
_distance *= scale;
}
else
{
// notify(DEBUG_INFO) << "Pushing forward"<<std::endl;
// push the camera forward.
float scale = -fd;
osg::Matrix rotation_matrix(_rotation);
osg::Vec3 dv = (osg::Vec3(0.0f,0.0f,-1.0f)*rotation_matrix)*(dy*scale);
_center += dv;
}
return true;
}
return false;
}
/*
* This size should really be based on the distance from the center of
* rotation to the point on the object underneath the mouse. That
* point would then track the mouse as closely as possible. This is a
* simple example, though, so that is left as an Exercise for the
* Programmer.
*/
void TrackballManipulator::setTrackballSize(float size)
{
_trackballSize = size;
osg::clampBetweenRange(_trackballSize,0.1f,1.0f,"TrackballManipulator::setTrackballSize(float)");
}
/*
* Ok, simulate a track-ball. Project the points onto the virtual
* trackball, then figure out the axis of rotation, which is the cross
* product of P1 P2 and O P1 (O is the center of the ball, 0,0,0)
* Note: This is a deformed trackball-- is a trackball in the center,
* but is deformed into a hyperbolic sheet of rotation away from the
* center. This particular function was chosen after trying out
* several variations.
*
* It is assumed that the arguments to this routine are in the range
* (-1.0 ... 1.0)
*/
void TrackballManipulator::trackball(osg::Vec3& axis,float& angle, float p1x, float p1y, float p2x, float p2y)
{
/*
* First, figure out z-coordinates for projection of P1 and P2 to
* deformed sphere
*/
osg::Matrix rotation_matrix(_rotation);
osg::Vec3 uv = osg::Vec3(0.0f,1.0f,0.0f)*rotation_matrix;
osg::Vec3 sv = osg::Vec3(1.0f,0.0f,0.0f)*rotation_matrix;
osg::Vec3 lv = osg::Vec3(0.0f,0.0f,-1.0f)*rotation_matrix;
osg::Vec3 p1 = sv * p1x + uv * p1y - lv * tb_project_to_sphere(_trackballSize, p1x, p1y);
osg::Vec3 p2 = sv * p2x + uv * p2y - lv * tb_project_to_sphere(_trackballSize, p2x, p2y);
/*
* Now, we want the cross product of P1 and P2
*/
// Robert,
//
// This was the quick 'n' dirty fix to get the trackball doing the right
// thing after fixing the Quat rotations to be right-handed. You may want
// to do something more elegant.
// axis = p1^p2;
axis = p2^p1;
axis.normalize();
/*
* Figure out how much to rotate around that axis.
*/
float t = (p2 - p1).length() / (2.0 * _trackballSize);
/*
* Avoid problems with out-of-control values...
*/
if (t > 1.0) t = 1.0;
if (t < -1.0) t = -1.0;
angle = inRadians(asin(t));
}
/*
* Project an x,y pair onto a sphere of radius r OR a hyperbolic sheet
* if we are away from the center of the sphere.
*/
float TrackballManipulator::tb_project_to_sphere(float r, float x, float y)
{
float d, t, z;
d = sqrt(x*x + y*y);
/* Inside sphere */
if (d < r * 0.70710678118654752440)
{
z = sqrt(r*r - d*d);
} /* On hyperbola */
else
{
t = r / 1.41421356237309504880;
z = t*t / d;
}
return z;
}

View File

@ -112,7 +112,7 @@ void UFOManipulator::setByMatrix( const osg::Matrixd &mat )
_position.set( _inverseMatrix(3,0), _inverseMatrix(3,1), _inverseMatrix(3,2 ));
osg::Matrix R(_inverseMatrix);
R(3,0) = R(3,1) = R(3,2) = 0.0;
_direction = osg::Vec3(0,0,-1) * R; // camera up is +Z, regardless of CoordinateFrame
_direction = osg::Vec3d(0,0,-1) * R; // camera up is +Z, regardless of CoordinateFrame
_stop();
}
@ -125,7 +125,7 @@ void UFOManipulator::setByInverseMatrix( const osg::Matrixd &invmat)
_position.set( _inverseMatrix(3,0), _inverseMatrix(3,1), _inverseMatrix(3,2 ));
osg::Matrix R(_inverseMatrix);
R(3,0) = R(3,1) = R(3,2) = 0.0;
_direction = osg::Vec3(0,0,-1) * R; // camera up is +Z, regardless of CoordinateFrame
_direction = osg::Vec3d(0,0,-1) * R; // camera up is +Z, regardless of CoordinateFrame
_stop();
}
@ -155,8 +155,8 @@ void UFOManipulator::computeHomePosition()
osg::CoordinateFrame cf( getCoordinateFrame(bs.center()) ); // not sure what position to use here
osg::Vec3d upVec( getUpVector(cf) );
osg::Vec3 A = bs.center() + (upVec*(bs.radius()*2));
osg::Vec3 B = bs.center() + (-upVec*(bs.radius()*2));
osg::Vec3d A = bs.center() + (upVec*(bs.radius()*2));
osg::Vec3d B = bs.center() + (-upVec*(bs.radius()*2));
if( (B-A).length() == 0.0)
{
@ -180,7 +180,7 @@ void UFOManipulator::computeHomePosition()
}
osg::Vec3 p(bs.center() + upVec*( ground + _minHeightAboveGround*1.25 ) );
osg::Vec3d p(bs.center() + upVec*( ground + _minHeightAboveGround*1.25 ) );
setHomePosition( p, p + getFrontVector(cf), upVec );
}
@ -462,7 +462,7 @@ void UFOManipulator::_frame( const osgGA::GUIEventAdapter &ea, osgGA::GUIActionA
}
{
osg::Vec3 _sideVec = _direction * osg::Matrix::rotate( -M_PI*0.5, upVec);
osg::Vec3d _sideVec = _direction * osg::Matrix::rotate( -M_PI*0.5, upVec);
_position += ((_direction * _forwardSpeed) +
(_sideVec * _sideSpeed) +
@ -577,7 +577,7 @@ void UFOManipulator::_stop()
_directionRotationRate = 0.0;
}
void UFOManipulator::getCurrentPositionAsLookAt( osg::Vec3 &eye, osg::Vec3 &center, osg::Vec3 &up )
void UFOManipulator::getCurrentPositionAsLookAt( osg::Vec3d& eye, osg::Vec3d& center, osg::Vec3d& up )
{
eye = _position;
center = _position + _direction;