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 
54 // move camera up so the focal point appears in the lower image half
55 static const float CAMERA_OFFSET = 0.2;
56 
58 {
60  focal_shape_->setColor(0.0f, 1.0f, 1.0f, 0.5f);
61 }
62 
63 bool ThirdPersonFollowerViewController::intersectGroundPlane( Ogre::Ray mouse_ray, 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 ) * mouse_ray.getDirection() );
68 
69  Ogre::Plane ground_plane( Ogre::Vector3::UNIT_Z, 0 );
70 
71  std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(ground_plane);
72  if (!intersection.first)
73  {
74  return false;
75  }
76 
77  intersection_3d = mouse_ray.getPoint(intersection.second);
78  return true;
79 }
80 
82 {
83  if ( event.shift() )
84  {
85  setStatus( "<b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom." );
86  }
87  else
88  {
89  setStatus( "<b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z. <b>Shift</b>: More options." );
90  }
91 
92  int32_t diff_x = 0;
93  int32_t diff_y = 0;
94 
95  bool moved = false;
96  if( event.type == QEvent::MouseButtonPress )
97  {
98  focal_shape_->getRootNode()->setVisible(true);
99  moved = true;
100  }
101  else if( event.type == QEvent::MouseButtonRelease )
102  {
103  focal_shape_->getRootNode()->setVisible(false);
104  moved = true;
105  }
106  else if( event.type == QEvent::MouseMove )
107  {
108  diff_x = event.x - event.last_x;
109  diff_y = event.y - event.last_y;
110  moved = true;
111  }
112 
113  if( event.left() && !event.shift() )
114  {
115  setCursor( Rotate3D );
116  yaw( diff_x*0.005 );
117  pitch( -diff_y*0.005 );
118  }
119  else if( event.middle() || (event.left() && event.shift()) )
120  {
121  setCursor( MoveXY );
122  // handle mouse movement
123  int width = event.viewport->getActualWidth();
124  int height = event.viewport->getActualHeight();
125 
126  Ogre::Ray mouse_ray = event.viewport->getCamera()->getCameraToViewportRay( event.x / (float) width,
127  event.y / (float) height );
128 
129  Ogre::Ray last_mouse_ray =
130  event.viewport->getCamera()->getCameraToViewportRay( event.last_x / (float) width,
131  event.last_y / (float) height );
132 
133  Ogre::Vector3 last_intersect, intersect;
134 
135  if( intersectGroundPlane( last_mouse_ray, last_intersect ) &&
136  intersectGroundPlane( mouse_ray, intersect ))
137  {
138  Ogre::Vector3 motion = last_intersect - intersect;
139 
140  // When dragging near the horizon, the motion can get out of
141  // control. This throttles it to an arbitrary limit per mouse
142  // event.
143  float motion_distance_limit = 1; /*meter*/
144  if( motion.length() > motion_distance_limit )
145  {
146  motion.normalise();
147  motion *= motion_distance_limit;
148  }
149 
150  focal_point_property_->add( motion );
152  }
153  }
154  else if( event.right() )
155  {
156  setCursor( Zoom );
157  zoom( -diff_y * 0.1 * (distance_property_->getFloat() / 10.0f) );
158  }
159  else
160  {
161  setCursor( event.shift() ? MoveXY : Rotate3D );
162  }
163 
164  if( event.wheel_delta != 0 )
165  {
166  int diff = event.wheel_delta;
167  zoom( diff * 0.001 * distance_property_->getFloat() );
168  moved = true;
169  }
170 
171  if( moved )
172  {
174  }
175 }
176 
178 {
180 
181  Ogre::Camera* source_camera = source_view->getCamera();
182  // do some trigonometry
183  Ogre::Ray camera_dir_ray( source_camera->getRealPosition(), source_camera->getRealDirection() );
184  Ogre::Ray camera_down_ray( source_camera->getRealPosition(), -1.0 * source_camera->getRealUp() );
185 
186  Ogre::Vector3 a,b;
187 
188  if( intersectGroundPlane( camera_dir_ray, b ) &&
189  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 ));
196 
197  camera_dir_ray.setOrigin( source_camera->getRealPosition() - source_camera->getRealUp() * distance * CAMERA_OFFSET );
198  Ogre::Vector3 new_focal_point;
199  intersectGroundPlane( camera_dir_ray, new_focal_point );
200  focal_point_property_->setVector( new_focal_point );
201 
202  calculatePitchYawFromPosition( source_camera->getPosition() - source_camera->getUp() * distance * CAMERA_OFFSET );
203  }
204 }
205 
207 {
209  camera_->setPosition( camera_->getPosition() + camera_->getUp() * distance_property_->getFloat() * CAMERA_OFFSET );
210 }
211 
213 {
215  {
216  target_scene_node_->setPosition( reference_position_ );
217  Ogre::Radian ref_yaw = reference_orientation_.getRoll( false ); // OGRE camera frame looks along -Z, so they call rotation around Z "roll".
218  Ogre::Quaternion ref_yaw_quat(Ogre::Math::Cos(ref_yaw/2), 0, 0, Ogre::Math::Sin(ref_yaw/2));
219  target_scene_node_->setOrientation( ref_yaw_quat );
220 
222  }
223 }
224 
225 void ThirdPersonFollowerViewController::lookAt( const Ogre::Vector3& point )
226 {
227  Ogre::Vector3 camera_position = camera_->getPosition();
228  Ogre::Vector3 new_focal_point = target_scene_node_->getOrientation().Inverse() * (point - target_scene_node_->getPosition());
229  new_focal_point.z = 0;
230  distance_property_->setFloat( new_focal_point.distance( camera_position ));
231  focal_point_property_->setVector( new_focal_point );
232 
233  calculatePitchYawFromPosition(camera_position);
234 }
235 
236 } // end namespace rviz
237 
FloatProperty * distance_property_
The camera&#39;s distance from the focal point.
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 void mimic(ViewController *source_view)
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
virtual void updateTargetSceneNode()
Update the position of the target_scene_node_ from the TF frame specified in the Target Frame propert...
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.
void setCursor(CursorType cursor_type)
virtual float getFloat() const
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set.
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
static const float CAMERA_OFFSET
Ogre::Camera * camera_
bool add(const Ogre::Vector3 &offset)
virtual void setColor(float r, float g, float b, float a)
Set the color of the object. Values are in the range [0, 1].
Definition: shape.cpp:142
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
VectorProperty * focal_point_property_
The point around which the camera "orbits".
Ogre::Camera * getCamera() const
void setStatus(const QString &message)
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set.
virtual void mimic(ViewController *source_view)
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
virtual void lookAt(const Ogre::Vector3 &point)
This should be implemented in each subclass to aim the camera at the given point in space (relative t...
Ogre::SceneNode * getRootNode()
Get the root scene node (pivot node) for this object.
Definition: shape.h:97
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 Wed Aug 28 2019 04:01:51