|
osgEarth 2.1.1
|
Collaboration diagram for osgEarth::Util::EarthManipulator:Classes | |
| struct | Action |
| struct | ActionOption |
| struct | ActionOptions |
| struct | CameraPostUpdateCallback |
| struct | InputSpec |
| class | Settings |
| struct | Task |
Public Types | |
| enum | ActionType { ACTION_NULL, ACTION_HOME, ACTION_GOTO, ACTION_PAN, ACTION_PAN_LEFT, ACTION_PAN_RIGHT, ACTION_PAN_UP, ACTION_PAN_DOWN, ACTION_ROTATE, ACTION_ROTATE_LEFT, ACTION_ROTATE_RIGHT, ACTION_ROTATE_UP, ACTION_ROTATE_DOWN, ACTION_ZOOM, ACTION_ZOOM_IN, ACTION_ZOOM_OUT, ACTION_EARTH_DRAG } |
| enum | EventType { EVENT_MOUSE_CLICK = osgGA::GUIEventAdapter::USER << 1, EVENT_MOUSE_DOUBLE_CLICK = osgGA::GUIEventAdapter::DOUBLECLICK, EVENT_MOUSE_DRAG = osgGA::GUIEventAdapter::DRAG, EVENT_KEY_DOWN = osgGA::GUIEventAdapter::KEYDOWN, EVENT_SCROLL = osgGA::GUIEventAdapter::SCROLL } |
| enum | MouseEvent { MOUSE_LEFT_BUTTON = osgGA::GUIEventAdapter::LEFT_MOUSE_BUTTON, MOUSE_MIDDLE_BUTTON = osgGA::GUIEventAdapter::MIDDLE_MOUSE_BUTTON, MOUSE_RIGHT_BUTTON = osgGA::GUIEventAdapter::RIGHT_MOUSE_BUTTON } |
| enum | ActionOptionType { OPTION_SCALE_X, OPTION_SCALE_Y, OPTION_CONTINUOUS, OPTION_SINGLE_AXIS, OPTION_GOTO_RANGE_FACTOR, OPTION_DURATION } |
| enum | TetherMode { TETHER_CENTER, TETHER_CENTER_AND_ROTATION, TETHER_CENTER_AND_HEADING } |
Public Member Functions | |
| EarthManipulator () | |
| EarthManipulator (const EarthManipulator &rhs) | |
| void | applySettings (Settings *settings) |
| Settings * | getSettings () const |
| Viewpoint | getViewpoint () const |
| virtual void | setViewpoint (const Viewpoint &vp, double duration_s=0.0) |
| void | setHomeViewpoint (const Viewpoint &vp, double duration_s=0.0) |
| void | setTetherNode (osg::Node *node) |
| osg::Node * | getTetherNode () const |
| const osgEarth::SpatialReference * | getSRS () const |
| virtual void | pan (double dx, double dy) |
| virtual void | rotate (double dx, double dy) |
| virtual void | zoom (double dx, double dy) |
| virtual void | drag (double dx, double dy, osg::View *view) |
| bool | screenToWorld (float x, float y, osg::View *view, osg::Vec3d &out_coords) const |
| double | getDistance () const |
| void | setDistance (double distance) |
| const osg::Quat & | getRotation () |
| void | setRotation (const osg::Quat &rotation) |
| virtual const char * | className () const |
| 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 osgUtil::SceneView::FusionDistanceMode | getFusionDistanceMode () const |
| virtual float | getFusionDistanceValue () const |
| virtual void | setNode (osg::Node *) |
| virtual osg::Node * | getNode () |
| virtual void | home (const osgGA::GUIEventAdapter &ea, osgGA::GUIActionAdapter &us) |
| 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 |
| virtual void | computeHomePosition () |
Protected Member Functions | |
| virtual | ~EarthManipulator () |
| bool | intersect (const osg::Vec3d &start, const osg::Vec3d &end, osg::Vec3d &intersection) const |
| void | resetMouse (osgGA::GUIActionAdapter &) |
| void | flushMouseEventStack () |
| void | addMouseEvent (const osgGA::GUIEventAdapter &ea) |
| void | setByLookAt (const osg::Vec3d &eye, const osg::Vec3d &lv, const osg::Vec3d &up) |
| bool | handleAction (const Action &action, double dx, double dy, double duration) |
| bool | handleMouseAction (const Action &action, osg::View *view) |
| bool | handleMouseClickAction (const Action &action) |
| bool | handleKeyboardAction (const Action &action, double duration_s=DBL_MAX) |
| bool | handleScrollAction (const Action &action, double duration_s=DBL_MAX) |
| bool | handlePointAction (const Action &type, float mx, float my, osg::View *view) |
| void | handleContinuousAction (const Action &action, osg::View *view) |
| void | handleMovementAction (const ActionType &type, double dx, double dy, osg::View *view) |
| bool | isMouseMoving () |
| void | recalculateRoll () |
Private Types | |
| enum | Direction { DIR_NA, DIR_LEFT, DIR_RIGHT, DIR_UP, DIR_DOWN } |
| enum | TaskType { TASK_NONE, TASK_PAN, TASK_ROTATE, TASK_ZOOM } |
| typedef std::list< InputSpec > | InputSpecs |
Private Member Functions | |
| void | dumpActionInfo (const Action &action, osg::NotifySeverity level) const |
| bool | serviceTask () |
| void | recalculateLocalPitchAndAzimuth () |
| double | getAzimuth () const |
| void | recalculateCenter (const osg::CoordinateFrame &frame) |
| osg::Matrixd | getRotation (const osg::Vec3d ¢er) const |
| osg::Quat | makeCenterRotation (const osg::Vec3d ¢er) const |
| void | updateTether () |
| void | updateSetViewpoint () |
| void | updateHandCam (const osg::Timer_t &now) |
| bool | isMouseClick (const osgGA::GUIEventAdapter *mouse_up_event) const |
| void | applyOptionsToDeltas (const Action &action, double &dx, double &dy) |
| void | configureDefaultSettings () |
| void | reinitialize () |
| bool | established () |
| osg::CoordinateFrame | getMyCoordinateFrame (const osg::Vec3d &position) const |
| void | postUpdate () |
| void | updateCamera (osg::Camera *eventCamera) |
Private Attributes | |
| osg::ref_ptr< const osgGA::GUIEventAdapter > | _ga_t1 |
| osg::ref_ptr< const osgGA::GUIEventAdapter > | _ga_t0 |
| osg::ref_ptr< const osgGA::GUIEventAdapter > | _mouse_down_event |
| osg::observer_ptr< osg::Node > | _node |
| osg::observer_ptr < osg::CoordinateSystemNode > | _csn |
| osg::NodePath | _csnPath |
| osg::ref_ptr< const osgEarth::SpatialReference > | _cached_srs |
| bool | _is_geocentric |
| bool | _srs_lookup_failed |
| osg::observer_ptr< osg::Node > | _tether_node |
| double | _time_s_last_frame |
| double | _time_s_now |
| osg::Timer_t | _now |
| double | _delta_t |
| double | _t_factor |
| bool | _thrown |
| osg::Vec3d | _center |
| osg::Quat | _rotation |
| osg::Quat | _centerRotation |
| double | _distance |
| double | _offset_x |
| double | _offset_y |
| osg::Vec3d | _previousUp |
| osg::ref_ptr< Task > | _task |
| osg::Timer_t | _time_last_frame |
| double | _local_pitch |
| double | _local_azim |
| bool | _continuous |
| double | _continuous_dx |
| double | _continuous_dy |
| double | _single_axis_x |
| double | _single_axis_y |
| bool | _has_pending_viewpoint |
| Viewpoint | _pending_viewpoint |
| double | _pending_viewpoint_duration_s |
| bool | _setting_viewpoint |
| Viewpoint | _start_viewpoint |
| double | _delta_heading |
| double | _delta_pitch |
| double | _delta_range |
| double | _arc_height |
| osg::Vec3d | _delta_focal_point |
| double | _time_s_set_viewpoint |
| double | _set_viewpoint_duration_s |
| double | _set_viewpoint_accel |
| double | _set_viewpoint_accel_2 |
| bool | _after_first_frame |
| osg::ref_ptr< Settings > | _settings |
| osgEarth::optional< Viewpoint > | _homeViewpoint |
| double | _homeViewpointDuration |
| Action | _last_action |
| osg::observer_ptr< osg::Camera > | _viewCamera |
| osg::observer_ptr < CameraPostUpdateCallback > | _cameraUpdateCB |
| osg::Vec3d | _lastPointOnEarth |
Static Private Attributes | |
| static Action | NullAction |
Friends | |
| struct | CameraUpdateCallback |
A programmable manipulator suitable for use with geospatial terrains.
You can use the "Settings" class to define custom input device bindings and navigation parameters. Create one or more of these and call applySettings() to "program" the manipulator at runtime.
Definition at line 40 of file EarthManipulator.
typedef std::list<InputSpec> osgEarth::Util::EarthManipulator::InputSpecs [private] |
Definition at line 152 of file EarthManipulator.
Action options. Certain options are only meaningful to certain Actions. See the bind* documentation for information.
| OPTION_SCALE_X | |
| OPTION_SCALE_Y | |
| OPTION_CONTINUOUS | |
| OPTION_SINGLE_AXIS | |
| OPTION_GOTO_RANGE_FACTOR | |
| OPTION_DURATION |
Definition at line 83 of file EarthManipulator.
{
OPTION_SCALE_X, // Sensitivity multiplier for horizontal input movements
OPTION_SCALE_Y, // Sensitivity multiplier for vertical input movements
OPTION_CONTINUOUS, // Whether to act as long as the button or key is depressed
OPTION_SINGLE_AXIS, // If true, only operate on one axis at a time (the one with the larger value)
OPTION_GOTO_RANGE_FACTOR, // for ACTION_GOTO, multiply the Range by this factor (to zoom in/out)
OPTION_DURATION // Time it takes to complete the action (in seconds)
};
Bindable manipulator actions.
Definition at line 45 of file EarthManipulator.
enum osgEarth::Util::EarthManipulator::Direction [private] |
Bindable event types.
Definition at line 66 of file EarthManipulator.
{
EVENT_MOUSE_CLICK = osgGA::GUIEventAdapter::USER << 1,
EVENT_MOUSE_DOUBLE_CLICK = osgGA::GUIEventAdapter::DOUBLECLICK,
EVENT_MOUSE_DRAG = osgGA::GUIEventAdapter::DRAG,
EVENT_KEY_DOWN = osgGA::GUIEventAdapter::KEYDOWN,
EVENT_SCROLL = osgGA::GUIEventAdapter::SCROLL
};
Bindable mouse buttons.
Definition at line 75 of file EarthManipulator.
{
MOUSE_LEFT_BUTTON = osgGA::GUIEventAdapter::LEFT_MOUSE_BUTTON,
MOUSE_MIDDLE_BUTTON = osgGA::GUIEventAdapter::MIDDLE_MOUSE_BUTTON,
MOUSE_RIGHT_BUTTON = osgGA::GUIEventAdapter::RIGHT_MOUSE_BUTTON
};
enum osgEarth::Util::EarthManipulator::TaskType [private] |
Definition at line 685 of file EarthManipulator.
{
TASK_NONE,
TASK_PAN,
TASK_ROTATE,
TASK_ZOOM
};
Tethering options
Definition at line 93 of file EarthManipulator.
{
TETHER_CENTER, // The camera will follow the center of the node.
TETHER_CENTER_AND_ROTATION, // The camera will follow the node and all rotations made by the node
TETHER_CENTER_AND_HEADING // The camera will follow the node and only follow heading rotation
};
| EarthManipulator::EarthManipulator | ( | ) |
Definition at line 399 of file EarthManipulator.cpp.
: _last_action( ACTION_NULL ) { reinitialize(); configureDefaultSettings(); }
Here is the call graph for this function:| EarthManipulator::EarthManipulator | ( | const EarthManipulator & | rhs | ) |
Definition at line 406 of file EarthManipulator.cpp.
: _thrown( rhs._thrown ), _distance( rhs._distance ), _offset_x( rhs._offset_x ), _offset_y( rhs._offset_y ), _continuous( rhs._continuous ), _task( new Task() ), _settings( new Settings( *rhs._settings.get() ) ), _srs_lookup_failed( rhs._srs_lookup_failed ), _last_action( rhs._last_action ), _setting_viewpoint( rhs._setting_viewpoint ), _delta_t( rhs._delta_t ), _t_factor( rhs._t_factor ), _time_s_last_frame( rhs._time_s_last_frame ), _local_azim( rhs._local_azim ), _local_pitch( rhs._local_pitch ), _has_pending_viewpoint( rhs._has_pending_viewpoint ), _homeViewpoint( rhs._homeViewpoint.get() ), _homeViewpointDuration( rhs._homeViewpointDuration ), _after_first_frame( rhs._after_first_frame ), _lastPointOnEarth( rhs._lastPointOnEarth ), _arc_height( rhs._arc_height ) { }
| EarthManipulator::~EarthManipulator | ( | ) | [protected, virtual] |
Definition at line 432 of file EarthManipulator.cpp.
{
//NOP
}
| void EarthManipulator::addMouseEvent | ( | const osgGA::GUIEventAdapter & | ea | ) | [protected] |
| void EarthManipulator::applyOptionsToDeltas | ( | const Action & | action, |
| double & | dx, | ||
| double & | dy | ||
| ) | [private] |
Definition at line 1989 of file EarthManipulator.cpp.
{
dx *= action.getDoubleOption( OPTION_SCALE_X, 1.0 );
dy *= action.getDoubleOption( OPTION_SCALE_Y, 1.0 );
if ( action.getBoolOption( OPTION_SINGLE_AXIS, false ) == true )
{
if ( osg::absolute(dx) > osg::absolute(dy) )
dy = 0.0;
else
dx = 0.0;
}
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::applySettings | ( | Settings * | settings | ) |
Applies a new settings object to the manipulator, which takes effect immediately.
Definition at line 485 of file EarthManipulator.cpp.
{
if ( settings )
{
_settings = settings;
}
else
{
configureDefaultSettings();
}
_task->_type = TASK_NONE;
flushMouseEventStack();
// apply new pitch restrictions
double old_pitch = osg::RadiansToDegrees( _local_pitch );
double new_pitch = osg::clampBetween( old_pitch, _settings->getMinPitch(), _settings->getMaxPitch() );
setDistance(_distance);
if ( new_pitch != old_pitch )
{
Viewpoint vp = getViewpoint();
setViewpoint( Viewpoint(vp.getFocalPoint(), vp.getHeading(), new_pitch, vp.getRange(), vp.getSRS()) );
}
}
Here is the call graph for this function:| virtual const char* osgEarth::Util::EarthManipulator::className | ( | ) | const [inline, virtual] |
Definition at line 605 of file EarthManipulator.
{ return "EarthManipulator"; }
| void EarthManipulator::computeHomePosition | ( | ) | [virtual] |
Definition at line 1094 of file EarthManipulator.cpp.
{
if( getNode() )
{
const osg::BoundingSphere& boundingSphere = getNode()->getBound();
osg::Vec3d eye =
boundingSphere._center +
osg::Vec3( 0.0, -3.5f * boundingSphere._radius, boundingSphere._radius * 0.0001 );
setHomePosition(
eye,
boundingSphere._center,
osg::Vec3d( 0, 0, 1 ),
_autoComputeHomePosition );
}
}
Here is the call graph for this function:| void EarthManipulator::configureDefaultSettings | ( | ) | [private] |
Definition at line 438 of file EarthManipulator.cpp.
{
_settings = new Settings();
// install default action bindings:
ActionOptions options;
_settings->bindKey( ACTION_HOME, osgGA::GUIEventAdapter::KEY_Space );
_settings->bindMouse( ACTION_PAN, osgGA::GUIEventAdapter::LEFT_MOUSE_BUTTON );
//_settings->bindMouse( ACTION_EARTH_DRAG, osgGA::GUIEventAdapter::LEFT_MOUSE_BUTTON );
// zoom as you hold the right button:
options.clear();
options.add( OPTION_CONTINUOUS, true );
_settings->bindMouse( ACTION_ZOOM, osgGA::GUIEventAdapter::RIGHT_MOUSE_BUTTON, 0L, options );
// rotate with either the middle button or the left+right buttons:
_settings->bindMouse( ACTION_ROTATE, osgGA::GUIEventAdapter::MIDDLE_MOUSE_BUTTON );
_settings->bindMouse( ACTION_ROTATE, osgGA::GUIEventAdapter::LEFT_MOUSE_BUTTON | osgGA::GUIEventAdapter::RIGHT_MOUSE_BUTTON );
// zoom with the scroll wheel:
_settings->bindScroll( ACTION_ZOOM_IN, osgGA::GUIEventAdapter::SCROLL_DOWN );
_settings->bindScroll( ACTION_ZOOM_OUT, osgGA::GUIEventAdapter::SCROLL_UP );
// pan around with arrow keys:
_settings->bindKey( ACTION_PAN_LEFT, osgGA::GUIEventAdapter::KEY_Left );
_settings->bindKey( ACTION_PAN_RIGHT, osgGA::GUIEventAdapter::KEY_Right );
_settings->bindKey( ACTION_PAN_UP, osgGA::GUIEventAdapter::KEY_Up );
_settings->bindKey( ACTION_PAN_DOWN, osgGA::GUIEventAdapter::KEY_Down );
// double click the left button to zoom in on a point:
options.clear();
options.add( OPTION_GOTO_RANGE_FACTOR, 0.4 );
_settings->bindMouseDoubleClick( ACTION_GOTO, osgGA::GUIEventAdapter::LEFT_MOUSE_BUTTON, 0L, options );
// double click the right button (or CTRL-left button) to zoom out to a point
options.clear();
options.add( OPTION_GOTO_RANGE_FACTOR, 2.5 );
_settings->bindMouseDoubleClick( ACTION_GOTO, osgGA::GUIEventAdapter::RIGHT_MOUSE_BUTTON, 0L, options );
_settings->bindMouseDoubleClick( ACTION_GOTO, osgGA::GUIEventAdapter::LEFT_MOUSE_BUTTON, osgGA::GUIEventAdapter::MODKEY_CTRL, options );
_settings->setThrowingEnabled( false );
_settings->setLockAzimuthWhilePanning( true );
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::drag | ( | double | dx, |
| double | dy, | ||
| osg::View * | view | ||
| ) | [virtual] |
Drag the earth using deltas
Definition at line 2372 of file EarthManipulator.cpp.
{
using namespace osg;
const osg::Vec3d zero(0.0, 0.0, 0.0);
if (_last_action._type != ACTION_EARTH_DRAG)
_lastPointOnEarth = zero;
ref_ptr<osg::CoordinateSystemNode> csnSafe = _csn.get();
double radiusEquator = csnSafe.valid() ? csnSafe->getEllipsoidModel()->getRadiusEquator() : 6378137.0;
osgViewer::View* view = dynamic_cast<osgViewer::View*>(theView);
float x = _ga_t0->getX(), y = _ga_t0->getY();
float local_x, local_y;
const osg::Camera* camera
= view->getCameraContainingPosition(x, y, local_x, local_y);
if (!camera)
camera = view->getCamera();
osg::Matrix viewMat = camera->getViewMatrix();
osg::Matrix viewMatInv = camera->getInverseViewMatrix();
if (!_ga_t1.valid())
return;
osg::Vec3d worldStartDrag;
// drag start in camera coordinate system.
bool onEarth;
if ((onEarth = screenToWorld(_ga_t1->getX(), _ga_t1->getY(),
view, worldStartDrag)))
{
if (_lastPointOnEarth == zero)
_lastPointOnEarth = worldStartDrag;
else
worldStartDrag = _lastPointOnEarth;
}
else if (_is_geocentric)
{
if (_lastPointOnEarth != zero)
{
worldStartDrag =_lastPointOnEarth;
}
else if (csnSafe.valid())
{
const osg::Vec3d startWinPt = getWindowPoint(view, _ga_t1->getX(),
_ga_t1->getY());
const osg::Vec3d startDrag = calcTangentPoint(
zero, zero * viewMat, radiusEquator,
startWinPt);
worldStartDrag = startDrag * viewMatInv;
}
}
else
return;
// ray from eye through pointer in camera coordinate system goes
// from origin through transformed pointer coordinates
const osg::Vec3d winpt = getWindowPoint(view, x, y);
// Find new point to which startDrag has been moved
osg::Vec3d worldEndDrag;
osg::Quat worldRot;
bool endOnEarth = screenToWorld(x, y, view, worldEndDrag);
if (endOnEarth)
{
// OE_WARN << "end drag: " << worldEndDrag << "\n";
}
else
{
Vec3d earthOrigin = zero * viewMat;
const osg::Vec3d endDrag = calcTangentPoint(
zero, earthOrigin, radiusEquator, winpt);
worldEndDrag = endDrag * viewMatInv;
OE_INFO << "tangent: " << worldEndDrag << "\n";
}
#if 0
if (onEarth != endOnEarth)
{
std::streamsize oldPrecision = osgEarth::notify(INFO).precision(10);
OE_INFO << (onEarth ? "leaving earth\n" : "entering earth\n");
OE_INFO << "start drag: " << worldStartDrag.x() << " "
<< worldStartDrag.y() << " "
<< worldStartDrag.z() << "\n";
OE_INFO << "end drag: " << worldEndDrag.x() << " "
<< worldEndDrag.y() << " "
<< worldEndDrag.z() << "\n";
osgEarth::notify(INFO).precision(oldPrecision);
}
#endif
if (_is_geocentric)
{
worldRot.makeRotate(worldStartDrag, worldEndDrag);
// Move the camera by the inverse rotation
Quat cameraRot = worldRot.conj();
// Derive manipulator parameters from the camera matrix. We
// can't use _center, _centerRotation, and _rotation directly
// from the manipulator because they may have been updated
// already this frame while the camera view matrix,
// used to do the terrain intersection, has not. This happens
// when several mouse movement events arrive in a frame. there
// will be bad stuttering artifacts if we use the updated
// manipulator parameters.
Matrixd Mmanip = Matrixd::translate(_offset_x, _offset_y, -_distance)
* viewMatInv;
Vec3d center = Mmanip.getTrans();
Quat centerRotation = makeCenterRotation(center);
Matrixd Mrotation = (Mmanip * Matrixd::translate(center * -1)
* Matrixd::rotate(centerRotation.inverse()));
Matrixd Me = Matrixd::rotate(centerRotation)
* Matrixd::translate(center) * Matrixd::rotate(cameraRot);
// In order for the Viewpoint settings to make sense, the
// inverse camera matrix must not have a roll component, which
// implies that its x axis remains parallel to the
// z = 0 plane. The strategy for doing that is different if
// the azimuth is locked.
// Additionally, the part of the camera rotation defined by
// _centerRotation must be oriented with the local frame of
// _center on the ellipsoid. For the purposes of the drag
// motion this is nearly identical to the frame obtained by
// the trackball motion, so we just fix it up at the end.
if (_settings->getLockAzimuthWhilePanning())
{
// The camera needs to be rotated that _centerRotation
// is a rotation only around the global Z axis and the
// camera frame X axis. We don't change _rotation, so that
// azimuth and pitch will stay constant, but the drag must
// still be correct i.e., the point dragged must remain
// under the cursor. Therefore the rotation must be around the
// point that was dragged, worldEndDrag.
//
// Rotate Me so that its x axis is parallel to the z=0
// plane.
// Find cone with worldEndDrag->center axis and x
// axis of coordinate frame as generator of the conical
// surface.
Vec3d coneAxis = worldEndDrag * -1;
coneAxis.normalize();
Vec3d xAxis(Me(0, 0), Me(0, 1), Me(0, 2));
// Center of disk: project xAxis onto coneAxis
double diskDist = xAxis * coneAxis;
Vec3d P1 = coneAxis * diskDist;
// Basis of disk equation:
// p = P1 + R * r * cos(theta) + S * r * sin(theta)
Vec3d R = xAxis - P1;
Vec3d S = R ^ coneAxis;
double r = R.normalize();
S.normalize();
// Solve for angle that rotates xAxis into z = 0 plane.
// soln to 0 = P1.z + r cos(theta) R.z + r sin(theta) S.z
double temp1 = r * (square(S.z()) + square(R.z()));
if (equivalent(temp1, 0.0))
return;
double radical = r * temp1 - square(P1.z());
if (radical < 0)
return;
double temp2 = R.z() * sqrt(radical) / temp1;
double temp3 = S.z() * P1.z() / temp1;
double sin1 = temp2 + temp3;
double sin2 = temp2 - temp3;
double theta1 = DBL_MAX;
double theta2 = DBL_MAX;
Matrixd cm1, cm2;
if (fabs(sin1) <= 1.0)
{
theta1 = -asin(sin1);
Matrixd m = rotateAroundPoint(worldEndDrag, -theta1, coneAxis);
cm1 = Me * m;
}
if (fabs(sin2) <= 1.0)
{
theta2 = asin(sin2);
Matrix m = rotateAroundPoint(worldEndDrag, -theta2, coneAxis);
cm2 = Me * m;
}
if (theta1 == DBL_MAX && theta2 == DBL_MAX)
return;
Matrixd* CameraMat = 0;
if (theta1 != DBL_MAX && cm1(1, 2) >= 0.0)
CameraMat = &cm1;
else if (theta2 != DBL_MAX && cm2(1, 2) >= 0.0)
CameraMat = &cm2;
else
return;
_center = CameraMat->getTrans();
}
else
{
// The camera matrix must be rotated around the local Z axis so
// that the X axis is parallel to the global z = 0
// plane. Then, _rotation is rotated by the inverse
// rotation to preserve the total transformation.
double theta = atan2(-Me(0, 2), Me(1, 2));
double s = sin(theta), c = cos(theta);
if (c * Me(1, 2) - s * Me(0, 2) < 0.0)
{
s = -s;
c = -c;
}
Matrixd m(c, s, 0, 0,
-s, c, 0, 0,
0, 0, 1, 0,
0, 0, 0, 1);
Matrixd CameraMat = m * Me;
_center = CameraMat.getTrans();
// It's not necessary to include the translation
// component, but it's useful for debugging.
Matrixd headMat
= (Matrixd::translate(-_offset_x, -_offset_y, _distance)
* Mrotation);
headMat = headMat * Matrixd::inverse(m);
_rotation = headMat.getRotate();
recalculateLocalPitchAndAzimuth();
}
_centerRotation = makeCenterRotation(_center);
CoordinateFrame local_frame = getMyCoordinateFrame(_center);
_previousUp = getUpVector(local_frame);
}
else
{
// This is obviously not correct.
_center = _center + (worldStartDrag - worldEndDrag);
}
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::dumpActionInfo | ( | const Action & | action, |
| osg::NotifySeverity | level | ||
| ) | const [private] |
Definition at line 1896 of file EarthManipulator.cpp.
{
osgEarth::notify(level) << "action: " << s_actionNames[action._type] << "; options: ";
for( ActionOptions::const_iterator i = action._options.begin(); i != action._options.end(); ++i )
{
const ActionOption& option = *i;
std::string val;
if ( s_actionOptionTypes[option.option()] == 0 )
val = option.boolValue() ? "true" : "false";
else
val = toString<double>(option.doubleValue());
osgEarth::notify(level)
<< s_actionOptionNames[option.option()] << "=" << val << ", ";
}
osgEarth::notify(level) << std::endl;
}
Here is the call graph for this function:| bool EarthManipulator::established | ( | ) | [private] |
Definition at line 539 of file EarthManipulator.cpp.
{
#ifdef USE_OBSERVER_NODE_PATH
bool needToReestablish = (!_csn.valid() || _csnObserverPath.empty()) && _node.valid();
#else
bool needToReestablish = !_csn.valid() && _node.valid();
#endif
if ( needToReestablish )
{
osg::ref_ptr<osg::Node> safeNode = _node.get();
if ( !safeNode.valid() )
return false;
// check the kids, then the parents
osg::ref_ptr<osg::CoordinateSystemNode> csn = osgEarth::findTopMostNodeOfType<osg::CoordinateSystemNode>( safeNode.get() );
if ( !csn.valid() )
csn = osgEarth::findFirstParentOfType<osg::CoordinateSystemNode>( safeNode.get() );
if ( csn.valid() )
{
_csn = csn.get();
_node = csn.get();
#if USE_OBSERVER_NODE_PATH
_csnObserverPath.setNodePathTo( csn.get() );
#endif
if ( !_homeViewpoint.isSet() )
{
if ( _has_pending_viewpoint )
{
setHomeViewpoint(
_pending_viewpoint,
_pending_viewpoint_duration_s );
_has_pending_viewpoint = false;
}
//If we have a CoordinateSystemNode and it has an ellipsoid model
if ( csn->getEllipsoidModel() )
{
setHomeViewpoint(
Viewpoint(osg::Vec3d(-90,0,0), 0, -89,
csn->getEllipsoidModel()->getRadiusEquator()*3.0 ) );
}
else
{
setHomeViewpoint( Viewpoint(
safeNode->getBound().center(),
0, -89.9,
safeNode->getBound().radius()*2.0) );
}
}
if ( !_has_pending_viewpoint )
setViewpoint( _homeViewpoint.get(), _homeViewpointDuration );
else
setViewpoint( _pending_viewpoint, _pending_viewpoint_duration_s );
_has_pending_viewpoint = false;
}
//if (getAutoComputeHomePosition()) computeHomePosition();
// reset the srs cache:
_cached_srs = NULL;
_srs_lookup_failed = false;
// track the local angles.
recalculateLocalPitchAndAzimuth();
//OE_DEBUG << "[EarthManip] new CSN established." << std::endl;
}
return _csn.valid() && _node.valid();
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::flushMouseEventStack | ( | ) | [protected] |
| double EarthManipulator::getAzimuth | ( | ) | const [private] |
Definition at line 2181 of file EarthManipulator.cpp.
{
osg::Matrix m = getMatrix() * osg::Matrixd::inverse( getMyCoordinateFrame( _center ) ); //getCoordinateFrame( _center ) );
osg::Vec3d look = -getUpVector( m ); // -m(2,0), -m(2,1), -m(2,2)
osg::Vec3d up = getFrontVector( m );
//osg::Vec3d look( -m(2,0), -m(2,1), -m(2,2) );
look.normalize();
up.normalize();
double azim;
if ( look.z() < -0.9 )
azim = atan2( up.x(), up.y() );
else if ( look.z() > 0.9 )
azim = atan2( -up.x(), -up.y() );
else
azim = atan2( look.x(), look.y() );
return normalizeAzimRad( azim );
}
Here is the call graph for this function:
Here is the caller graph for this function:| double osgEarth::Util::EarthManipulator::getDistance | ( | ) | const [inline] |
Gets the distance from the focal point in world coordiantes
Definition at line 583 of file EarthManipulator.
{ return _distance; }
| virtual osgUtil::SceneView::FusionDistanceMode osgEarth::Util::EarthManipulator::getFusionDistanceMode | ( | ) | const [inline, virtual] |
Definition at line 620 of file EarthManipulator.
{ return osgUtil::SceneView::USE_FUSION_DISTANCE_VALUE; }
| virtual float osgEarth::Util::EarthManipulator::getFusionDistanceValue | ( | ) | const [inline, virtual] |
Definition at line 623 of file EarthManipulator.
{ return _distance; }
| osg::Matrixd EarthManipulator::getInverseMatrix | ( | ) | const [virtual] |
get the position of the manipulator as a inverse matrix of the manipulator, typically used as a model view matrix.
Definition at line 1588 of file EarthManipulator.cpp.
{
return osg::Matrixd::translate(-_center)*
osg::Matrixd::rotate(_centerRotation.inverse() ) *
osg::Matrixd::rotate(_rotation.inverse())*
osg::Matrixd::translate(_offset_x,_offset_y,-_distance);
}
Here is the call graph for this function:| osg::Matrixd EarthManipulator::getMatrix | ( | ) | const [virtual] |
get the position of the manipulator as 4x4 Matrix.
Definition at line 1579 of file EarthManipulator.cpp.
{
return osg::Matrixd::translate(-_offset_x,-_offset_y,_distance)*
osg::Matrixd::rotate(_rotation)*
osg::Matrixd::rotate(_centerRotation)*
osg::Matrixd::translate(_center);
}
Here is the call graph for this function:
Here is the caller graph for this function:| osg::CoordinateFrame EarthManipulator::getMyCoordinateFrame | ( | const osg::Vec3d & | position | ) | const [private] |
Definition at line 621 of file EarthManipulator.cpp.
{
osg::CoordinateFrame coordinateFrame;
osg::ref_ptr<osg::CoordinateSystemNode> csnSafe = _csn.get();
if ( csnSafe.valid() )
{
#ifdef USE_OBSERVER_NODE_PATH
if ( _csnObserverPath.empty() )
{
const_cast<EarthManipulator*>(this)->_csnObserverPath.setNodePathTo( csnSafe.get() );
_csnObserverPath.getNodePath( const_cast<EarthManipulator*>(this)->_csnPath );
}
#else
const_cast<EarthManipulator*>(this)->_csnPath = csnSafe->getParentalNodePaths()[0];
#endif
osg::Vec3 local_position = position * osg::computeWorldToLocal( _csnPath );
// get the coordinate frame in world coords.
coordinateFrame = csnSafe->computeLocalCoordinateFrame( local_position ) * osg::computeLocalToWorld( _csnPath );
// keep the position of the coordinate frame to reapply after rescale.
osg::Vec3d pos = coordinateFrame.getTrans();
// compensate for any scaling, so that the coordinate frame is a unit size
osg::Vec3d x(1.0,0.0,0.0);
osg::Vec3d y(0.0,1.0,0.0);
osg::Vec3d z(0.0,0.0,1.0);
x = osg::Matrixd::transform3x3(x,coordinateFrame);
y = osg::Matrixd::transform3x3(y,coordinateFrame);
z = osg::Matrixd::transform3x3(z,coordinateFrame);
coordinateFrame.preMultScale( osg::Vec3d(1.0/x.length(),1.0/y.length(),1.0/z.length()) );
// reapply the position.
coordinateFrame.setTrans( pos );
}
else
{
coordinateFrame = osg::computeLocalToWorld( _csnPath );
}
return coordinateFrame;
}
Here is the caller graph for this function:| osg::Node * EarthManipulator::getNode | ( | ) | [virtual] |
Definition at line 689 of file EarthManipulator.cpp.
{
return _node.get();
}
Here is the caller graph for this function:| const osg::Quat& osgEarth::Util::EarthManipulator::getRotation | ( | ) | [inline] |
Gets the rotation of the manipulator. Note: This rotation is in addition to the rotation needed to center the view on the focal point.
Definition at line 595 of file EarthManipulator.
{ return _rotation; }
Here is the caller graph for this function:| osg::Matrixd EarthManipulator::getRotation | ( | const osg::Vec3d & | center | ) | const [private] |
Definition at line 749 of file EarthManipulator.cpp.
{
//The look vector will be going directly from the eye point to the point on the earth,
//so the look vector is simply the up vector at the center point
osg::CoordinateFrame cf = getMyCoordinateFrame( point ); //getCoordinateFrame(point);
osg::Vec3d lookVector = -getUpVector(cf);
osg::Vec3d side;
//Force the side vector to be orthogonal to north
osg::Vec3d worldUp(0,0,1);
double dot = osg::absolute(worldUp * lookVector);
if (osg::equivalent(dot, 1.0))
{
//We are looking nearly straight down the up vector, so use the Y vector for world up instead
worldUp = osg::Vec3d(0, 1, 0);
//OE_NOTICE << "using y vector victor" << std::endl;
}
side = lookVector ^ worldUp;
osg::Vec3d up = side ^ lookVector;
up.normalize();
//We want a very slight offset
double offset = 1e-6;
return osg::Matrixd::lookAt( point - (lookVector * offset), point, up);
}
Here is the call graph for this function:| EarthManipulator::Settings * EarthManipulator::getSettings | ( | ) | const |
Gets a handle on the current manipulator settings object.
Definition at line 512 of file EarthManipulator.cpp.
{
return _settings.get();
}
Here is the caller graph for this function:| const osgEarth::SpatialReference * EarthManipulator::getSRS | ( | ) | const |
Gets the spatial reference system of the terrain map to which this manipulator is currently attached.
Definition at line 695 of file EarthManipulator.cpp.
{
osg::ref_ptr<osg::Node> safeNode = _node.get();
if ( !_cached_srs.valid() && !_srs_lookup_failed && safeNode.valid() )
{
EarthManipulator* nonconst_this = const_cast<EarthManipulator*>(this);
nonconst_this->_is_geocentric = false;
// first try to find a map node:
osgEarth::MapNode* mapNode = osgEarth::MapNode::findMapNode( safeNode.get() );
if ( mapNode )
{
nonconst_this->_cached_srs = mapNode->getMap()->getProfile()->getSRS();
nonconst_this->_is_geocentric = mapNode->isGeocentric();
}
// if that doesn't work, try gleaning info from a CSN:
if ( !_cached_srs.valid() )
{
osg::CoordinateSystemNode* csn = osgEarth::findTopMostNodeOfType<osg::CoordinateSystemNode>( safeNode.get() );
if ( csn )
{
nonconst_this->_cached_srs = osgEarth::SpatialReference::create( csn );
nonconst_this->_is_geocentric = csn->getEllipsoidModel() != NULL;
}
}
nonconst_this->_srs_lookup_failed = !_cached_srs.valid();
if ( _cached_srs.valid() )
{
OE_INFO << "[EarthManip] cached SRS: "
<< _cached_srs->getName()
<< ", geocentric=" << _is_geocentric
<< std::endl;
}
}
return _cached_srs.get();
}
Here is the call graph for this function:
Here is the caller graph for this function:| osg::Node * EarthManipulator::getTetherNode | ( | ) | const |
Gets the node to which the camera is tethered, or NULL if tethering is disabled.
Definition at line 1056 of file EarthManipulator.cpp.
{
return _tether_node.get();
}
| void EarthManipulator::getUsage | ( | osg::ApplicationUsage & | usage | ) | const [virtual] |
Definition at line 1120 of file EarthManipulator.cpp.
{
}
| Viewpoint EarthManipulator::getViewpoint | ( | ) | const |
Gets the current camera position.
Definition at line 1020 of file EarthManipulator.cpp.
{
osg::Vec3d focal_point = _center;
if ( getSRS() && _is_geocentric )
{
// convert geocentric to lat/long:
getSRS()->getEllipsoid()->convertXYZToLatLongHeight(
_center.x(), _center.y(), _center.z(),
focal_point.y(), focal_point.x(), focal_point.z() );
focal_point.x() = osg::RadiansToDegrees( focal_point.x() );
focal_point.y() = osg::RadiansToDegrees( focal_point.y() );
}
return Viewpoint(
focal_point,
osg::RadiansToDegrees( _local_azim ),
osg::RadiansToDegrees( _local_pitch ),
_distance,
getSRS() );
}
Here is the call graph for this function:
Here is the caller graph for this function:| bool EarthManipulator::handle | ( | const osgGA::GUIEventAdapter & | ea, |
| osgGA::GUIActionAdapter & | us | ||
| ) | [virtual] |
Definition at line 1175 of file EarthManipulator.cpp.
{
bool handled = false;
// first order of business: make sure the CSN is established.
if ( !established() )
return false;
// make sure the camera callback is up to date:
updateCamera( aa.asView()->getCamera() );
if ( ea.getEventType() == osgGA::GUIEventAdapter::FRAME )
{
_time_s_last_frame = _time_s_now;
_time_s_now = osg::Timer::instance()->time_s();
_delta_t = _time_s_now - _time_s_last_frame;
// this factor adjusts for the variation of frame rate relative to 60fps
_t_factor = _delta_t / 0.01666666666;
//OE_NOTICE
// << "center=(" << _center.x() << "," << _center.y() << "," << _center.z() << ")"
// << ", dist=" << _distance
// << ", p=" << _local_pitch
// << ", h=" << _local_azim
// << std::endl;
if ( _has_pending_viewpoint && _node.valid() )
{
_has_pending_viewpoint = false;
setViewpoint( _pending_viewpoint, _pending_viewpoint_duration_s );
aa.requestRedraw();
}
if ( _setting_viewpoint )
{
updateSetViewpoint();
aa.requestRedraw();
}
if ( _thrown || _continuous )
{
handleContinuousAction( _last_action, aa.asView() );
aa.requestRedraw();
}
if ( !_continuous )
{
_continuous_dx = 0.0;
_continuous_dy = 0.0;
}
if ( _task.valid() )
{
if ( serviceTask() )
aa.requestRedraw();
}
_after_first_frame = true;
return false;
}
// the camera manipulator runs last after any other event handlers. So bail out
// if the incoming event has already been handled by another handler.
if ( ea.getHandled() )
{
return false;
}
// form the current Action based on the event type:
Action action = ACTION_NULL;
switch( ea.getEventType() )
{
case osgGA::GUIEventAdapter::PUSH:
resetMouse( aa );
addMouseEvent( ea );
_mouse_down_event = &ea;
aa.requestRedraw();
handled = true;
break;
case osgGA::GUIEventAdapter::RELEASE:
if ( _continuous )
{
// bail out of continuous mode if necessary:
_continuous = false;
}
else
{
// check for a mouse-throw continuation:
if ( _settings->getThrowingEnabled() && isMouseMoving() )
{
action = _last_action;
if( handleMouseAction( action, aa.asView() ) )
{
aa.requestRedraw();
aa.requestContinuousUpdate( true );
_thrown = true;
}
}
else if ( isMouseClick( &ea ) )
{
addMouseEvent( ea );
if ( _mouse_down_event )
{
action = _settings->getAction( EVENT_MOUSE_CLICK, _mouse_down_event->getButtonMask(), _mouse_down_event->getModKeyMask() );
if ( handlePointAction( action, ea.getX(), ea.getY(), aa.asView() ))
aa.requestRedraw();
}
resetMouse( aa );
}
else
{
resetMouse( aa );
addMouseEvent( ea );
}
}
handled = true;
break;
case osgGA::GUIEventAdapter::DOUBLECLICK:
// bail out of continuous mode if necessary:
_continuous = false;
addMouseEvent( ea );
if (_mouse_down_event)
{
action = _settings->getAction( EVENT_MOUSE_DOUBLE_CLICK, _mouse_down_event->getButtonMask(), _mouse_down_event->getModKeyMask() );
if ( handlePointAction( action, ea.getX(), ea.getY(), aa.asView() ) )
aa.requestRedraw();
resetMouse( aa );
handled = true;
}
break;
case osgGA::GUIEventAdapter::MOVE: // MOVE not currently bindable
//NOP
break;
case osgGA::GUIEventAdapter::DRAG:
{
action = _settings->getAction( ea.getEventType(), ea.getButtonMask(), ea.getModKeyMask() );
addMouseEvent( ea );
_continuous = action.getBoolOption(OPTION_CONTINUOUS, false);
if ( handleMouseAction( action, aa.asView() ) )
aa.requestRedraw();
aa.requestContinuousUpdate(false);
_thrown = false;
handled = true;
}
break;
case osgGA::GUIEventAdapter::KEYDOWN:
if ( ea.getKey() < osgGA::GUIEventAdapter::KEY_Shift_L )
{
resetMouse( aa );
action = _settings->getAction( ea.getEventType(), ea.getKey(), ea.getModKeyMask() );
if ( handleKeyboardAction( action ) )
aa.requestRedraw();
handled = true;
}
break;
case osgGA::GUIEventAdapter::KEYUP:
resetMouse( aa );
_task->_type = TASK_NONE;
handled = true;
break;
case osgGA::GUIEventAdapter::SCROLL:
resetMouse( aa );
addMouseEvent( ea );
action = _settings->getAction( ea.getEventType(), ea.getScrollingMotion(), ea.getModKeyMask() );
if ( handleScrollAction( action, 0.2 ) )
aa.requestRedraw();
handled = true;
break;
}
if ( handled && action._type != ACTION_NULL )
_last_action = action;
return handled;
}
Here is the call graph for this function:| bool EarthManipulator::handleAction | ( | const Action & | action, |
| double | dx, | ||
| double | dy, | ||
| double | duration | ||
| ) | [protected] |
Definition at line 2091 of file EarthManipulator.cpp.
{
bool handled = true;
//if ( osgEarth::getNotifyLevel() > osg::INFO )
// dumpActionInfo( action, osg::DEBUG_INFO );
//OE_NOTICE << "action=" << action << ", dx=" << dx << ", dy=" << dy << std::endl;
switch( action._type )
{
case ACTION_HOME:
if ( _homeViewpoint.isSet() )
{
setViewpoint( _homeViewpoint.value(), _homeViewpointDuration );
}
//else
//{
// if ( getAutoComputeHomePosition() )
// computeHomePosition();
// setByLookAt( _homeEye, _homeCenter, _homeUp );
//}
break;
case ACTION_PAN:
case ACTION_PAN_LEFT:
case ACTION_PAN_RIGHT:
case ACTION_PAN_UP:
case ACTION_PAN_DOWN:
_task->set( TASK_PAN, dx, dy, duration );
break;
case ACTION_ROTATE:
case ACTION_ROTATE_LEFT:
case ACTION_ROTATE_RIGHT:
case ACTION_ROTATE_UP:
case ACTION_ROTATE_DOWN:
_task->set( TASK_ROTATE, dx, dy, duration );
break;
case ACTION_ZOOM:
case ACTION_ZOOM_IN:
case ACTION_ZOOM_OUT:
_task->set( TASK_ZOOM, dx, dy, duration );
break;
default:
handled = false;
}
return handled;
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::handleContinuousAction | ( | const Action & | action, |
| osg::View * | view | ||
| ) | [protected] |
Definition at line 1983 of file EarthManipulator.cpp.
{
handleMovementAction( action._type, _continuous_dx * _t_factor, _continuous_dy * _t_factor, view );
}
Here is the call graph for this function:
Here is the caller graph for this function:| bool EarthManipulator::handleKeyboardAction | ( | const Action & | action, |
| double | duration_s = DBL_MAX |
||
| ) | [protected] |
Definition at line 2047 of file EarthManipulator.cpp.
{
double dx = 0, dy = 0;
switch( action._dir )
{
case DIR_LEFT: dx = 1; break;
case DIR_RIGHT: dx = -1; break;
case DIR_UP: dy = -1; break;
case DIR_DOWN: dy = 1; break;
}
dx *= _settings->getKeyboardSensitivity();
dy *= _settings->getKeyboardSensitivity();
applyOptionsToDeltas( action, dx, dy );
return handleAction( action, dx, dy, duration );
}
Here is the call graph for this function:
Here is the caller graph for this function:| bool EarthManipulator::handleMouseAction | ( | const Action & | action, |
| osg::View * | view | ||
| ) | [protected] |
Definition at line 2004 of file EarthManipulator.cpp.
{
// return if less then two events have been added.
if (_ga_t0.get()==NULL || _ga_t1.get()==NULL) return false;
//if ( osgEarth::getNotifyLevel() > osg::INFO )
// dumpActionInfo( action, osg::DEBUG_INFO );
double dx = _ga_t0->getXnormalized()-_ga_t1->getXnormalized();
double dy = _ga_t0->getYnormalized()-_ga_t1->getYnormalized();
// return if there is no movement.
if (dx==0 && dy==0) return false;
// here we adjust for action scale, global sensitivy
dx *= _settings->getMouseSensitivity();
dy *= _settings->getMouseSensitivity();
applyOptionsToDeltas( action, dx, dy );
// in "continuous" mode, we accumulate the deltas each frame - thus
// the deltas act more like speeds.
if ( _continuous )
{
_continuous_dx += dx * 0.01;
_continuous_dy += dy * 0.01;
}
else
{
handleMovementAction( action._type, dx, dy, view );
}
return true;
}
Here is the call graph for this function:
Here is the caller graph for this function:| bool EarthManipulator::handleMouseClickAction | ( | const Action & | action | ) | [protected] |
Definition at line 2040 of file EarthManipulator.cpp.
{
//TODO.
return false;
}
| void EarthManipulator::handleMovementAction | ( | const ActionType & | type, |
| double | dx, | ||
| double | dy, | ||
| osg::View * | view | ||
| ) | [protected] |
Definition at line 1915 of file EarthManipulator.cpp.
{
switch( type )
{
case ACTION_PAN:
pan( dx, dy );
break;
case ACTION_ROTATE:
// in "single axis" mode, zero out one of the deltas.
if ( _continuous && _settings->getSingleAxisRotation() )
{
if ( ::fabs(dx) > ::fabs(dy) )
dy = 0.0;
else
dx = 0.0;
}
rotate( dx, dy );
break;
case ACTION_ZOOM:
zoom( dx, dy );
break;
case ACTION_EARTH_DRAG:
drag( dx, dy, view );
break;
}
}
Here is the call graph for this function:
Here is the caller graph for this function:| bool EarthManipulator::handlePointAction | ( | const Action & | type, |
| float | mx, | ||
| float | my, | ||
| osg::View * | view | ||
| ) | [protected] |
Definition at line 1946 of file EarthManipulator.cpp.
{
//Exit early if the action is null
if (action._type == ACTION_NULL)
return true;
osg::Vec3d point;
if ( screenToWorld( mx, my, view, point ))
{
switch( action._type )
{
case ACTION_GOTO:
Viewpoint here = getViewpoint();
if ( getSRS() && _is_geocentric )
{
double lat_r, lon_r, h;
getSRS()->getEllipsoid()->convertXYZToLatLongHeight(
point.x(), point.y(), point.z(),
lat_r, lon_r, h );
point.set( osg::RadiansToDegrees(lon_r), osg::RadiansToDegrees(lat_r), h );
}
here.setFocalPoint( point );
double duration_s = action.getDoubleOption(OPTION_DURATION, 1.0);
double range_factor = action.getDoubleOption(OPTION_GOTO_RANGE_FACTOR, 1.0);
here.setRange( here.getRange() * range_factor );
setViewpoint( here, duration_s );
break;
}
}
return true;
}
Here is the call graph for this function:
Here is the caller graph for this function:| bool EarthManipulator::handleScrollAction | ( | const Action & | action, |
| double | duration_s = DBL_MAX |
||
| ) | [protected] |
Definition at line 2068 of file EarthManipulator.cpp.
{
const double scrollFactor = 1.5;
double dx = 0, dy = 0;
switch( action._dir )
{
case DIR_LEFT: dx = 1; break;
case DIR_RIGHT: dx = -1; break;
case DIR_UP: dy = -1; break;
case DIR_DOWN: dy = 1; break;
}
dx *= scrollFactor * _settings->getScrollSensitivity();
dy *= scrollFactor * _settings->getScrollSensitivity();
applyOptionsToDeltas( action, dx, dy );
return handleAction( action, dx, dy, duration );
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::home | ( | const osgGA::GUIEventAdapter & | ea, |
| osgGA::GUIActionAdapter & | us | ||
| ) | [virtual] |
Definition at line 1085 of file EarthManipulator.cpp.
{
handleAction( ACTION_HOME, 0, 0, 0 );
//if (getAutoComputeHomePosition()) computeHomePosition();
//setByLookAt(_homeEye, _homeCenter, _homeUp);
us.requestRedraw();
}
Here is the call graph for this function:| void EarthManipulator::init | ( | const osgGA::GUIEventAdapter & | ea, |
| osgGA::GUIActionAdapter & | us | ||
| ) | [virtual] |
Definition at line 1113 of file EarthManipulator.cpp.
{
flushMouseEventStack();
}
Here is the call graph for this function:| bool EarthManipulator::intersect | ( | const osg::Vec3d & | start, |
| const osg::Vec3d & | end, | ||
| osg::Vec3d & | intersection | ||
| ) | const [protected] |
Definition at line 1063 of file EarthManipulator.cpp.
{
osg::ref_ptr<osg::Node> safeNode = _node.get();
if ( safeNode.valid() )
{
osg::ref_ptr<osgUtil::LineSegmentIntersector> lsi = new osgUtil::LineSegmentIntersector(start,end);
osgUtil::IntersectionVisitor iv(lsi.get());
iv.setTraversalMask(_intersectTraversalMask);
safeNode->accept(iv);
if (lsi->containsIntersections())
{
intersection = lsi->getIntersections().begin()->getWorldIntersectPoint();
return true;
}
}
return false;
}
Here is the caller graph for this function:| bool EarthManipulator::isMouseClick | ( | const osgGA::GUIEventAdapter * | mouse_up_event | ) | const [private] |
Definition at line 1487 of file EarthManipulator.cpp.
{
if ( mouse_up_event == NULL || _mouse_down_event == NULL ) return false;
static const float velocity = 0.1f;
float dx = mouse_up_event->getXnormalized() - _mouse_down_event->getXnormalized();
float dy = mouse_up_event->getYnormalized() - _mouse_down_event->getYnormalized();
float len = sqrtf( dx*dx + dy*dy );
float dt = mouse_up_event->getTime( ) - _mouse_down_event->getTime();
return len < dt * velocity;
}
Here is the caller graph for this function:| bool EarthManipulator::isMouseMoving | ( | ) | [protected] |
Definition at line 1472 of file EarthManipulator.cpp.
{
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 > _delta_t * velocity;
}
Here is the caller graph for this function:| osg::Quat osgEarth::Util::EarthManipulator::makeCenterRotation | ( | const osg::Vec3d & | center | ) | const [inline, private] |
Definition at line 714 of file EarthManipulator.
{
return getRotation(center).getRotate().inverse();
}
Here is the caller graph for this function:| void EarthManipulator::pan | ( | double | dx, |
| double | dy | ||
| ) | [virtual] |
Move the focal point of the camera using deltas (normalized screen coords).
Definition at line 1708 of file EarthManipulator.cpp.
{
//OE_NOTICE << "pan " << dx << "," << dy << std::endl;
if (!_tether_node.valid())
{
double scale = -0.3f*_distance;
//double old_azim = _local_azim;
double old_azim = getAzimuth();
osg::Matrixd rotation_matrix;// = getMatrix();
rotation_matrix.makeRotate( _rotation * _centerRotation );
// compute look vector.
osg::Vec3d lookVector = -getUpVector(rotation_matrix);
osg::Vec3d sideVector = getSideVector(rotation_matrix);
osg::Vec3d upVector = getFrontVector(rotation_matrix);
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);
// save the previous CF so we can do azimuth locking:
osg::CoordinateFrame old_frame = getMyCoordinateFrame( _center ); //getCoordinateFrame( _center );
_center += dv;
// need to recompute the intersection point along the look vector.
osg::ref_ptr<osg::Node> safeNode = _node.get();
if (safeNode.valid())
{
// now reorientate the coordinate frame to the frame coords.
osg::CoordinateFrame coordinateFrame = old_frame; // getCoordinateFrame(_center);
recalculateCenter( coordinateFrame );
coordinateFrame = getMyCoordinateFrame( _center ); // getCoordinateFrame(_center);
osg::Vec3d new_localUp = getUpVector(coordinateFrame);
osg::Quat pan_rotation;
pan_rotation.makeRotate( localUp, new_localUp );
if ( !pan_rotation.zeroRotation() )
{
_centerRotation = _centerRotation * pan_rotation;
_previousUp = new_localUp;
}
else
{
//OE_DEBUG<<"New up orientation nearly inline - no need to rotate"<<std::endl;
}
if ( _settings->getLockAzimuthWhilePanning() )
{
double new_azim = getAzimuth();
double delta_azim = new_azim - old_azim;
//OE_NOTICE << "DeltaAzim" << delta_azim << std::endl;
osg::Quat q;
q.makeRotate( delta_azim, new_localUp );
if ( !q.zeroRotation() )
{
_centerRotation = _centerRotation * q;
}
}
}
recalculateLocalPitchAndAzimuth();
}
else
{
double scale = _distance;
_offset_x += dx * scale;
_offset_y += dy * scale;
//Clamp values within range
if (_offset_x < -_settings->getMaxXOffset()) _offset_x = -_settings->getMaxXOffset();
if (_offset_y < -_settings->getMaxYOffset()) _offset_y = -_settings->getMaxYOffset();
if (_offset_x > _settings->getMaxXOffset()) _offset_x = _settings->getMaxXOffset();
if (_offset_y > _settings->getMaxYOffset()) _offset_y = _settings->getMaxYOffset();
}
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::postUpdate | ( | ) | [private] |
Definition at line 1363 of file EarthManipulator.cpp.
{
updateTether();
}
Here is the call graph for this function:| void EarthManipulator::recalculateCenter | ( | const osg::CoordinateFrame & | frame | ) | [private] |
Definition at line 1650 of file EarthManipulator.cpp.
{
osg::ref_ptr<osg::Node> safeNode = _node.get();
if ( safeNode.valid() )
{
bool hitFound = false;
// need to reintersect with the terrain
double distance = safeNode->getBound().radius()*0.25f;
//OE_NOTICE
// << std::fixed
// << "ISECT: center=(" << _center.x() << "," << _center.y() << "," << _center.y() << ")"
// << ", distnace=" << distance
// << std::endl;
//osg::Vec3d ev = getUpVector(coordinateFrame);
//osg::Vec3d ip;
//if ( intersect( _center -ev * distance, _center + ev*distance, ip ) )
//{
// _center = ip;
// hitFound = true;
//}
osg::Vec3d ip1;
osg::Vec3d ip2;
// extend coordonate to fall on the edge of the boundingbox see http://www.osgearth.org/ticket/113
bool hit_ip1 = intersect(_center - getUpVector(coordinateFrame) * distance * 0.1, _center + getUpVector(coordinateFrame) * distance, ip1);
bool hit_ip2 = intersect(_center + getUpVector(coordinateFrame) * distance * 0.1, _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)
{
// ??
//OE_DEBUG<<"EarthManipulator unable to intersect with terrain."<<std::endl;
}
}
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::recalculateLocalPitchAndAzimuth | ( | ) | [private] |
Definition at line 2204 of file EarthManipulator.cpp.
{
double r;
s_getHPRFromQuat( _rotation, _local_azim, _local_pitch, r);
_local_pitch -= osg::PI_2;
//OE_NOTICE << "Azim=" << osg::RadiansToDegrees(_local_azim) << " Pitch=" << osg::RadiansToDegrees(_local_pitch) << std::endl;
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::recalculateRoll | ( | ) | [protected] |
Definition at line 2146 of file EarthManipulator.cpp.
{
osg::Matrixd rotation_matrix;
rotation_matrix.makeRotate(_centerRotation);
osg::Vec3d lookVector = -getUpVector(rotation_matrix);
osg::Vec3d upVector = getFrontVector(rotation_matrix);
osg::CoordinateFrame coordinateFrame = getMyCoordinateFrame( _center ); //getCoordinateFrame(_center);
osg::Vec3d localUp = getUpVector(coordinateFrame);
osg::Vec3d sideVector = lookVector ^ localUp;
if (sideVector.length()<0.1)
{
//OE_INFO<<"Side vector short "<<sideVector.length()<<std::endl;
sideVector = upVector^localUp;
sideVector.normalize();
}
osg::Vec3d newUpVector = sideVector^lookVector;
newUpVector.normalize();
osg::Quat rotate_roll;
rotate_roll.makeRotate(upVector,newUpVector);
if (!rotate_roll.zeroRotation())
{
_centerRotation = _centerRotation * rotate_roll;
}
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::reinitialize | ( | ) | [private] |
Definition at line 518 of file EarthManipulator.cpp.
{
_distance = 1.0;
_offset_x = 0.0;
_offset_y = 0.0;
_thrown = false;
_continuous = false;
_task = new Task();
_last_action = ACTION_NULL;
_srs_lookup_failed = false;
_setting_viewpoint = false;
_delta_t = 0.0;
_t_factor = 1.0;
_local_azim = 0.0;
_local_pitch = 0.0;
_has_pending_viewpoint = false;
_lastPointOnEarth.set(0.0, 0.0, 0.0);
_arc_height = 0.0;
}
Here is the caller graph for this function:| void EarthManipulator::resetMouse | ( | osgGA::GUIActionAdapter & | aa | ) | [protected] |
Definition at line 1125 of file EarthManipulator.cpp.
{
flushMouseEventStack();
aa.requestContinuousUpdate( false );
_thrown = false;
_continuous = false;
_single_axis_x = 1.0;
_single_axis_y = 1.0;
_lastPointOnEarth.set(0.0, 0.0, 0.0);
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::rotate | ( | double | dx, |
| double | dy | ||
| ) | [virtual] |
Rotate the camera (dx = azimuth, dy = pitch) using deltas (radians).
Definition at line 1798 of file EarthManipulator.cpp.
{
//OE_NOTICE << "rotate " << dx <<", " << dy << std::endl;
// clamp the local pitch delta; never allow the pitch to hit -90.
double minp = osg::DegreesToRadians( osg::clampAbove( _settings->getMinPitch(), -89.9 ) );
double maxp = osg::DegreesToRadians( _settings->getMaxPitch() );
//OE_NOTICE << LC
// << "LocalPitch=" << osg::RadiansToDegrees(_local_pitch)
// << ", dy=" << osg::RadiansToDegrees(dy)
// << ", dy+lp=" << osg::RadiansToDegrees(_local_pitch+dy)
// << ", limits=" << osg::RadiansToDegrees(minp) << "," << osg::RadiansToDegrees(maxp)
// << std::endl;
// clamp pitch range:
if ( dy + _local_pitch > maxp || dy + _local_pitch < minp )
dy = 0;
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);
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;
recalculateLocalPitchAndAzimuth();
}
Here is the call graph for this function:
Here is the caller graph for this function:| bool EarthManipulator::screenToWorld | ( | float | x, |
| float | y, | ||
| osg::View * | view, | ||
| osg::Vec3d & | out_coords | ||
| ) | const |
Converts screen coordinates (relative to the view's viewpoint) to world coordinates. Note, this method will use the mask set by setTraversalMask().
| x,y | Viewport coordinates |
| view | View for which to calculate world coordinates |
| out_coords | Output world coordinates (only valid if the method returns true) |
Definition at line 1858 of file EarthManipulator.cpp.
{
osgViewer::View* view = dynamic_cast<osgViewer::View*>( theView );
if ( !view || !view->getCamera() )
return false;
float local_x, local_y = 0.0;
const osg::Camera* camera = view->getCameraContainingPosition(x, y, local_x, local_y);
if ( !camera )
camera = view->getCamera();
osgUtil::LineSegmentIntersector::CoordinateFrame cf =
camera->getViewport() ? osgUtil::Intersector::WINDOW : osgUtil::Intersector::PROJECTION;
osg::ref_ptr< osgUtil::LineSegmentIntersector > picker = new osgUtil::LineSegmentIntersector(cf, local_x, local_y);
osgUtil::IntersectionVisitor iv(picker.get());
iv.setTraversalMask(_intersectTraversalMask);
const_cast<osg::Camera*>(camera)->accept(iv);
if ( picker->containsIntersections() )
{
osgUtil::LineSegmentIntersector::Intersections& results = picker->getIntersections();
out_coords = results.begin()->getWorldIntersectPoint();
return true;
}
return false;
}
Here is the caller graph for this function:| bool EarthManipulator::serviceTask | ( | ) | [private] |
Definition at line 1436 of file EarthManipulator.cpp.
{
bool result;
if ( _task.valid() && _task->_type != TASK_NONE )
{
switch( _task->_type )
{
case TASK_PAN:
pan( _delta_t * _task->_dx, _delta_t * _task->_dy );
break;
case TASK_ROTATE:
rotate( _delta_t * _task->_dx, _delta_t * _task->_dy );
break;
case TASK_ZOOM:
zoom( _delta_t * _task->_dx, _delta_t * _task->_dy );
break;
default: break;
}
_task->_duration_s -= _delta_t;
if ( _task->_duration_s <= 0.0 )
_task->_type = TASK_NONE;
result = true;
}
else
{
result = false;
}
//_time_last_frame = now;
return result;
}
Here is the call graph for this function:
Here is the caller graph for this function:| virtual void osgEarth::Util::EarthManipulator::setByInverseMatrix | ( | const osg::Matrixd & | matrix | ) | [inline, virtual] |
set the position of the matrix manipulator using a 4x4 Matrix.
Definition at line 611 of file EarthManipulator.
{ setByMatrix(osg::Matrixd::inverse(matrix)); }
| void EarthManipulator::setByLookAt | ( | const osg::Vec3d & | eye, |
| const osg::Vec3d & | lv, | ||
| const osg::Vec3d & | up | ||
| ) | [protected] |
Definition at line 1597 of file EarthManipulator.cpp.
{
osg::ref_ptr<osg::Node> safeNode = _node.get();
if ( !safeNode.valid() ) return;
// compute rotation matrix
osg::Vec3d lv(center-eye);
setDistance( lv.length() );
_center = center;
if (_node.valid())
{
bool hitFound = false;
double distance = lv.length();
double maxDistance = distance+2*(eye-safeNode->getBound().center()).length();
osg::Vec3d farPosition = eye+lv*(maxDistance/distance);
osg::Vec3d endPoint = center;
for(int i=0;
!hitFound && i<2;
++i, endPoint = farPosition)
{
// compute the intersection with the scene.s
osg::Vec3d ip;
if (intersect(eye, endPoint, ip))
{
_center = ip;
setDistance( (ip-eye).length() );
hitFound = true;
}
}
}
// 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);
_centerRotation = getRotation( _center ).getRotate().inverse();
_rotation = rotation_matrix.getRotate().inverse() * _centerRotation.inverse();
osg::CoordinateFrame coordinateFrame = getMyCoordinateFrame( _center ); //getCoordinateFrame(_center);
_previousUp = getUpVector(coordinateFrame);
recalculateRoll();
recalculateLocalPitchAndAzimuth();
}
Here is the call graph for this function:| void EarthManipulator::setByMatrix | ( | const osg::Matrixd & | matrix | ) | [virtual] |
set the position of the matrix manipulator using a 4x4 Matrix.
Definition at line 1517 of file EarthManipulator.cpp.
{
osg::Vec3d lookVector(- matrix(2,0),-matrix(2,1),-matrix(2,2));
osg::Vec3d eye(matrix(3,0),matrix(3,1),matrix(3,2));
_centerRotation = makeCenterRotation(_center);
osg::ref_ptr<osg::Node> safeNode = _node.get();
if ( !safeNode.valid() )
{
_center = eye + lookVector;
setDistance( lookVector.length() );
_rotation = matrix.getRotate().inverse() * _centerRotation.inverse();
return;
}
// need to reintersect with the terrain
const osg::BoundingSphere& bs = safeNode->getBound();
float distance = (eye-bs.center()).length() + safeNode->getBound().radius();
osg::Vec3d start_segment = eye;
osg::Vec3d end_segment = eye + lookVector*distance;
osg::Vec3d ip;
bool hitFound = false;
if (intersect(start_segment, end_segment, ip))
{
_center = ip;
_centerRotation = makeCenterRotation(_center);
setDistance( (eye-ip).length());
osg::Matrixd rotation_matrix = osg::Matrixd::translate(0.0,0.0,-_distance)*
matrix*
osg::Matrixd::translate(-_center);
_rotation = rotation_matrix.getRotate() * _centerRotation.inverse();
hitFound = true;
}
if (!hitFound)
{
osg::CoordinateFrame eyePointCoordFrame = getMyCoordinateFrame( eye ); //getCoordinateFrame( eye );
if (intersect(eye+getUpVector(eyePointCoordFrame)*distance,
eye-getUpVector(eyePointCoordFrame)*distance,
ip))
{
_center = ip;
_centerRotation = makeCenterRotation(_center);
setDistance((eye-ip).length());
_rotation.set(0,0,0,1);
hitFound = true;
}
}
osg::CoordinateFrame coordinateFrame = getMyCoordinateFrame( _center ); //getCoordinateFrame( _center );
_previousUp = getUpVector(coordinateFrame);
recalculateRoll();
recalculateLocalPitchAndAzimuth();
}
Here is the call graph for this function:| void EarthManipulator::setDistance | ( | double | distance | ) |
Sets the distance from the focal point in world coordinates.
The incoming distance value will be clamped within the valid range specified by the settings.
Definition at line 1890 of file EarthManipulator.cpp.
{
_distance = osg::clampBetween( distance, _settings->getMinDistance(), _settings->getMaxDistance() );
}
Here is the caller graph for this function:| void EarthManipulator::setHomeViewpoint | ( | const Viewpoint & | vp, |
| double | duration_s = 0.0 |
||
| ) |
Sets the viewpoint to activate when performing the ACTION_HOME action.
Definition at line 2213 of file EarthManipulator.cpp.
{
_homeViewpoint = vp;
_homeViewpointDuration = duration_s;
}
Here is the caller graph for this function:| void EarthManipulator::setNode | ( | osg::Node * | node | ) | [virtual] |
Definition at line 668 of file EarthManipulator.cpp.
{
// you can only set the node if it has not already been set, OR if you are setting
// it to NULL. (So to change it, you must first set it to NULL.) This is to prevent
// OSG from overwriting the node after you have already set on manually.
if ( node == 0L || !_node.valid() )
{
_node = node;
_csn = 0L;
#ifdef USE_OBSERVER_NODE_PATH
_csnObserverPath.clearNodePath();
#endif
_csnPath.clear();
reinitialize();
// this might be unnecessary..
established();
}
}
Here is the call graph for this function:
Here is the caller graph for this function:| void osgEarth::Util::EarthManipulator::setRotation | ( | const osg::Quat & | rotation | ) | [inline] |
Sets the rotation of the manipulator. Note: This rotation is in addition to the rotation needed to center the view on the focal point.
Definition at line 600 of file EarthManipulator.
{ _rotation = rotation; }
| void EarthManipulator::setTetherNode | ( | osg::Node * | node | ) |
Locks the camera's focal point on the center of a node's bounding sphere. While tethered, you can still call navigate or call setViewpoint() to move the camera relative to the tether object. Pass NULL to deactivate the tether.
| node | Node to which to tether the viewpoint. |
Definition at line 1045 of file EarthManipulator.cpp.
{
if (_tether_node != node)
{
_offset_x = 0.0;
_offset_y = 0.0;
}
_tether_node = node;
}
| void EarthManipulator::setViewpoint | ( | const Viewpoint & | vp, |
| double | duration_s = 0.0 |
||
| ) | [virtual] |
Sets the camera position, optionally moving it there over time.
Definition at line 780 of file EarthManipulator.cpp.
{
if ( !established() ) // !_node.valid() ) // || !_after_first_frame )
{
_pending_viewpoint = vp;
_pending_viewpoint_duration_s = duration_s;
_has_pending_viewpoint = true;
}
else if ( duration_s > 0.0 )
{
_start_viewpoint = getViewpoint();
_delta_heading = vp.getHeading() - _start_viewpoint.getHeading(); //TODO: adjust for crossing -180
_delta_pitch = vp.getPitch() - _start_viewpoint.getPitch();
_delta_range = vp.getRange() - _start_viewpoint.getRange();
_delta_focal_point = vp.getFocalPoint() - _start_viewpoint.getFocalPoint(); // TODO: adjust for lon=180 crossing
while( _delta_heading > 180.0 ) _delta_heading -= 360.0;
while( _delta_heading < -180.0 ) _delta_heading += 360.0;
// adjust for geocentric date-line crossing
if ( _is_geocentric )
{
while( _delta_focal_point.x() > 180.0 ) _delta_focal_point.x() -= 360.0;
while( _delta_focal_point.x() < -180.0 ) _delta_focal_point.x() += 360.0;
}
// calculate an acceleration factor based on the Z differential
double h0 = _start_viewpoint.getRange() * sin( osg::DegreesToRadians(-_start_viewpoint.getPitch()) );
double h1 = vp.getRange() * sin( osg::DegreesToRadians( -vp.getPitch() ) );
double dh = (h1 - h0);
// calculate the total distance the focal point will travel and derive an arc height:
double de;
if ( _is_geocentric && (vp.getSRS() == 0L || vp.getSRS()->isGeographic()) )
{
osg::Vec3d startFP = _start_viewpoint.getFocalPoint();
double x0,y0,z0, x1,y1,z1;
_cached_srs->getEllipsoid()->convertLatLongHeightToXYZ(
osg::DegreesToRadians( _start_viewpoint.y() ), osg::DegreesToRadians( _start_viewpoint.x() ), 0.0, x0, y0, z0 );
_cached_srs->getEllipsoid()->convertLatLongHeightToXYZ(
osg::DegreesToRadians( vp.y() ), osg::DegreesToRadians( vp.x() ), 0.0, x1, y1, z1 );
de = (osg::Vec3d(x0,y0,z0) - osg::Vec3d(x1,y1,z1)).length();
}
else
{
de = _delta_focal_point.length();
}
_arc_height = 0.0;
if ( _settings->getArcViewpointTransitions() )
{
_arc_height = osg::maximum( de - fabs(dh), 0.0 );
}
// calculate acceleration coefficients
if ( _arc_height > 0.0 )
{
// if we're arcing, we need seperate coefficients for the up and down stages
double h_apex = 2.0*(h0+h1) + _arc_height;
double dh2_up = fabs(h_apex - h0)/100000.0;
_set_viewpoint_accel = log10( dh2_up );
double dh2_down = fabs(h_apex - h1)/100000.0;
_set_viewpoint_accel_2 = -log10( dh2_down );
}
else
{
// on arc => simple unidirectional acceleration:
double dh2 = (h1 - h0)/100000.0;
_set_viewpoint_accel = fabs(dh2) <= 1.0? 0.0 : dh2 > 0.0? log10( dh2 ) : -log10( -dh2 );
if ( fabs( _set_viewpoint_accel ) < 1.0 ) _set_viewpoint_accel = 0.0;
}
if ( _settings->getAutoViewpointDurationEnabled() )
{
double maxDistance = _cached_srs->getEllipsoid()->getRadiusEquator();
double ratio = osg::clampBetween( de/maxDistance, 0.0, 1.0 );
ratio = accelerationInterp( ratio, -4.5 );
double minDur, maxDur;
_settings->getAutoViewpointDurationLimits( minDur, maxDur );
duration_s = minDur + ratio*(maxDur-minDur);
}
// don't use _time_s_now; that's the time of the last event
_time_s_set_viewpoint = osg::Timer::instance()->time_s();
_set_viewpoint_duration_s = duration_s;
// OE_NOTICE
// << ", h0=" << h0
// << ", h1=" << h0
// << ", dh=" << dh
// //<< ", h_delta=" << h_delta
// << ", accel = " << _set_viewpoint_accel
// << ", archeight = " << _arc_height
// << std::endl;
_setting_viewpoint = true;
_thrown = false;
_task->_type = TASK_NONE;
recalculateCenter( getMyCoordinateFrame(_center) );
//recalculateCenter( getCoordinateFrame(_center) );
}
else
{
osg::Vec3d new_center = vp.getFocalPoint();
// start by transforming the requested focal point into world coordinates:
if ( getSRS() )
{
// resolve the VP's srs. If the VP's SRS is not specified, assume that it
// is either lat/long (if the map is geocentric) or X/Y (otherwise).
osg::ref_ptr<const SpatialReference> vp_srs = vp.getSRS()? vp.getSRS() :
_is_geocentric? getSRS()->getGeographicSRS() :
getSRS();
if ( !getSRS()->isEquivalentTo( vp_srs.get() ) )
{
osg::Vec3d local = new_center;
// reproject the focal point if necessary:
vp_srs->transform2D( new_center.x(), new_center.y(), getSRS(), local.x(), local.y() );
new_center = local;
}
// convert to geocentric coords if necessary:
if ( _is_geocentric )
{
osg::Vec3d geocentric;
getSRS()->getEllipsoid()->convertLatLongHeightToXYZ(
osg::DegreesToRadians( new_center.y() ),
osg::DegreesToRadians( new_center.x() ),
new_center.z(),
geocentric.x(), geocentric.y(), geocentric.z() );
new_center = geocentric;
}
}
// now calculate the new rotation matrix based on the angles:
double new_pitch = osg::DegreesToRadians(
osg::clampBetween( vp.getPitch(), _settings->getMinPitch(), _settings->getMaxPitch() ) );
double new_azim = normalizeAzimRad( osg::DegreesToRadians( vp.getHeading() ) );
_center = new_center;
setDistance( vp.getRange() );
osg::CoordinateFrame local_frame = getMyCoordinateFrame( new_center ); //getCoordinateFrame( new_center );
_previousUp = getUpVector( local_frame );
_centerRotation = getRotation( new_center ).getRotate().inverse();
osg::Quat azim_q( new_azim, osg::Vec3d(0,0,1) );
osg::Quat pitch_q( -new_pitch -osg::PI_2, osg::Vec3d(1,0,0) );
osg::Matrix new_rot = osg::Matrixd( azim_q * pitch_q );
_rotation = osg::Matrixd::inverse(new_rot).getRotate();
//OE_NOTICE << "Pitch old=" << _local_pitch << " new=" << new_pitch << std::endl;
//OE_NOTICE << "Azim old=" << _local_azim << " new=" << new_azim << std::endl;
_local_pitch = new_pitch;
_local_azim = new_azim;
// re-intersect the terrain to get a new correct center point, but only if this is
// NOT a viewpoint transition update. (disabled check for now)
//if ( !_setting_viewpoint )
recalculateCenter( local_frame );
}
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::updateCamera | ( | osg::Camera * | eventCamera | ) | [private] |
Definition at line 1148 of file EarthManipulator.cpp.
{
// check to see if the camera has changed, and update the callback if necessary
if ( _viewCamera.get() != eventCamera )
{
if ( _cameraUpdateCB.valid() )
_viewCamera->removeUpdateCallback( _cameraUpdateCB.get() );
_viewCamera = eventCamera;
if ( _cameraUpdateCB.valid() )
_viewCamera->addUpdateCallback( _cameraUpdateCB.get() );
}
// check to see if we need to install a new camera callback:
if ( _tether_node.valid() && !_cameraUpdateCB.valid() )
{
_cameraUpdateCB = new CameraPostUpdateCallback(this);
_viewCamera->addUpdateCallback( _cameraUpdateCB.get() );
}
else if ( !_tether_node.valid() && _cameraUpdateCB.valid() )
{
_viewCamera->removeUpdateCallback( _cameraUpdateCB.get() );
_cameraUpdateCB = 0L;
}
}
Here is the caller graph for this function:| void osgEarth::Util::EarthManipulator::updateHandCam | ( | const osg::Timer_t & | now | ) | [private] |
| void EarthManipulator::updateSetViewpoint | ( | ) | [private] |
Definition at line 962 of file EarthManipulator.cpp.
{
double t = ( _time_s_now - _time_s_set_viewpoint ) / _set_viewpoint_duration_s;
double tp = t;
if ( t >= 1.0 )
{
t = tp = 1.0;
_setting_viewpoint = false;
}
else if ( _arc_height > 0.0 )
{
if ( tp <= 0.5 )
{
double t2 = 2.0*tp;
t2 = accelerationInterp( t2, _set_viewpoint_accel );
tp = 0.5*t2;
}
else
{
double t2 = 2.0*(tp-0.5);
t2 = accelerationInterp( t2, _set_viewpoint_accel_2 );
tp = 0.5+(0.5*t2);
}
// the more smoothsteps you do, the more pronounced the fade-in/out effect
tp = smoothStepInterp( tp );
tp = smoothStepInterp( tp );
}
else if ( t > 0.0 )
{
tp = accelerationInterp( tp, _set_viewpoint_accel );
tp = smoothStepInterp( tp );
}
Viewpoint new_vp(
_start_viewpoint.getFocalPoint() + _delta_focal_point * tp,
_start_viewpoint.getHeading() + _delta_heading * tp,
_start_viewpoint.getPitch() + _delta_pitch * tp,
_start_viewpoint.getRange() + _delta_range * tp + (sin(osg::PI*tp)*_arc_height),
_start_viewpoint.getSRS() );
#if 0
OE_INFO
<< "t=" << t
<< ", tp=" << tp
<< ", tsv=" << _time_s_set_viewpoint
<< ", now=" << _time_s_now
<< ", accel=" << _set_viewpoint_accel
<< ", accel2=" << _set_viewpoint_accel_2
<< std::endl;
#endif
setViewpoint( new_vp );
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::updateTether | ( | ) | [private] |
Definition at line 1369 of file EarthManipulator.cpp.
{
// capture a temporary ref since _tether_node is just an observer:
osg::ref_ptr<osg::Node> temp = _tether_node.get();
if ( temp.valid() )
{
osg::NodePathList nodePaths = temp->getParentalNodePaths();
if ( nodePaths.empty() )
return;
osg::NodePath path = nodePaths[0];
osg::Matrixd localToWorld = osg::computeLocalToWorld( path );
_center = osg::Vec3d(0,0,0) * localToWorld;
// if the tether node is a MT, we are set. If it's not, we need to get the
// local bound and add its translation to the localToWorld. We cannot just use
// the bounds directly because they are single precision (unless you built OSG
// with double-precision bounding spheres, which you probably did not :)
if ( !dynamic_cast<osg::MatrixTransform*>( temp.get() ) )
{
const osg::BoundingSphere& bs = temp->getBound();
_center += bs.center();
}
//OE_INFO
// << std::fixed << std::setprecision(3)
// << "Tether center: (" << _center.x() << "," << _center.y() << "," << _center.z()
// << "); bbox center: (" << bs.center().x() << "," << bs.center().y() << "," << bs.center().z() << ")"
// << std::endl;
osg::CoordinateFrame local_frame = getMyCoordinateFrame( _center ); //getCoordinateFrame( _center );
_previousUp = getUpVector( local_frame );
// osg::Matrixd localToWorld = osg::computeLocalToWorld( path );
double sx = 1.0/sqrt(localToWorld(0,0)*localToWorld(0,0) + localToWorld(1,0)*localToWorld(1,0) + localToWorld(2,0)*localToWorld(2,0));
double sy = 1.0/sqrt(localToWorld(0,1)*localToWorld(0,1) + localToWorld(1,1)*localToWorld(1,1) + localToWorld(2,1)*localToWorld(2,1));
double sz = 1.0/sqrt(localToWorld(0,2)*localToWorld(0,2) + localToWorld(1,2)*localToWorld(1,2) + localToWorld(2,2)*localToWorld(2,2));
localToWorld = localToWorld*osg::Matrixd::scale(sx,sy,sz);
// didn't we just call this a few lines ago?
//osg::CoordinateFrame coordinateFrame = getMyCoordinateFrame( _center ); //getCoordinateFrame(_center);
//Just track the center
if (_settings->getTetherMode() == TETHER_CENTER)
{
_centerRotation = local_frame.getRotate(); //coordinateFrame.getRotate();
}
//Track all rotations
else if (_settings->getTetherMode() == TETHER_CENTER_AND_ROTATION)
{
_centerRotation = localToWorld.getRotate();
}
else if (_settings->getTetherMode() == TETHER_CENTER_AND_HEADING)
{
//Track just the heading
osg::Matrixd localToFrame(localToWorld*osg::Matrixd::inverse( local_frame )); //coordinateFrame));
double azim = atan2(-localToFrame(0,1),localToFrame(0,0));
osg::Quat nodeRotationRelToFrame, rotationOfFrame;
nodeRotationRelToFrame.makeRotate(-azim,0.0,0.0,1.0);
rotationOfFrame = local_frame.getRotate(); //coordinateFrame.getRotate();
_centerRotation = nodeRotationRelToFrame*rotationOfFrame;
}
}
}
Here is the call graph for this function:
Here is the caller graph for this function:| void EarthManipulator::zoom | ( | double | dx, |
| double | dy | ||
| ) | [virtual] |
Zoom the camera using deltas (dy only)
Definition at line 1842 of file EarthManipulator.cpp.
{
double fd = 1000;
double scale = 1.0f + dy;
if ( fd * scale > _settings->getMinDistance() )
{
setDistance( _distance * scale );
}
else
{
setDistance( _settings->getMinDistance() );
}
}
Here is the call graph for this function:
Here is the caller graph for this function:friend struct CameraUpdateCallback [friend] |
Definition at line 821 of file EarthManipulator.
bool osgEarth::Util::EarthManipulator::_after_first_frame [private] |
Definition at line 804 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_arc_height [private] |
Definition at line 797 of file EarthManipulator.
osg::ref_ptr<const osgEarth::SpatialReference> osgEarth::Util::EarthManipulator::_cached_srs [private] |
Definition at line 752 of file EarthManipulator.
osg::observer_ptr<CameraPostUpdateCallback> osgEarth::Util::EarthManipulator::_cameraUpdateCB [private] |
Definition at line 823 of file EarthManipulator.
osg::Vec3d osgEarth::Util::EarthManipulator::_center [private] |
Definition at line 765 of file EarthManipulator.
osg::Quat osgEarth::Util::EarthManipulator::_centerRotation [private] |
Definition at line 772 of file EarthManipulator.
bool osgEarth::Util::EarthManipulator::_continuous [private] |
Definition at line 782 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_continuous_dx [private] |
Definition at line 783 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_continuous_dy [private] |
Definition at line 784 of file EarthManipulator.
osg::observer_ptr<osg::CoordinateSystemNode> osgEarth::Util::EarthManipulator::_csn [private] |
Definition at line 746 of file EarthManipulator.
osg::NodePath osgEarth::Util::EarthManipulator::_csnPath [private] |
Definition at line 750 of file EarthManipulator.
osg::Vec3d osgEarth::Util::EarthManipulator::_delta_focal_point [private] |
Definition at line 798 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_delta_heading [private] |
Definition at line 797 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_delta_pitch [private] |
Definition at line 797 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_delta_range [private] |
Definition at line 797 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_delta_t [private] |
Definition at line 761 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_distance [private] |
Definition at line 773 of file EarthManipulator.
osg::ref_ptr<const osgGA::GUIEventAdapter> osgEarth::Util::EarthManipulator::_ga_t0 [private] |
Definition at line 740 of file EarthManipulator.
osg::ref_ptr<const osgGA::GUIEventAdapter> osgEarth::Util::EarthManipulator::_ga_t1 [private] |
Definition at line 739 of file EarthManipulator.
bool osgEarth::Util::EarthManipulator::_has_pending_viewpoint [private] |
Definition at line 791 of file EarthManipulator.
Definition at line 808 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_homeViewpointDuration [private] |
Definition at line 809 of file EarthManipulator.
bool osgEarth::Util::EarthManipulator::_is_geocentric [private] |
Definition at line 753 of file EarthManipulator.
Definition at line 811 of file EarthManipulator.
osg::Vec3d osgEarth::Util::EarthManipulator::_lastPointOnEarth [private] |
Definition at line 828 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_local_azim [private] |
Definition at line 780 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_local_pitch [private] |
Definition at line 779 of file EarthManipulator.
osg::ref_ptr<const osgGA::GUIEventAdapter> osgEarth::Util::EarthManipulator::_mouse_down_event [private] |
Definition at line 742 of file EarthManipulator.
osg::observer_ptr<osg::Node> osgEarth::Util::EarthManipulator::_node [private] |
Definition at line 745 of file EarthManipulator.
osg::Timer_t osgEarth::Util::EarthManipulator::_now [private] |
Definition at line 760 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_offset_x [private] |
Definition at line 774 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_offset_y [private] |
Definition at line 775 of file EarthManipulator.
Definition at line 792 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_pending_viewpoint_duration_s [private] |
Definition at line 793 of file EarthManipulator.
osg::Vec3d osgEarth::Util::EarthManipulator::_previousUp [private] |
Definition at line 776 of file EarthManipulator.
osg::Quat osgEarth::Util::EarthManipulator::_rotation [private] |
Definition at line 768 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_set_viewpoint_accel [private] |
Definition at line 801 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_set_viewpoint_accel_2 [private] |
Definition at line 802 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_set_viewpoint_duration_s [private] |
Definition at line 800 of file EarthManipulator.
bool osgEarth::Util::EarthManipulator::_setting_viewpoint [private] |
Definition at line 795 of file EarthManipulator.
osg::ref_ptr<Settings> osgEarth::Util::EarthManipulator::_settings [private] |
Definition at line 806 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_single_axis_x [private] |
Definition at line 786 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_single_axis_y [private] |
Definition at line 787 of file EarthManipulator.
bool osgEarth::Util::EarthManipulator::_srs_lookup_failed [private] |
Definition at line 754 of file EarthManipulator.
Definition at line 796 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_t_factor [private] |
Definition at line 762 of file EarthManipulator.
osg::ref_ptr<Task> osgEarth::Util::EarthManipulator::_task [private] |
Definition at line 777 of file EarthManipulator.
osg::observer_ptr<osg::Node> osgEarth::Util::EarthManipulator::_tether_node [private] |
Definition at line 756 of file EarthManipulator.
bool osgEarth::Util::EarthManipulator::_thrown [private] |
Definition at line 763 of file EarthManipulator.
osg::Timer_t osgEarth::Util::EarthManipulator::_time_last_frame [private] |
Definition at line 778 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_time_s_last_frame [private] |
Definition at line 758 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_time_s_now [private] |
Definition at line 759 of file EarthManipulator.
double osgEarth::Util::EarthManipulator::_time_s_set_viewpoint [private] |
Definition at line 799 of file EarthManipulator.
osg::observer_ptr<osg::Camera> osgEarth::Util::EarthManipulator::_viewCamera [private] |
Definition at line 813 of file EarthManipulator.
EarthManipulator::Action EarthManipulator::NullAction [static, private] |
Definition at line 179 of file EarthManipulator.
1.7.3