31 #include <OgrePlane.h> 32 #include <OgreCamera.h> 33 #include <OgreSceneNode.h> 34 #include <OgreViewport.h> 47 Ogre::Vector3& intersection_out)
49 int width = viewport->getActualWidth();
50 int height = viewport->getActualHeight();
52 Ogre::Ray mouse_ray = viewport->getCamera()->getCameraToViewportRay((
float)window_x / (
float)width,
53 (
float)window_y / (
float)height);
54 std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(plane);
55 if (!intersection.first)
59 intersection_out = mouse_ray.getPoint(intersection.second);
66 angle = fmod(angle, Ogre::Math::TWO_PI);
70 angle = Ogre::Math::TWO_PI + angle;
77 Ogre::Camera* cam = view->getCamera();
78 Ogre::Vector3 pos2D = cam->getProjectionMatrix() * (cam->getViewMatrix() * pos);
80 Ogre::Real x = ((pos2D.x * 0.5) + 0.5);
81 Ogre::Real y = 1 - ((pos2D.y * 0.5) + 0.5);
83 return Ogre::Vector2(x * view->getActualWidth(), y * view->getActualHeight());
float mapAngleTo0_2Pi(float angle)
Return the input angle mapped back to the range 0 to 2*PI.
Ogre::Vector2 project3DPointToViewportXY(const Ogre::Viewport *view, const Ogre::Vector3 &pos)
Given a viewport and a 3D position in world coordinates, project that point into the view plane...
bool getPointOnPlaneFromWindowXY(Ogre::Viewport *viewport, Ogre::Plane &plane, int window_x, int window_y, Ogre::Vector3 &intersection_out)
Given a viewport and an x,y position in window-pixel coordinates, find the point on a plane directly ...