Go to the documentation of this file.
34 #include <OgreCamera.h>
35 #include <OgrePlane.h>
36 #include <OgreQuaternion.h>
38 #include <OgreSceneNode.h>
40 #include <OgreViewport.h>
63 Ogre::Vector3& intersection_3d)
66 mouse_ray.setOrigin(
target_scene_node_->convertWorldToLocalPosition(mouse_ray.getOrigin()));
67 mouse_ray.setDirection(
target_scene_node_->convertWorldToLocalOrientation(Ogre::Quaternion::IDENTITY) *
68 mouse_ray.getDirection());
70 Ogre::Plane ground_plane(Ogre::Vector3::UNIT_Z, 0);
72 std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(ground_plane);
73 if (!intersection.first)
78 intersection_3d = mouse_ray.getPoint(intersection.second);
86 setStatus(
"<b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom.");
90 setStatus(
"<b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z. "
91 " <b>Shift</b>: More options.");
98 if (event.
type == QEvent::MouseButtonPress)
103 else if (event.
type == QEvent::MouseButtonRelease)
108 else if (event.
type == QEvent::MouseMove)
110 diff_x =
event.x -
event.last_x;
111 diff_y =
event.y -
event.last_y;
119 pitch(-diff_y * 0.005);
125 int width =
event.viewport->getActualWidth();
126 int height =
event.viewport->getActualHeight();
128 Ogre::Ray mouse_ray =
event.viewport->getCamera()->getCameraToViewportRay(event.
x / (
float)width,
129 event.
y / (
float)height);
131 Ogre::Ray last_mouse_ray =
event.viewport->getCamera()->getCameraToViewportRay(
132 event.
last_x / (
float)width, event.
last_y / (
float)height);
134 Ogre::Vector3 last_intersect, intersect;
139 Ogre::Vector3 motion = last_intersect - intersect;
144 float motion_distance_limit = 1;
145 if (motion.length() > motion_distance_limit)
148 motion *= motion_distance_limit;
155 else if (event.
right())
167 int diff =
event.wheel_delta;
182 Ogre::Camera* source_camera = source_view->
getCamera();
184 Ogre::Ray camera_dir_ray(source_camera->getRealPosition(), source_camera->getRealDirection());
185 Ogre::Ray camera_down_ray(source_camera->getRealPosition(), -1.0 * source_camera->getRealUp());
191 float l_a = source_camera->getPosition().distance(b);
192 float l_b = source_camera->getPosition().distance(a);
197 camera_dir_ray.setOrigin(source_camera->getRealPosition() -
199 Ogre::Vector3 new_focal_point;
222 Ogre::Quaternion ref_yaw_quat(Ogre::Math::Cos(ref_yaw / 2), 0, 0, Ogre::Math::Sin(ref_yaw / 2));
231 Ogre::Vector3 camera_position =
camera_->getPosition();
232 Ogre::Vector3 new_focal_point =
234 new_focal_point.z = 0;
void zoom(float amount)
Move in/out from the focal point, ie. adjust #distance_ by amount.
Ogre::Vector3 reference_position_
Ogre::SceneNode * getRootNode()
Get the root scene node (pivot node) for this object.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
void setColor(float r, float g, float b, float a) override
Set the color of the object. Values are in the range [0, 1].
VectorProperty * focal_point_property_
The point around which the camera "orbits".
void mimic(ViewController *source_view) override
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
FloatProperty * distance_property_
The camera's distance from the focal point.
void lookAt(const Ogre::Vector3 &point) override
This should be implemented in each subclass to aim the camera at the given point in space (relative t...
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_,...
void handleMouseEvent(ViewportMouseEvent &evt) override
DisplayContext * context_
void updateCamera() override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual float getFloat() const
void calculatePitchYawFromPosition(const Ogre::Vector3 &position)
Calculates pitch and yaw values given a new position and the current focal point.
virtual bool setVector(const Ogre::Vector3 &vector)
virtual void updateCamera()
Ogre::Quaternion reference_orientation_
Like the orbit view controller, but focal point moves only in the x-y plane.
void mimic(ViewController *source_view) override
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
Ogre::Camera * getCamera() const
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
void emitConfigChanged()
Subclasses should call this whenever a change is made which would change the results of toString().
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_,...
void updateTargetSceneNode() override
Update the position of the target_scene_node_ from the TF frame specified in the Target Frame propert...
void setCursor(CursorType cursor_type)
bool intersectGroundPlane(Ogre::Ray mouse_ray, Ogre::Vector3 &intersection_3d)
void setStatus(const QString &message)
static const float CAMERA_OFFSET
bool add(const Ogre::Vector3 &offset)
Ogre::SceneNode * target_scene_node_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:10