xy_orbit_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 
42 #include "rviz/display_context.h"
47 
49 
50 namespace rviz
51 {
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 
62 bool XYOrbitViewController::intersectGroundPlane( Ogre::Ray mouse_ray, Ogre::Vector3 &intersection_3d )
63 {
64  //convert rays into reference frame
65  mouse_ray.setOrigin( target_scene_node_->convertWorldToLocalPosition( mouse_ray.getOrigin() ) );
66  mouse_ray.setDirection( target_scene_node_->convertWorldToLocalOrientation( Ogre::Quaternion::IDENTITY ) * mouse_ray.getDirection() );
67 
68  Ogre::Plane ground_plane( Ogre::Vector3::UNIT_Z, 0 );
69 
70  std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(ground_plane);
71  if (!intersection.first)
72  {
73  return false;
74  }
75 
76  intersection_3d = mouse_ray.getPoint(intersection.second);
77  return true;
78 }
79 
81 {
82  if ( event.shift() )
83  {
84  setStatus( "<b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom." );
85  }
86  else
87  {
88  setStatus( "<b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z. <b>Shift</b>: More options." );
89  }
90 
91  int32_t diff_x = 0;
92  int32_t diff_y = 0;
93 
94  bool moved = false;
95  if( event.type == QEvent::MouseButtonPress )
96  {
97  focal_shape_->getRootNode()->setVisible(true);
98  moved = true;
99  }
100  else if( event.type == QEvent::MouseButtonRelease )
101  {
102  focal_shape_->getRootNode()->setVisible(false);
103  moved = true;
104  }
105  else if( event.type == QEvent::MouseMove )
106  {
107  diff_x = event.x - event.last_x;
108  diff_y = event.y - event.last_y;
109  moved = true;
110  }
111 
112  if( event.left() && !event.shift() )
113  {
114  setCursor( Rotate3D );
115  yaw( diff_x*0.005 );
116  pitch( -diff_y*0.005 );
117  }
118  else if( event.middle() || (event.left() && event.shift()) )
119  {
120  setCursor( MoveXY );
121  // handle mouse movement
122  int width = event.viewport->getActualWidth();
123  int height = event.viewport->getActualHeight();
124 
125  Ogre::Ray mouse_ray = event.viewport->getCamera()->getCameraToViewportRay( event.x / (float) width,
126  event.y / (float) height );
127 
128  Ogre::Ray last_mouse_ray =
129  event.viewport->getCamera()->getCameraToViewportRay( event.last_x / (float) width,
130  event.last_y / (float) height );
131 
132  Ogre::Vector3 last_intersect, intersect;
133 
134  if( intersectGroundPlane( last_mouse_ray, last_intersect ) &&
135  intersectGroundPlane( mouse_ray, intersect ))
136  {
137  Ogre::Vector3 motion = last_intersect - intersect;
138 
139  // When dragging near the horizon, the motion can get out of
140  // control. This throttles it to an arbitrary limit per mouse
141  // event.
142  float motion_distance_limit = 1; /*meter*/
143  if( motion.length() > motion_distance_limit )
144  {
145  motion.normalise();
146  motion *= motion_distance_limit;
147  }
148 
149  focal_point_property_->add( motion );
151  }
152  }
153  else if( event.right() )
154  {
155  setCursor( Zoom );
156  zoom( -diff_y * 0.1 * (distance_property_->getFloat() / 10.0f) );
157  }
158  else
159  {
160  setCursor( event.shift() ? MoveXY : Rotate3D );
161  }
162 
163  if( event.wheel_delta != 0 )
164  {
165  int diff = event.wheel_delta;
166  zoom( diff * 0.001 * distance_property_->getFloat() );
167  moved = true;
168  }
169 
170  if( moved )
171  {
173  }
174 }
175 
177 {
179 
180  Ogre::Camera* source_camera = source_view->getCamera();
181  // do some trigonometry
182  Ogre::Ray camera_dir_ray( source_camera->getRealPosition(), source_camera->getRealDirection() );
183  Ogre::Ray camera_down_ray( source_camera->getRealPosition(), -1.0 * source_camera->getRealUp() );
184 
185  Ogre::Vector3 a,b;
186 
187  if( intersectGroundPlane( camera_dir_ray, b ) &&
188  intersectGroundPlane( camera_down_ray, a ) )
189  {
190  float l_a = source_camera->getPosition().distance( b );
191  float l_b = source_camera->getPosition().distance( a );
192 
193  distance_property_->setFloat(( l_a * l_b ) / ( CAMERA_OFFSET * l_a + l_b ));
195 
196  camera_dir_ray.setOrigin( source_camera->getRealPosition() - source_camera->getRealUp() * distance * CAMERA_OFFSET );
197  Ogre::Vector3 new_focal_point;
198  intersectGroundPlane( camera_dir_ray, new_focal_point );
199  focal_point_property_->setVector( new_focal_point );
200 
201  calculatePitchYawFromPosition( source_camera->getPosition() - source_camera->getUp() * distance * CAMERA_OFFSET );
202  }
203 }
204 
206 {
208  camera_->setPosition( camera_->getPosition() + camera_->getUp() * distance_property_->getFloat() * CAMERA_OFFSET );
209 }
210 
211 void XYOrbitViewController::lookAt( const Ogre::Vector3& point )
212 {
213  Ogre::Vector3 camera_position = camera_->getPosition();
214  Ogre::Vector3 new_focal_point = target_scene_node_->getOrientation().Inverse() * (point - target_scene_node_->getPosition());
215  new_focal_point.z = 0;
216  distance_property_->setFloat( new_focal_point.distance( camera_position ));
217  focal_point_property_->setVector( new_focal_point );
218 
219  calculatePitchYawFromPosition(camera_position);
220 }
221 
222 } // end namespace rviz
223 
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. ...
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...
bool intersectGroundPlane(Ogre::Ray mouse_ray, Ogre::Vector3 &intersection_3d)
Like the orbit view controller, but focal point moves only in the x-y plane.
virtual bool setVector(const Ogre::Vector3 &vector)
f
virtual void handleMouseEvent(ViewportMouseEvent &evt)
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
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 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 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
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...
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
VectorProperty * focal_point_property_
The point around which the camera "orbits".
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set.
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 queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
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)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:52