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>
35 #include <OgreViewport.h>
36 
37 #include <rviz/display_context.h>
43 
45 
46 namespace rviz
47 {
49 {
51  new FloatProperty("Scale", 10, "How much to scale up the size of things in the scene.", this);
52  angle_property_ = new FloatProperty("Angle", 0, "Angle around the Z axis to rotate.", this);
53  x_property_ = new FloatProperty("X", 0, "X component of camera position.", this);
54  y_property_ = new FloatProperty("Y", 0, "Y component of camera position.", this);
55 }
56 
58 {
59 }
60 
62 {
64 
65  camera_->setProjectionType(Ogre::PT_ORTHOGRAPHIC);
66  camera_->setFixedYawAxis(false);
67  invert_z_->hide();
68 }
69 
71 {
76 }
77 
79 {
80  if (event.shift())
81  {
82  setStatus("<b>Left-Click:</b> Move X/Y.");
83  }
84  else
85  {
86  setStatus("<b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom. "
87  "<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  {
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(
150  Ogre::Quaternion(Ogre::Radian(angle_property_->getFloat()), Ogre::Vector3::UNIT_Z));
151 }
152 
154 {
156 
157  if (FixedOrientationOrthoViewController* source_ortho =
158  qobject_cast<FixedOrientationOrthoViewController*>(source_view))
159  {
160  scale_property_->setFloat(source_ortho->scale_property_->getFloat());
161  angle_property_->setFloat(source_ortho->angle_property_->getFloat());
162  x_property_->setFloat(source_ortho->x_property_->getFloat());
163  y_property_->setFloat(source_ortho->y_property_->getFloat());
164  }
165  else
166  {
167  Ogre::Camera* source_camera = source_view->getCamera();
168  setPosition(source_camera->getPosition());
169  }
170 }
171 
173 {
175  updateCamera();
176 }
177 
178 void FixedOrientationOrthoViewController::lookAt(const Ogre::Vector3& point)
179 {
180  setPosition(point - target_scene_node_->getPosition());
181 }
182 
184  const Ogre::Vector3& old_reference_position,
185  const Ogre::Quaternion& /*old_reference_orientation*/)
186 {
187  move(old_reference_position.x - reference_position_.x,
188  old_reference_position.y - reference_position_.y);
189 }
190 
192 {
193  orientCamera();
194 
195  float width = camera_->getViewport()->getActualWidth();
196  float height = camera_->getViewport()->getActualHeight();
197 
198  float scale = scale_property_->getFloat();
199  Ogre::Matrix4 proj;
200  buildScaledOrthoMatrix(proj, -width / scale / 2, width / scale / 2, -height / scale / 2,
201  height / scale / 2, camera_->getNearClipDistance(),
202  camera_->getFarClipDistance());
203  camera_->setCustomProjectionMatrix(true, proj);
204 
205  // For Z, we use half of the far-clip distance set in
206  // selection_context.cpp, so that the shader program which computes
207  // depth can see equal distances above and below the Z=0 plane.
208  camera_->setPosition(x_property_->getFloat(), y_property_->getFloat(), 500);
209 }
210 
211 void FixedOrientationOrthoViewController::setPosition(const Ogre::Vector3& pos_rel_target)
212 {
213  x_property_->setFloat(pos_rel_target.x);
214  y_property_->setFloat(pos_rel_target.y);
215 }
216 
218 {
219  float angle = angle_property_->getFloat();
220  x_property_->add(dx * std::cos(angle) - dy * std::sin(angle));
221  y_property_->add(dx * std::sin(angle) + dy * std::cos(angle));
222 }
223 
224 } // end namespace rviz
225 
226 #include <cmath>
227 
rviz::FixedOrientationOrthoViewController::reset
void reset() override
Definition: fixed_orientation_ortho_view_controller.cpp:70
shape.h
rviz::FramePositionTrackingViewController::reference_position_
Ogre::Vector3 reference_position_
Definition: frame_position_tracking_view_controller.h:101
rviz::DisplayContext::queueRender
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
rviz::FixedOrientationOrthoViewController::orientCamera
void orientCamera()
Definition: fixed_orientation_ortho_view_controller.cpp:147
rviz::FixedOrientationOrthoViewController::onTargetFrameChanged
void onTargetFrameChanged(const Ogre::Vector3 &old_reference_position, const Ogre::Quaternion &old_reference_orientation) override
Override to implement the change in properties which nullifies the change in target frame.
Definition: fixed_orientation_ortho_view_controller.cpp:183
rviz::FixedOrientationOrthoViewController::x_property_
FloatProperty * x_property_
Definition: fixed_orientation_ortho_view_controller.h:80
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
rviz::ViewportMouseEvent
Definition: viewport_mouse_event.h:45
rviz::FixedOrientationOrthoViewController::setPosition
void setPosition(const Ogre::Vector3 &pos_rel_target)
Definition: fixed_orientation_ortho_view_controller.cpp:211
fixed_orientation_ortho_view_controller.h
viewport_mouse_event.h
rviz::FixedOrientationOrthoViewController::mimic
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...
Definition: fixed_orientation_ortho_view_controller.cpp:153
float_property.h
rviz::FloatProperty::add
bool add(float delta)
Add the given delta to the property value.
Definition: float_property.h:103
rviz::ViewController::Rotate2D
@ Rotate2D
Definition: view_controller.h:210
rviz::ViewportMouseEvent::left
bool left()
Definition: viewport_mouse_event.h:100
bool_property.h
rviz::FixedOrientationOrthoViewController::scale_property_
FloatProperty * scale_property_
Definition: fixed_orientation_ortho_view_controller.h:78
rviz::ViewController::context_
DisplayContext * context_
Definition: view_controller.h:225
rviz::ViewportMouseEvent::right
bool right()
Definition: viewport_mouse_event.h:108
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
rviz::Property::hide
void hide()
Hide this Property in any PropertyTreeWidgets.
Definition: property.h:462
orthographic.h
rviz::buildScaledOrthoMatrix
void buildScaledOrthoMatrix(Ogre::Matrix4 &proj, float left, float right, float bottom, float top, float near, float far)
Definition: orthographic.cpp:36
rviz::FramePositionTrackingViewController::onInitialize
void onInitialize() override
Do subclass-specific initialization.
Definition: frame_position_tracking_view_controller.cpp:52
rviz::FixedOrientationOrthoViewController::update
void update(float dt, float ros_dt) override
Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to r...
Definition: fixed_orientation_ortho_view_controller.cpp:172
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::FloatProperty::getFloat
virtual float getFloat() const
Definition: float_property.h:79
rviz
Definition: add_display_dialog.cpp:54
rviz::ViewportMouseEvent::middle
bool middle()
Definition: viewport_mouse_event.h:104
rviz::FixedOrientationOrthoViewController::angle_property_
FloatProperty * angle_property_
Definition: fixed_orientation_ortho_view_controller.h:79
rviz::ViewportMouseEvent::type
QEvent::Type type
Definition: viewport_mouse_event.h:156
ogre_vector.h
rviz::FixedOrientationOrthoViewController::dragging_
bool dragging_
Definition: fixed_orientation_ortho_view_controller.h:82
rviz::FixedOrientationOrthoViewController::updateCamera
void updateCamera()
Definition: fixed_orientation_ortho_view_controller.cpp:191
rviz::FixedOrientationOrthoViewController::~FixedOrientationOrthoViewController
~FixedOrientationOrthoViewController() override
Definition: fixed_orientation_ortho_view_controller.cpp:57
rviz::ViewportMouseEvent::wheel_delta
int wheel_delta
Definition: viewport_mouse_event.h:159
rviz::ViewController::invert_z_
BoolProperty * invert_z_
Definition: view_controller.h:240
rviz::FramePositionTrackingViewController::mimic
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...
Definition: frame_position_tracking_view_controller.cpp:134
rviz::ViewportMouseEvent::shift
bool shift()
Definition: viewport_mouse_event.h:113
rviz::ViewController::getCamera
Ogre::Camera * getCamera() const
Definition: view_controller.h:147
rviz::FixedOrientationOrthoViewController::move
void move(float x, float y)
Definition: fixed_orientation_ortho_view_controller.cpp:217
rviz::FixedOrientationOrthoViewController::handleMouseEvent
void handleMouseEvent(ViewportMouseEvent &evt) override
Definition: fixed_orientation_ortho_view_controller.cpp:78
rviz::FloatProperty::setFloat
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
Definition: float_property.h:97
rviz::ViewController
Definition: view_controller.h:55
rviz::FramePositionTrackingViewController::update
void update(float dt, float ros_dt) override
Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to r...
Definition: frame_position_tracking_view_controller.cpp:80
rviz::ViewController::camera_
Ogre::Camera * camera_
Definition: view_controller.h:226
rviz::ViewController::emitConfigChanged
void emitConfigChanged()
Subclasses should call this whenever a change is made which would change the results of toString().
Definition: view_controller.cpp:180
class_list_macros.hpp
rviz::ViewController::Zoom
@ Zoom
Definition: view_controller.h:214
display_context.h
rviz::ViewController::setCursor
void setCursor(CursorType cursor_type)
Definition: view_controller.cpp:224
rviz::ViewController::MoveXY
@ MoveXY
Definition: view_controller.h:212
rviz::ViewController::setStatus
void setStatus(const QString &message)
Definition: view_controller.cpp:235
rviz::FixedOrientationOrthoViewController::onInitialize
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
Definition: fixed_orientation_ortho_view_controller.cpp:61
rviz::FixedOrientationOrthoViewController::y_property_
FloatProperty * y_property_
Definition: fixed_orientation_ortho_view_controller.h:81
rviz::FixedOrientationOrthoViewController
Definition: fixed_orientation_ortho_view_controller.h:43
rviz::FramePositionTrackingViewController::target_scene_node_
Ogre::SceneNode * target_scene_node_
Definition: frame_position_tracking_view_controller.h:99
rviz::FloatProperty::multiply
bool multiply(float factor)
Multiply the property value by the given factor.
Definition: float_property.h:109
rviz::FixedOrientationOrthoViewController::FixedOrientationOrthoViewController
FixedOrientationOrthoViewController()
Definition: fixed_orientation_ortho_view_controller.cpp:48
rviz::FixedOrientationOrthoViewController::lookAt
void lookAt(const Ogre::Vector3 &point_rel_world) override
This should be implemented in each subclass to aim the camera at the given point in space (relative t...
Definition: fixed_orientation_ortho_view_controller.cpp:178


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Tue May 28 2024 02:33:17