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 "fps_view_controller.h"
31 #include <rviz/display_context.h>
37 
38 #include <OgreViewport.h>
39 #include <OgreCamera.h>
40 #include <OgreSceneNode.h>
41 #include <Eigen/Geometry>
42 #include <QSignalBlocker>
43 
44 namespace rviz
45 {
46 const Ogre::Quaternion FPSViewController::ROBOT_TO_CAMERA_ROTATION =
47  Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y) *
48  Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Z);
49 
51 {
52  invert_z_->hide();
53 
54  yaw_property_ = new FloatProperty("Yaw", 0, "Rotation of the camera around the Z (up) axis.", this,
56  yaw_property_->setMax(Ogre::Math::PI);
57  yaw_property_->setMin(-Ogre::Math::PI);
58 
59  pitch_property_ = new FloatProperty("Pitch", 0, "How much the camera is tipped downward.", this,
61  pitch_property_->setMax(Ogre::Math::PI);
62  pitch_property_->setMin(-Ogre::Math::PI);
63 
64  roll_property_ = new FloatProperty("Roll", 0, "Rotation about the camera's view direction.", this,
66  roll_property_->setMax(Ogre::Math::PI);
67  roll_property_->setMin(-Ogre::Math::PI);
68 
69  position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, "Position of the camera.",
71 }
72 
74 {
76  camera_->setProjectionType(Ogre::PT_PERSPECTIVE);
78 }
79 
81 {
82  camera_->setPosition(Ogre::Vector3(5, 5, 10));
83  camera_->lookAt(0, 0, 0);
84  resetRoll();
87 }
88 
90 {
92  auto source_camera = source_view->getCamera();
93  camera_->setPosition(source_camera->getPosition());
94  camera_->setOrientation(source_camera->getOrientation());
96 }
97 
98 void FPSViewController::lookAt(const Ogre::Vector3& point)
99 {
100  camera_->lookAt(target_scene_node_->convertWorldToLocalPosition(point));
101  resetRoll();
103 }
104 
106 {
107  if (event.shift())
108  setStatus(
109  "<b>Left-Click:</b> Rotate Roll. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z.");
110  else
111  setStatus("<b>Left-Click:</b> Rotate Yaw/Pitch. <b>Shift Left-Click</b>: Rotate Roll. "
112  "<b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z.");
113 
114  int32_t diff_x = 0;
115  int32_t diff_y = 0;
116 
117  if (event.type == QEvent::MouseMove)
118  {
119  diff_x = event.x - event.last_x;
120  diff_y = event.y - event.last_y;
121  }
122 
123  if (event.left() && !event.shift())
124  {
126  rotate(-diff_x * 0.005, diff_y * 0.005, 0.0f);
127  }
128  else if (event.left() && event.shift())
129  {
131  int cx = event.viewport->getActualWidth() / 2;
132  int cy = event.viewport->getActualHeight() / 2;
133 
134  float roll = atan2(event.last_y - cy, event.last_x - cx) - atan2(event.y - cy, event.x - cx);
135  if (std::isfinite(roll))
136  rotate(0.0f, 0.0f, roll);
137  }
138  else if (event.middle())
139  {
140  setCursor(MoveXY);
141  move(diff_x * 0.01, -diff_y * 0.01, 0.0f);
142  }
143  else if (event.right())
144  {
145  setCursor(MoveZ);
146  move(0.0f, 0.0f, diff_y * 0.1);
147  }
148  else
149  {
150  setCursor(event.shift() ? Rotate2D : Rotate3D);
151  }
152 
153  if (event.wheel_delta != 0)
154  {
155  int diff = event.wheel_delta;
156  move(0.0f, 0.0f, -diff * 0.01);
157  }
158 }
159 
160 Ogre::Quaternion FPSViewController::getOrientation(float yaw, float pitch, float roll)
161 {
162  Eigen::Quaterniond q = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) *
163  Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()) *
164  Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX());
165 
166  return Ogre::Quaternion(q.w(), q.x(), q.y(), q.z()) * ROBOT_TO_CAMERA_ROTATION;
167 }
168 
170 {
171  Ogre::Quaternion q = camera_->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse();
172  Eigen::Quaterniond quat(q.w, q.x, q.y, q.z);
173  auto ypr = quat.toRotationMatrix().eulerAngles(2, 1, 0);
174 
175  QSignalBlocker blockY(yaw_property_);
176  QSignalBlocker blockP(pitch_property_);
177  QSignalBlocker blockR(roll_property_);
178  QSignalBlocker block(position_property_);
179 
180  yaw_property_->setFloat(ypr[0]);
181  pitch_property_->setFloat(ypr[1]);
182  roll_property_->setFloat(ypr[2]);
183  position_property_->setVector(camera_->getPosition());
184 }
185 
187 {
188  Ogre::Quaternion q = camera_->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse();
189  Eigen::Quaterniond quat(q.w, q.x, q.y, q.z);
190  auto ypr = quat.toRotationMatrix().eulerAngles(2, 1, 0);
191  camera_->setOrientation(getOrientation(ypr[0], ypr[1], Ogre::Math::PI));
192 }
193 
194 void FPSViewController::onTargetFrameChanged(const Ogre::Vector3& old_reference_position,
195  const Ogre::Quaternion& /*old_reference_orientation*/)
196 {
197  position_property_->add(old_reference_position - reference_position_);
198 }
199 
200 void FPSViewController::move(float x, float y, float z)
201 {
202  Ogre::Vector3 translate(x, y, z);
203  position_property_->add(camera_->getOrientation() * translate);
204 }
205 
207 {
208  camera_->setPosition(position_property_->getVector());
210 }
211 
212 inline void _rotate(FloatProperty* prop, float angle)
213 {
214  if (angle == 0)
215  return;
216 
217  QSignalBlocker block(prop);
218  angle = fmod(prop->getFloat() + angle, Ogre::Math::TWO_PI);
219 
220  // map angle onto range -PI .. PI
221  if (angle > Ogre::Math::PI)
222  angle = -Ogre::Math::PI + fmod(angle, Ogre::Math::PI);
223  if (angle < -Ogre::Math::PI)
224  angle = Ogre::Math::PI + fmod(angle, Ogre::Math::PI);
225 
226  prop->setFloat(angle);
227 }
228 
229 void FPSViewController::rotate(float yaw, float pitch, float roll)
230 {
231  _rotate(yaw_property_, yaw);
232  _rotate(pitch_property_, pitch);
233  _rotate(roll_property_, roll);
235 }
236 
238 {
242 }
243 
244 
245 } // end namespace rviz
246 
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.
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
rviz::FPSViewController::pitch_property_
FloatProperty * pitch_property_
The camera's pitch (rotation around the y-axis), in radians.
Definition: fps_view_controller.h:72
rviz::FPSViewController::position_property_
VectorProperty * position_property_
The camera's position.
Definition: fps_view_controller.h:74
rviz::FPSViewController::setPropertiesFromCamera
void setPropertiesFromCamera()
set yaw, pitch, roll, position properties from camera
Definition: fps_view_controller.cpp:169
rviz::ViewportMouseEvent
Definition: viewport_mouse_event.h:45
rviz::FloatProperty::setMax
void setMax(float max)
Definition: float_property.cpp:57
rviz::ViewportMouseEvent::x
int x
Definition: viewport_mouse_event.h:157
rviz::FPSViewController::move
void move(float x, float y, float z)
Definition: fps_view_controller.cpp:200
viewport_mouse_event.h
float_property.h
rviz::FPSViewController::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: fps_view_controller.cpp:98
rviz::ViewController::Rotate2D
@ Rotate2D
Definition: view_controller.h:210
rviz::FPSViewController
A first-person camera, controlled by yaw, pitch, roll, and position.
Definition: fps_view_controller.h:41
rviz::ViewportMouseEvent::left
bool left()
Definition: viewport_mouse_event.h:100
bool_property.h
rviz::FPSViewController::changedPosition
virtual void changedPosition()
Definition: fps_view_controller.cpp:206
rviz::FPSViewController::ROBOT_TO_CAMERA_ROTATION
static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION
Definition: fps_view_controller.h:69
rviz::FPSViewController::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: fps_view_controller.cpp:194
rviz::FloatProperty::setMin
void setMin(float min)
Definition: float_property.cpp:51
f
f
rviz::FPSViewController::yaw_property_
FloatProperty * yaw_property_
The camera's yaw (rotation around the z-axis), in radians.
Definition: fps_view_controller.h:71
rviz::ViewController::context_
DisplayContext * context_
Definition: view_controller.h:225
rviz::FPSViewController::getOrientation
Ogre::Quaternion getOrientation(float yaw, float pitch, float roll)
yield camera orientation for given Euler angles
Definition: fps_view_controller.cpp:160
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::FPSViewController::roll_property_
FloatProperty * roll_property_
The camera's roll (rotation around the x-axis), in radians.
Definition: fps_view_controller.h:73
rviz::Property::hide
void hide()
Hide this Property in any PropertyTreeWidgets.
Definition: property.h:462
rviz::FPSViewController::reset
void reset() override
Definition: fps_view_controller.cpp:80
rviz::_rotate
void _rotate(FloatProperty *prop, float angle)
Definition: fps_view_controller.cpp:212
rviz::FramePositionTrackingViewController::onInitialize
void onInitialize() override
Do subclass-specific initialization.
Definition: frame_position_tracking_view_controller.cpp:52
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::FPSViewController::onInitialize
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
Definition: fps_view_controller.cpp:73
rviz::FloatProperty::getFloat
virtual float getFloat() const
Definition: float_property.h:79
rviz::FPSViewController::FPSViewController
FPSViewController()
Definition: fps_view_controller.cpp:50
rviz
Definition: add_display_dialog.cpp:54
rviz::VectorProperty::setVector
virtual bool setVector(const Ogre::Vector3 &vector)
Definition: vector_property.cpp:55
rviz::ViewportMouseEvent::middle
bool middle()
Definition: viewport_mouse_event.h:104
rviz::ViewportMouseEvent::y
int y
Definition: viewport_mouse_event.h:158
rviz::ViewportMouseEvent::type
QEvent::Type type
Definition: viewport_mouse_event.h:156
rviz::FPSViewController::handleMouseEvent
void handleMouseEvent(ViewportMouseEvent &event) override
Definition: fps_view_controller.cpp:105
fps_view_controller.h
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::FPSViewController::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: fps_view_controller.cpp:89
rviz::ViewportMouseEvent::shift
bool shift()
Definition: viewport_mouse_event.h:113
rviz::FPSViewController::rotate
void rotate(float yaw, float pitch, float roll)
Definition: fps_view_controller.cpp:229
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
class_list_macros.hpp
rviz::ViewportMouseEvent::last_y
int last_y
Definition: viewport_mouse_event.h:165
display_context.h
rviz::VectorProperty
Definition: vector_property.h:39
rviz::ViewportMouseEvent::last_x
int last_x
Definition: viewport_mouse_event.h:164
rviz::FPSViewController::resetRoll
void resetRoll()
zero roll angle
Definition: fps_view_controller.cpp:186
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::VectorProperty::getVector
virtual Ogre::Vector3 getVector() const
Definition: vector_property.h:73
rviz::ViewController::setStatus
void setStatus(const QString &message)
Definition: view_controller.cpp:235
rviz::FPSViewController::changedOrientation
virtual void changedOrientation()
Definition: fps_view_controller.cpp:237
rviz::VectorProperty::add
bool add(const Ogre::Vector3 &offset)
Definition: vector_property.h:77
rviz::ViewController::MoveZ
@ MoveZ
Definition: view_controller.h:213
rviz::FramePositionTrackingViewController::target_scene_node_
Ogre::SceneNode * target_scene_node_
Definition: frame_position_tracking_view_controller.h:99
enum_property.h


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Thu May 16 2024 02:30:48