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 static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION =
51  Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y) *
52  Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Z);
53 
55 {
56  yaw_property_ = new FloatProperty("Yaw", 0, "Rotation of the camera around the Z (up) axis.", this);
57 
58  pitch_property_ = new FloatProperty("Pitch", 0, "How much the camera is tipped downward.", this);
59  pitch_property_->setMax(Ogre::Math::HALF_PI);
60  pitch_property_->setMin(-Ogre::Math::HALF_PI);
61 
63  new VectorProperty("Position", Ogre::Vector3(5, 5, 10), "Position of the camera.", this);
64 
65  invert_z_->hide();
66 }
67 
69 {
70 }
71 
73 {
75  camera_->setProjectionType(Ogre::PT_PERSPECTIVE);
76 }
77 
79 {
80  camera_->setPosition(Ogre::Vector3(5, 5, 10));
81  camera_->lookAt(0, 0, 0);
84 }
85 
87 {
88  if (event.shift())
89  {
90  setStatus("<b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z.");
91  }
92  else
93  {
94  setStatus("<b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z. "
95  " <b>Shift</b>: More options.");
96  }
97 
98  int32_t diff_x = 0;
99  int32_t diff_y = 0;
100 
101  if (event.type == QEvent::MouseMove)
102  {
103  diff_x = event.x - event.last_x;
104  diff_y = event.y - event.last_y;
105  }
106  bool moved = diff_x != 0 || diff_y != 0;
107 
108  if (event.left() && !event.shift())
109  {
111  yaw(-diff_x * 0.005);
112  pitch(diff_y * 0.005);
113  }
114  else if (event.middle() || (event.shift() && event.left()))
115  {
116  setCursor(MoveXY);
117  move(diff_x * 0.01, -diff_y * 0.01, 0.0f);
118  }
119  else if (event.right())
120  {
121  setCursor(MoveZ);
122  move(0.0f, 0.0f, diff_y * 0.1);
123  }
124  else
125  {
126  setCursor(event.shift() ? MoveXY : Rotate3D);
127  moved = false;
128  }
129 
130  if (event.wheel_delta != 0)
131  {
132  int diff = event.wheel_delta;
133  move(0.0f, 0.0f, -diff * 0.01);
134  moved = diff != 0;
135  }
136 
137  if (moved)
138  {
140  }
141 }
142 
143 void FPSViewController::setPropertiesFromCamera(Ogre::Camera* source_camera)
144 {
145  Ogre::Quaternion quat = source_camera->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse();
146  // need to reset roll to zero to correctly interpret retrieved yaw and pitch angles
147  quat = camera_->getOrientation() * Ogre::Quaternion(-quat.getRoll(false), Ogre::Vector3::UNIT_Z) *
148  ROBOT_TO_CAMERA_ROTATION.Inverse();
149 
150  float yaw =
151  quat.getRoll(false)
152  .valueRadians(); // OGRE camera frame looks along -Z, so they call rotation around Z "roll".
153  float pitch =
154  quat.getYaw(false)
155  .valueRadians(); // OGRE camera frame has +Y as "up", so they call rotation around Y "yaw".
156 
157  Ogre::Vector3 direction = quat * Ogre::Vector3::NEGATIVE_UNIT_Z;
158 
159  if (direction.dotProduct(Ogre::Vector3::NEGATIVE_UNIT_Z) < 0)
160  {
161  if (pitch > Ogre::Math::HALF_PI)
162  {
163  pitch -= Ogre::Math::PI;
164  }
165  else if (pitch < -Ogre::Math::HALF_PI)
166  {
167  pitch += Ogre::Math::PI;
168  }
169 
170  yaw = -yaw;
171 
172  if (direction.dotProduct(Ogre::Vector3::UNIT_X) < 0)
173  {
174  yaw -= Ogre::Math::PI;
175  }
176  else
177  {
178  yaw += Ogre::Math::PI;
179  }
180  }
181 
182  pitch_property_->setFloat(pitch);
184  position_property_->setVector(source_camera->getPosition());
185 }
186 
188 {
190  setPropertiesFromCamera(source_view->getCamera());
191 }
192 
193 void FPSViewController::update(float dt, float ros_dt)
194 {
196  updateCamera();
197 }
198 
199 void FPSViewController::lookAt(const Ogre::Vector3& point)
200 {
201  camera_->lookAt(target_scene_node_->convertWorldToLocalPosition(point));
203 }
204 
205 void FPSViewController::onTargetFrameChanged(const Ogre::Vector3& old_reference_position,
206  const Ogre::Quaternion& /*old_reference_orientation*/)
207 {
208  position_property_->add(old_reference_position - reference_position_);
209 }
210 
212 {
213  camera_->setOrientation(getOrientation());
214  camera_->setPosition(position_property_->getVector());
215 }
216 
217 void FPSViewController::yaw(float angle)
218 {
220 }
221 
222 void FPSViewController::pitch(float angle)
223 {
224  pitch_property_->add(angle);
225 }
226 
228 {
229  Ogre::Quaternion pitch, yaw;
230 
231  yaw.FromAngleAxis(Ogre::Radian(yaw_property_->getFloat()), Ogre::Vector3::UNIT_Z);
232  pitch.FromAngleAxis(Ogre::Radian(pitch_property_->getFloat()), Ogre::Vector3::UNIT_Y);
233 
234  return yaw * pitch * ROBOT_TO_CAMERA_ROTATION;
235 }
236 
237 void FPSViewController::move(float x, float y, float z)
238 {
239  Ogre::Vector3 translate(x, y, z);
240  position_property_->add(getOrientation() * translate);
241 }
242 
243 } // end namespace rviz
244 
Ogre::Quaternion getOrientation()
Return a Quaternion based on the yaw and pitch properties.
void setMin(float min)
void setMax(float max)
virtual bool setVector(const Ogre::Vector3 &vector)
void handleMouseEvent(ViewportMouseEvent &evt) override
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.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void setCursor(CursorType cursor_type)
Ogre::Camera * getCamera() const
VectorProperty * position_property_
virtual Ogre::Vector3 getVector() const
BoolProperty * invert_z_
Ogre::Camera * camera_
Property specialized to enforce floating point max/min.
bool add(const Ogre::Vector3 &offset)
float mapAngleTo0_2Pi(float angle)
Return the input angle mapped back to the range 0 to 2*PI.
Definition: geometry.cpp:64
void onInitialize() override
Do subclass-specific initialization.
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)
void setPropertiesFromCamera(Ogre::Camera *source_camera)
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
void setStatus(const QString &message)
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...
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...
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
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...
virtual float getFloat() const
FloatProperty * yaw_property_
The camera&#39;s yaw (rotation around the y-axis), in radians.
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...
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...
void hide()
Hide this Property in any PropertyTreeWidgets.
Definition: property.h:401
DisplayContext * context_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION
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...


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:24