fps_view_controller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, 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 <OgreViewport.h>
31 #include <OgreQuaternion.h>
32 #include <OgreVector3.h>
33 #include <OgreSceneNode.h>
34 #include <OgreSceneManager.h>
35 #include <OgreCamera.h>
36 
38 #include "rviz/display_context.h"
40 #include "rviz/geometry.h"
45 
46 #include "fps_view_controller.h"
47 
48 namespace rviz
49 {
50 
51 static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION =
52  Ogre::Quaternion( Ogre::Radian( -Ogre::Math::HALF_PI ), Ogre::Vector3::UNIT_Y ) *
53  Ogre::Quaternion( Ogre::Radian( -Ogre::Math::HALF_PI ), Ogre::Vector3::UNIT_Z );
54 
55 static const float PITCH_LIMIT_LOW = -Ogre::Math::HALF_PI + 0.001;
56 static const float PITCH_LIMIT_HIGH = Ogre::Math::HALF_PI - 0.001;
57 
59 {
60  yaw_property_ = new FloatProperty( "Yaw", 0, "Rotation of the camera around the Z (up) axis.", this );
61 
62  pitch_property_ = new FloatProperty( "Pitch", 0, "How much the camera is tipped downward.", this );
63  pitch_property_->setMax( Ogre::Math::HALF_PI - 0.001 );
65 
66  position_property_ = new VectorProperty( "Position", Ogre::Vector3( 5, 5, 10 ), "Position of the camera.", this );
67 }
68 
70 {
71 }
72 
74 {
76  camera_->setProjectionType( Ogre::PT_PERSPECTIVE );
77  invert_z_->hide();
78 }
79 
81 {
82  camera_->setPosition( Ogre::Vector3( 5, 5, 10 ));
83  camera_->lookAt( 0, 0, 0 );
85 
86  // Hersh says: why is the following junk necessary? I don't know.
87  // However, without this you need to call reset() twice after
88  // switching from TopDownOrtho to FPS. After the first call the
89  // camera is in the right position but pointing the wrong way.
90  updateCamera();
91  camera_->lookAt( 0, 0, 0 );
93 }
94 
96 {
97  if ( event.shift() )
98  {
99  setStatus( "<b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z." );
100  }
101  else
102  {
103  setStatus( "<b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom. <b>Shift</b>: More options." );
104  }
105 
106  bool moved = false;
107 
108  int32_t diff_x = 0;
109  int32_t diff_y = 0;
110 
111  if( event.type == QEvent::MouseMove )
112  {
113  diff_x = event.x - event.last_x;
114  diff_y = event.y - event.last_y;
115  moved = true;
116  }
117 
118  if( event.left() && !event.shift() )
119  {
120  setCursor( Rotate3D );
121  yaw( -diff_x*0.005 );
122  pitch( diff_y*0.005 );
123  }
124  else if( event.middle() || ( event.shift() && event.left() ))
125  {
126  setCursor( MoveXY );
127  move( diff_x*0.01, -diff_y*0.01, 0.0f );
128  }
129  else if( event.right() )
130  {
131  setCursor( MoveZ );
132  move( 0.0f, 0.0f, diff_y*0.1 );
133  }
134  else
135  {
136  setCursor( event.shift() ? MoveXY : Rotate3D );
137  }
138 
139  if ( event.wheel_delta != 0 )
140  {
141  int diff = event.wheel_delta;
142  move( 0.0f, 0.0f, -diff * 0.01 );
143 
144  moved = true;
145  }
146 
147  if (moved)
148  {
150  }
151 }
152 
153 void FPSViewController::setPropertiesFromCamera( Ogre::Camera* source_camera )
154 {
155  Ogre::Quaternion quat = source_camera->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse();
156  float yaw = quat.getRoll( false ).valueRadians(); // OGRE camera frame looks along -Z, so they call rotation around Z "roll".
157  float pitch = quat.getYaw( false ).valueRadians(); // OGRE camera frame has +Y as "up", so they call rotation around Y "yaw".
158 
159  Ogre::Vector3 direction = quat * Ogre::Vector3::NEGATIVE_UNIT_Z;
160 
161  if ( direction.dotProduct( Ogre::Vector3::NEGATIVE_UNIT_Z ) < 0 )
162  {
163  if ( pitch > Ogre::Math::HALF_PI )
164  {
165  pitch -= Ogre::Math::PI;
166  }
167  else if ( pitch < -Ogre::Math::HALF_PI )
168  {
169  pitch += Ogre::Math::PI;
170  }
171 
172  yaw = -yaw;
173 
174  if ( direction.dotProduct( Ogre::Vector3::UNIT_X ) < 0 )
175  {
176  yaw -= Ogre::Math::PI;
177  }
178  else
179  {
180  yaw += Ogre::Math::PI;
181  }
182  }
183 
184  pitch_property_->setFloat( pitch );
186  position_property_->setVector( source_camera->getPosition() );
187 }
188 
190 {
192  setPropertiesFromCamera( source_view->getCamera() );
193 }
194 
195 void FPSViewController::update(float dt, float ros_dt)
196 {
198  updateCamera();
199 }
200 
201 void FPSViewController::lookAt( const Ogre::Vector3& point )
202 {
203  camera_->lookAt( point );
205 }
206 
207 void FPSViewController::onTargetFrameChanged(const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation)
208 {
209  position_property_->add( old_reference_position - reference_position_ );
210 }
211 
213 {
214  camera_->setOrientation( getOrientation() );
215  camera_->setPosition( position_property_->getVector() );
216 }
217 
218 void FPSViewController::yaw( float angle )
219 {
221 }
222 
223 void FPSViewController::pitch( float angle )
224 {
225  pitch_property_->add( angle );
226 }
227 
229 {
230  Ogre::Quaternion pitch, yaw;
231 
232  yaw.FromAngleAxis( Ogre::Radian( yaw_property_->getFloat() ), Ogre::Vector3::UNIT_Z );
233  pitch.FromAngleAxis( Ogre::Radian( pitch_property_->getFloat() ), Ogre::Vector3::UNIT_Y );
234 
235  return yaw * pitch * ROBOT_TO_CAMERA_ROTATION;
236 }
237 
238 void FPSViewController::move( float x, float y, float z )
239 {
240  Ogre::Vector3 translate( x, y, z );
241  position_property_->add( getOrientation() * translate );
242 }
243 
244 } // end namespace rviz
245 
Ogre::Quaternion getOrientation()
Return a Quaternion based on the yaw and pitch properties.
void setMin(float min)
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...
void setMax(float max)
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set. This version calls updateTargetSceneNode().
virtual bool setVector(const Ogre::Vector3 &vector)
FloatProperty * pitch_property_
The camera&#39;s pitch (rotation around the x-axis), in radians.
f
A first-person camera, controlled by yaw, pitch, and position.
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...
void setCursor(CursorType cursor_type)
virtual float getFloat() const
VectorProperty * position_property_
BoolProperty * invert_z_
Ogre::Camera * camera_
Property specialized to enforce floating point max/min.
virtual void handleMouseEvent(ViewportMouseEvent &evt)
bool add(const Ogre::Vector3 &offset)
virtual void onTargetFrameChanged(const Ogre::Vector3 &old_reference_position, const Ogre::Quaternion &old_reference_orientation)
Override to implement the change in properties which nullifies the change in target frame...
float mapAngleTo0_2Pi(float angle)
Return the input angle mapped back to the range 0 to 2*PI.
Definition: geometry.cpp:64
bool add(float delta)
Add the given delta to the property value.
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
void move(float x, float y, float z)
virtual void update(float dt, float ros_dt)
Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to r...
void setPropertiesFromCamera(Ogre::Camera *source_camera)
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...
Ogre::Camera * getCamera() const
void setStatus(const QString &message)
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
virtual Ogre::Vector3 getVector() const
virtual void update(float dt, float ros_dt)
Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to r...
FloatProperty * yaw_property_
The camera&#39;s yaw (rotation around the y-axis), in radians.
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set. This version calls updateTargetSceneNode().
static const float PITCH_LIMIT_HIGH
void hide()
Hide this Property in any PropertyTreeWidgets.
Definition: property.h:371
static const float PITCH_LIMIT_LOW
DisplayContext * context_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION


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