fixed_orientation_ortho_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 <OgreCamera.h>
31 #include <OgreQuaternion.h>
32 #include <OgreSceneManager.h>
33 #include <OgreSceneNode.h>
34 #include <OgreVector3.h>
35 #include <OgreViewport.h>
36 
37 #include "rviz/display_context.h"
43 
45 
46 namespace rviz
47 {
48 
50  : dragging_( false )
51 {
52  scale_property_ = new FloatProperty( "Scale", 10, "How much to scale up the size of things in the scene.", this );
53  angle_property_ = new FloatProperty( "Angle", 0, "Angle around the Z axis to rotate.", this );
54  x_property_ = new FloatProperty( "X", 0, "X component of camera position.", this );
55  y_property_ = new FloatProperty( "Y", 0, "Y component of camera position.", this );
56 }
57 
59 {
60 }
61 
63 {
65 
66  camera_->setProjectionType( Ogre::PT_ORTHOGRAPHIC );
67  camera_->setFixedYawAxis( false );
68  invert_z_->hide();
69 }
70 
72 {
75  x_property_->setFloat( 0 );
76  y_property_->setFloat( 0 );
77 }
78 
80 {
81  if ( event.shift() )
82  {
83  setStatus( "<b>Left-Click:</b> Move X/Y." );
84  }
85  else
86  {
87  setStatus( "<b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom. <b>Shift</b>: More options." );
88  }
89 
90  bool moved = false;
91 
92  int32_t diff_x = 0;
93  int32_t diff_y = 0;
94 
95  if( event.type == QEvent::MouseButtonPress )
96  {
97  dragging_ = true;
98  }
99  else if( event.type == QEvent::MouseButtonRelease )
100  {
101  dragging_ = false;
102  }
103  else if( dragging_ && event.type == QEvent::MouseMove )
104  {
105  diff_x = event.x - event.last_x;
106  diff_y = event.y - event.last_y;
107  moved = true;
108  }
109 
110  if( event.left() && !event.shift() )
111  {
112  setCursor( Rotate2D );
113  angle_property_->add( diff_x * 0.005 );
114  orientCamera();
115  }
116  else if( event.middle() || ( event.shift() && event.left() ))
117  {
118  setCursor( MoveXY );
119  float scale = scale_property_->getFloat();
120  move( -diff_x / scale, diff_y / scale );
121  }
122  else if( event.right() )
123  {
124  setCursor( Zoom );
125  scale_property_->multiply( 1.0 - diff_y * 0.01 );
126  }
127  else
128  {
129  setCursor( event.shift() ? MoveXY : Rotate2D );
130  }
131 
132  if ( event.wheel_delta != 0 )
133  {
134  int diff = event.wheel_delta;
135  scale_property_->multiply( 1.0 - (-diff) * 0.001 );
136 
137  moved = true;
138  }
139 
140  if (moved)
141  {
144  }
145 }
146 
148 {
149  camera_->setOrientation( Ogre::Quaternion( Ogre::Radian( angle_property_->getFloat() ), Ogre::Vector3::UNIT_Z ));
150 }
151 
153 {
155 
156  if( FixedOrientationOrthoViewController* source_ortho = qobject_cast<FixedOrientationOrthoViewController*>( source_view ))
157  {
158  scale_property_->setFloat( source_ortho->scale_property_->getFloat() );
159  angle_property_->setFloat( source_ortho->angle_property_->getFloat() );
160  x_property_->setFloat( source_ortho->x_property_->getFloat() );
161  y_property_->setFloat( source_ortho->y_property_->getFloat() );
162  }
163  else
164  {
165  Ogre::Camera* source_camera = source_view->getCamera();
166  setPosition( source_camera->getPosition() );
167  }
168 }
169 
171 {
173  updateCamera();
174 }
175 
176 void FixedOrientationOrthoViewController::lookAt( const Ogre::Vector3& point )
177 {
178  setPosition( point - target_scene_node_->getPosition() );
179 }
180 
181 void FixedOrientationOrthoViewController::onTargetFrameChanged(const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation)
182 {
183  move( old_reference_position.x - reference_position_.x,
184  old_reference_position.y - reference_position_.y );
185 }
186 
188 {
189  orientCamera();
190 
191  float width = camera_->getViewport()->getActualWidth();
192  float height = camera_->getViewport()->getActualHeight();
193 
194  float scale = scale_property_->getFloat();
195  Ogre::Matrix4 proj;
196  buildScaledOrthoMatrix( proj, -width / scale / 2, width / scale / 2, -height / scale / 2, height / scale / 2,
197  camera_->getNearClipDistance(), camera_->getFarClipDistance() );
198  camera_->setCustomProjectionMatrix(true, proj);
199 
200  // For Z, we use half of the far-clip distance set in
201  // selection_context.cpp, so that the shader program which computes
202  // depth can see equal distances above and below the Z=0 plane.
203  camera_->setPosition( x_property_->getFloat(), y_property_->getFloat(), 500 );
204 }
205 
206 void FixedOrientationOrthoViewController::setPosition( const Ogre::Vector3& pos_rel_target )
207 {
208  x_property_->setFloat( pos_rel_target.x );
209  y_property_->setFloat( pos_rel_target.y );
210 }
211 
213 {
214  float angle = angle_property_->getFloat();
215  x_property_->add( dx*cos(angle)-dy*sin(angle) );
216  y_property_->add( dx*sin(angle)+dy*cos(angle) );
217 }
218 
219 } // end namespace rviz
220 
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 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 emitConfigChanged()
Subclasses should call this whenever a change is made which would change the results of toString()...
void setCursor(CursorType cursor_type)
virtual float getFloat() const
BoolProperty * invert_z_
bool multiply(float factor)
Multiply the property value by the given factor.
virtual void lookAt(const Ogre::Vector3 &point_rel_world)
This should be implemented in each subclass to aim the camera at the given point in space (relative t...
Ogre::Camera * camera_
Property specialized to enforce floating point max/min.
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
bool add(float delta)
Add the given delta to the property value.
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
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...
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.
void buildScaledOrthoMatrix(Ogre::Matrix4 &proj, float left, float right, float bottom, float top, float near, float far)
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 void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set. This version calls updateTargetSceneNode().
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...
void hide()
Hide this Property in any PropertyTreeWidgets.
Definition: property.h:371
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:51