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>
40 #include <OgreViewport.h>
41 
42 #include <rviz/display_context.h>
47 
49 
50 namespace rviz
51 {
52 // move camera up so the focal point appears in the lower image half
53 static const float CAMERA_OFFSET = 0.2;
54 
56 {
58  focal_shape_->setColor(0.0f, 1.0f, 1.0f, 0.5f);
59 }
60 
61 bool XYOrbitViewController::intersectGroundPlane(Ogre::Ray mouse_ray, Ogre::Vector3& intersection_3d)
62 {
63  // convert rays into reference frame
64  mouse_ray.setOrigin(target_scene_node_->convertWorldToLocalPosition(mouse_ray.getOrigin()));
65  mouse_ray.setDirection(target_scene_node_->convertWorldToLocalOrientation(Ogre::Quaternion::IDENTITY) *
66  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. "
89  " <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  {
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 = event.viewport->getCamera()->getCameraToViewportRay(
130  event.last_x / (float)width, 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) && intersectGroundPlane(camera_down_ray, a))
188  {
189  float l_a = source_camera->getPosition().distance(b);
190  float l_b = source_camera->getPosition().distance(a);
191 
192  distance_property_->setFloat((l_a * l_b) / (CAMERA_OFFSET * l_a + l_b));
193  float distance = distance_property_->getFloat();
194 
195  camera_dir_ray.setOrigin(source_camera->getRealPosition() -
196  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() -
202  source_camera->getUp() * distance * CAMERA_OFFSET);
203  }
204 }
205 
207 {
209  camera_->setPosition(camera_->getPosition() +
211 }
212 
213 void XYOrbitViewController::lookAt(const Ogre::Vector3& point)
214 {
215  Ogre::Vector3 camera_position = camera_->getPosition();
216  Ogre::Vector3 new_focal_point =
217  target_scene_node_->getOrientation().Inverse() * (point - target_scene_node_->getPosition());
218  new_focal_point.z = 0;
219  distance_property_->setFloat(new_focal_point.distance(camera_position));
220  focal_point_property_->setVector(new_focal_point);
221 
222  calculatePitchYawFromPosition(camera_position);
223 }
224 
225 } // end namespace rviz
226 
rviz::OrbitViewController::zoom
void zoom(float amount)
Move in/out from the focal point, ie. adjust #distance_ by amount.
Definition: orbit_view_controller.cpp:324
shape.h
rviz::Shape::getRootNode
Ogre::SceneNode * getRootNode()
Get the root scene node (pivot node) for this object.
Definition: shape.h:100
rviz::OrbitViewController::yaw
void yaw(float angle)
Definition: orbit_view_controller.cpp:296
rviz::XYOrbitViewController::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: xy_orbit_view_controller.cpp:176
rviz::DisplayContext::queueRender
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
rviz::Shape::setColor
void setColor(float r, float g, float b, float a) override
Set the color of the object. Values are in the range [0, 1].
Definition: shape.cpp:136
rviz::OrbitViewController::focal_point_property_
VectorProperty * focal_point_property_
The point around which the camera "orbits".
Definition: orbit_view_controller.h:118
ros.h
rviz::OrbitViewController::distance_property_
FloatProperty * distance_property_
The camera's distance from the focal point.
Definition: orbit_view_controller.h:116
rviz::XYOrbitViewController
Like the orbit view controller, but focal point moves only in the x-y plane.
Definition: xy_orbit_view_controller.h:47
rviz::ViewportMouseEvent
Definition: viewport_mouse_event.h:45
rviz::ViewportMouseEvent::x
int x
Definition: viewport_mouse_event.h:157
viewport_mouse_event.h
float_property.h
rviz::ViewportMouseEvent::left
bool left()
Definition: viewport_mouse_event.h:100
rviz::OrbitViewController::onInitialize
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_,...
Definition: orbit_view_controller.cpp:91
rviz::XYOrbitViewController::updateCamera
void updateCamera() override
Definition: xy_orbit_view_controller.cpp:206
f
f
rviz::ViewController::context_
DisplayContext * context_
Definition: view_controller.h:225
rviz::XYOrbitViewController::lookAt
void lookAt(const Ogre::Vector3 &point) override
This should be implemented in each subclass to aim the camera at the given point in space (relative t...
Definition: xy_orbit_view_controller.cpp:213
rviz::ViewportMouseEvent::right
bool right()
Definition: viewport_mouse_event.h:108
xy_orbit_view_controller.h
rviz::OrbitViewController::focal_shape_
Shape * focal_shape_
Definition: orbit_view_controller.h:122
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::OrbitViewController::calculatePitchYawFromPosition
void calculatePitchYawFromPosition(const Ogre::Vector3 &position)
Calculates pitch and yaw values given a new position and the current focal point.
Definition: orbit_view_controller.cpp:306
rviz
Definition: add_display_dialog.cpp:54
rviz::VectorProperty::setVector
virtual bool setVector(const Ogre::Vector3 &vector)
Definition: vector_property.cpp:55
rviz::OrbitViewController::pitch
void pitch(float angle)
Definition: orbit_view_controller.cpp:301
rviz::ViewportMouseEvent::middle
bool middle()
Definition: viewport_mouse_event.h:104
rviz::ViewportMouseEvent::y
int y
Definition: viewport_mouse_event.h:158
rviz::OrbitViewController::updateCamera
virtual void updateCamera()
Definition: orbit_view_controller.cpp:263
rviz::ViewportMouseEvent::type
QEvent::Type type
Definition: viewport_mouse_event.h:156
ogre_vector.h
rviz::XYOrbitViewController::onInitialize
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_,...
Definition: xy_orbit_view_controller.cpp:55
rviz::ViewportMouseEvent::wheel_delta
int wheel_delta
Definition: viewport_mouse_event.h:159
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::FloatProperty::setFloat
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
Definition: float_property.h:97
vector_property.h
rviz::ViewController
Definition: view_controller.h:55
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
rviz::ViewportMouseEvent::last_y
int last_y
Definition: viewport_mouse_event.h:165
display_context.h
rviz::ViewportMouseEvent::last_x
int last_x
Definition: viewport_mouse_event.h:164
rviz::ViewController::setCursor
void setCursor(CursorType cursor_type)
Definition: view_controller.cpp:224
rviz::ViewController::MoveXY
@ MoveXY
Definition: view_controller.h:212
rviz::ViewController::Rotate3D
@ Rotate3D
Definition: view_controller.h:211
rviz::ViewController::setStatus
void setStatus(const QString &message)
Definition: view_controller.cpp:235
rviz::XYOrbitViewController::intersectGroundPlane
bool intersectGroundPlane(Ogre::Ray mouse_ray, Ogre::Vector3 &intersection_3d)
Definition: xy_orbit_view_controller.cpp:61
rviz::CAMERA_OFFSET
static const float CAMERA_OFFSET
Definition: third_person_follower_view_controller.cpp:54
rviz::VectorProperty::add
bool add(const Ogre::Vector3 &offset)
Definition: vector_property.h:77
rviz::FramePositionTrackingViewController::target_scene_node_
Ogre::SceneNode * target_scene_node_
Definition: frame_position_tracking_view_controller.h:99
rviz::XYOrbitViewController::handleMouseEvent
void handleMouseEvent(ViewportMouseEvent &evt) override
Definition: xy_orbit_view_controller.cpp:80


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:10