third_person_follower_view_controller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <stdint.h>
31 
32 #include <ros/ros.h>
33 
34 #include <OgreCamera.h>
35 #include <OgrePlane.h>
36 #include <OgreQuaternion.h>
37 #include <OgreRay.h>
38 #include <OgreSceneNode.h>
39 #include <OgreVector3.h>
40 #include <OgreViewport.h>
41 #include <OgreMath.h>
42 
43 #include "rviz/display_context.h"
48 
50 
51 namespace rviz
52 {
53 // move camera up so the focal point appears in the lower image half
54 static const float CAMERA_OFFSET = 0.2;
55 
57 {
59  focal_shape_->setColor(0.0f, 1.0f, 1.0f, 0.5f);
60 }
61 
63  Ogre::Vector3& intersection_3d)
64 {
65  // convert rays into reference frame
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());
69 
70  Ogre::Plane ground_plane(Ogre::Vector3::UNIT_Z, 0);
71 
72  std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(ground_plane);
73  if (!intersection.first)
74  {
75  return false;
76  }
77 
78  intersection_3d = mouse_ray.getPoint(intersection.second);
79  return true;
80 }
81 
83 {
84  if (event.shift())
85  {
86  setStatus("<b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom.");
87  }
88  else
89  {
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.");
92  }
93 
94  int32_t diff_x = 0;
95  int32_t diff_y = 0;
96 
97  bool moved = false;
98  if (event.type == QEvent::MouseButtonPress)
99  {
100  focal_shape_->getRootNode()->setVisible(true);
101  moved = true;
102  }
103  else if (event.type == QEvent::MouseButtonRelease)
104  {
105  focal_shape_->getRootNode()->setVisible(false);
106  moved = true;
107  }
108  else if (event.type == QEvent::MouseMove)
109  {
110  diff_x = event.x - event.last_x;
111  diff_y = event.y - event.last_y;
112  moved = true;
113  }
114 
115  if (event.left() && !event.shift())
116  {
118  yaw(diff_x * 0.005);
119  pitch(-diff_y * 0.005);
120  }
121  else if (event.middle() || (event.left() && event.shift()))
122  {
123  setCursor(MoveXY);
124  // handle mouse movement
125  int width = event.viewport->getActualWidth();
126  int height = event.viewport->getActualHeight();
127 
128  Ogre::Ray mouse_ray = event.viewport->getCamera()->getCameraToViewportRay(event.x / (float)width,
129  event.y / (float)height);
130 
131  Ogre::Ray last_mouse_ray = event.viewport->getCamera()->getCameraToViewportRay(
132  event.last_x / (float)width, event.last_y / (float)height);
133 
134  Ogre::Vector3 last_intersect, intersect;
135 
136  if (intersectGroundPlane(last_mouse_ray, last_intersect) &&
137  intersectGroundPlane(mouse_ray, intersect))
138  {
139  Ogre::Vector3 motion = last_intersect - intersect;
140 
141  // When dragging near the horizon, the motion can get out of
142  // control. This throttles it to an arbitrary limit per mouse
143  // event.
144  float motion_distance_limit = 1; /*meter*/
145  if (motion.length() > motion_distance_limit)
146  {
147  motion.normalise();
148  motion *= motion_distance_limit;
149  }
150 
151  focal_point_property_->add(motion);
153  }
154  }
155  else if (event.right())
156  {
157  setCursor(Zoom);
158  zoom(-diff_y * 0.1 * (distance_property_->getFloat() / 10.0f));
159  }
160  else
161  {
162  setCursor(event.shift() ? MoveXY : Rotate3D);
163  }
164 
165  if (event.wheel_delta != 0)
166  {
167  int diff = event.wheel_delta;
168  zoom(diff * 0.001 * distance_property_->getFloat());
169  moved = true;
170  }
171 
172  if (moved)
173  {
175  }
176 }
177 
179 {
181 
182  Ogre::Camera* source_camera = source_view->getCamera();
183  // do some trigonometry
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());
186 
187  Ogre::Vector3 a, b;
188 
189  if (intersectGroundPlane(camera_dir_ray, b) && intersectGroundPlane(camera_down_ray, a))
190  {
191  float l_a = source_camera->getPosition().distance(b);
192  float l_b = source_camera->getPosition().distance(a);
193 
194  distance_property_->setFloat((l_a * l_b) / (CAMERA_OFFSET * l_a + l_b));
195  float distance = distance_property_->getFloat();
196 
197  camera_dir_ray.setOrigin(source_camera->getRealPosition() -
198  source_camera->getRealUp() * distance * CAMERA_OFFSET);
199  Ogre::Vector3 new_focal_point;
200  intersectGroundPlane(camera_dir_ray, new_focal_point);
201  focal_point_property_->setVector(new_focal_point);
202 
203  calculatePitchYawFromPosition(source_camera->getPosition() -
204  source_camera->getUp() * distance * CAMERA_OFFSET);
205  }
206 }
207 
209 {
211  camera_->setPosition(camera_->getPosition() +
213 }
214 
216 {
218  {
220  Ogre::Radian ref_yaw = reference_orientation_.getRoll(
221  false); // OGRE camera frame looks along -Z, so they call rotation around Z "roll".
222  Ogre::Quaternion ref_yaw_quat(Ogre::Math::Cos(ref_yaw / 2), 0, 0, Ogre::Math::Sin(ref_yaw / 2));
223  target_scene_node_->setOrientation(ref_yaw_quat);
224 
226  }
227 }
228 
229 void ThirdPersonFollowerViewController::lookAt(const Ogre::Vector3& point)
230 {
231  Ogre::Vector3 camera_position = camera_->getPosition();
232  Ogre::Vector3 new_focal_point =
233  target_scene_node_->getOrientation().Inverse() * (point - target_scene_node_->getPosition());
234  new_focal_point.z = 0;
235  distance_property_->setFloat(new_focal_point.distance(camera_position));
236  focal_point_property_->setVector(new_focal_point);
237 
238  calculatePitchYawFromPosition(camera_position);
239 }
240 
241 } // end namespace rviz
242 
FloatProperty * distance_property_
The camera&#39;s distance from the focal point.
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...
void calculatePitchYawFromPosition(const Ogre::Vector3 &position)
Calculates pitch and yaw values given a new position and the current focal point. ...
Like the orbit view controller, but focal point moves only in the x-y plane.
virtual bool setVector(const Ogre::Vector3 &vector)
f
void emitConfigChanged()
Subclasses should call this whenever a change is made which would change the results of toString()...
void zoom(float amount)
Move in/out from the focal point, ie. adjust #distance_ by amount.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void setCursor(CursorType cursor_type)
Ogre::Camera * getCamera() const
static const float CAMERA_OFFSET
Ogre::Camera * camera_
void setColor(float r, float g, float b, float a) override
Set the color of the object. Values are in the range [0, 1].
Definition: shape.cpp:140
bool add(const Ogre::Vector3 &offset)
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...
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
VectorProperty * focal_point_property_
The point around which the camera "orbits".
void setStatus(const QString &message)
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
virtual float getFloat() const
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::SceneNode * getRootNode()
Get the root scene node (pivot node) for this object.
Definition: shape.h:100
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set.
void updateTargetSceneNode() override
Update the position of the target_scene_node_ from the TF frame specified in the Target Frame propert...
DisplayContext * context_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool intersectGroundPlane(Ogre::Ray mouse_ray, Ogre::Vector3 &intersection_3d)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:25