frame_view_controller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, Bielefeld University
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 Bielefeld University 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 "frame_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 static const QString ANY_AXIS("arbitrary");
47 
48 static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION =
49  Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y) *
50  Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Z);
51 
52 // helper function to create axis strings from option ID
53 inline QString fmtAxis(int i)
54 {
55  return QStringLiteral("%1%2 axis").arg(QChar(i % 2 ? '+' : '-')).arg(QChar('x' + (i - 1) / 2));
56 }
57 
59 {
60  invert_z_->hide();
61 
62  axis_property_ = new EnumProperty("Point towards", fmtAxis(6),
63  "Point the camera along the given axis of the frame.", this,
64  SLOT(changedAxis()), this);
66  // x,y,z axes get integers from 1..6: +x, -x, +y, -y, +z, -z
67  for (int i = 1; i <= 6; ++i)
70 
71  yaw_property_ = new FloatProperty("Yaw", 0, "Rotation of the camera around the Z (up) axis.", this,
72  SLOT(changedOrientation()), this);
73  yaw_property_->setMax(Ogre::Math::PI);
74  yaw_property_->setMin(-Ogre::Math::PI);
75 
76  pitch_property_ = new FloatProperty("Pitch", 0, "How much the camera is tipped downward.", this,
77  SLOT(changedOrientation()), this);
78  pitch_property_->setMax(Ogre::Math::PI);
79  pitch_property_->setMin(-Ogre::Math::PI);
80 
81  roll_property_ = new FloatProperty("Roll", 0, "Rotation about the camera's view direction.", this,
82  SLOT(changedOrientation()), this);
83  roll_property_->setMax(Ogre::Math::PI);
84  roll_property_->setMin(-Ogre::Math::PI);
85 
86  position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, "Position of the camera.",
87  this, SLOT(changedPosition()), this);
88 
89  locked_property_ = new BoolProperty("Lock Camera", false,
90  "Lock camera in its current pose relative to the frame", this);
91 }
92 
94 {
96  camera_->setProjectionType(Ogre::PT_PERSPECTIVE);
98  changedAxis();
99 }
100 
102 {
103  camera_->setPosition(Ogre::Vector3::ZERO);
104  Eigen::Vector3d axis(0, 0, 0);
105  int option = previous_axis_;
106  if (option >= 1 && option <= 6)
107  {
108  axis[(option - 1) / 2] = (option % 2) ? +1 : -1;
109  Eigen::Quaterniond q = Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitX(), axis);
110  camera_->setOrientation(Ogre::Quaternion(q.w(), q.x(), q.y(), q.z()) * ROBOT_TO_CAMERA_ROTATION);
111  }
113 }
114 
116 {
118  auto source_camera = source_view->getCamera();
119  camera_->setPosition(source_camera->getPosition());
120  camera_->setOrientation(source_camera->getOrientation());
122 }
123 
124 void FrameViewController::lookAt(const Ogre::Vector3& point)
125 {
126  camera_->lookAt(target_scene_node_->convertWorldToLocalPosition(point));
128 }
129 
131 {
132  if (locked_property_->getBool())
133  {
134  setStatus("Unlock camera in settings to enable mouse interaction.");
135  return;
136  }
137 
138  setStatus("<b>Left-Click:</b> Rotate Yaw/Pitch. <b>Shift Left-Click</b>: Rotate Roll. "
139  "<b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z.");
140 
141  int32_t diff_x = 0;
142  int32_t diff_y = 0;
143 
144  if (event.type == QEvent::MouseMove)
145  {
146  diff_x = event.x - event.last_x;
147  diff_y = event.y - event.last_y;
148  }
149 
150  if (event.left() && !event.shift())
151  {
153  rotate(-diff_x * 0.005, diff_y * 0.005, 0.0f);
154  }
155  else if (event.left() && event.shift())
156  {
158  int cx = event.viewport->getActualWidth() / 2;
159  int cy = event.viewport->getActualHeight() / 2;
160 
161  float roll = atan2(event.last_y - cy, event.last_x - cx) - atan2(event.y - cy, event.x - cx);
162  if (std::isfinite(roll))
163  rotate(0.0f, 0.0f, roll);
164  }
165  else if (event.middle())
166  {
167  setCursor(MoveXY);
168  move(diff_x * 0.01, -diff_y * 0.01, 0.0f);
169  }
170  else if (event.right())
171  {
172  setCursor(MoveZ);
173  move(0.0f, 0.0f, diff_y * 0.1);
174  }
175  else
176  {
177  setCursor(event.shift() ? Rotate2D : Rotate3D);
178  }
179 
180  if (event.wheel_delta != 0)
181  {
182  int diff = event.wheel_delta;
183  move(0.0f, 0.0f, -diff * 0.01);
184  }
185 }
186 
187 Ogre::Quaternion FrameViewController::getOrientation(float yaw, float pitch, float roll)
188 {
189  Eigen::Quaterniond q = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) *
190  Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()) *
191  Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX());
192 
193  return Ogre::Quaternion(q.w(), q.x(), q.y(), q.z()) * ROBOT_TO_CAMERA_ROTATION;
194 }
195 
197 {
198  Ogre::Quaternion q = camera_->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse();
199  Eigen::Quaterniond quat(q.w, q.x, q.y, q.z);
200  auto ypr = quat.toRotationMatrix().eulerAngles(2, 1, 0);
201 
202  QSignalBlocker blockY(yaw_property_);
203  QSignalBlocker blockP(pitch_property_);
204  QSignalBlocker blockR(roll_property_);
205  QSignalBlocker block(position_property_);
206 
207  yaw_property_->setFloat(ypr[0]);
208  pitch_property_->setFloat(ypr[1]);
209  roll_property_->setFloat(ypr[2]);
210  position_property_->setVector(camera_->getPosition());
211 }
212 
214 {
215  // compare current camera direction with unit axes
216  Ogre::Vector3 actual =
217  (camera_->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse()) * Ogre::Vector3::UNIT_X;
218  for (unsigned int i = 0; i < 3; ++i)
219  {
220  Ogre::Vector3 axis(0, 0, 0);
221  axis[i] = 1.0;
222  auto scalar_product = axis.dotProduct(actual);
223  if (std::abs(scalar_product) > 1.0 - precision)
224  return 1 + 2 * i + (scalar_product > 0 ? 0 : 1);
225  }
226  return -1;
227 }
228 
230 {
231  int actual = actualCameraAxisOption();
232  if (axis_property_->getOptionInt() == actual) // no change?
233  return;
234 
235  QSignalBlocker block(axis_property_);
236  axis_property_->setString(actual == -1 ? ANY_AXIS : fmtAxis(actual));
237  rememberAxis(actual);
238 }
239 
240 void FrameViewController::move(float x, float y, float z)
241 {
242  Ogre::Vector3 translate(x, y, z);
243  position_property_->add(camera_->getOrientation() * translate);
244 }
245 
247 {
248  camera_->setPosition(position_property_->getVector());
250 }
251 
252 inline void _rotate(FloatProperty* prop, float angle)
253 {
254  if (angle == 0)
255  return;
256 
257  QSignalBlocker block(prop);
258  angle = fmod(prop->getFloat() + angle, Ogre::Math::TWO_PI);
259 
260  // map angle onto range -PI .. PI
261  if (angle > Ogre::Math::PI)
262  angle = -Ogre::Math::PI + fmod(angle, Ogre::Math::PI);
263  if (angle < -Ogre::Math::PI)
264  angle = Ogre::Math::PI + fmod(angle, Ogre::Math::PI);
265 
266  prop->setFloat(angle);
267 }
268 
269 void FrameViewController::rotate(float yaw, float pitch, float roll)
270 {
271  _rotate(yaw_property_, yaw);
272  _rotate(pitch_property_, pitch);
273  _rotate(roll_property_, roll);
275 }
276 
278 {
283 }
284 
286 {
288  reset();
289 }
290 
291 inline void FrameViewController::rememberAxis(int current)
292 {
293  if (current >= 1) // remember previous axis selection
294  previous_axis_ = current;
295 }
296 
297 void FrameViewController::onTargetFrameChanged(const Ogre::Vector3& /* old_reference_position */,
298  const Ogre::Quaternion& /* old_reference_orientation */)
299 {
300  // don't adapt the camera pose to the old reference position, but just jump to new frame
301 }
302 
304 {
305  if (getNewTransform())
306  {
307  // track both, position and orientation of reference frame
311  }
312 }
313 
314 } // end namespace rviz
315 
void setMin(float min)
void setMax(float max)
int actualCameraAxisOption(double precision=0.001) const
find enum ID from camera&#39;s current pose
virtual bool setVector(const Ogre::Vector3 &vector)
BoolProperty * locked_property_
Lock camera, i.e. disable mouse interaction?
void move(float x, float y, float z)
f
QString fmtAxis(int i)
void rotate(float yaw, float pitch, float roll)
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
virtual Ogre::Vector3 getVector() const
FloatProperty * pitch_property_
The camera&#39;s pitch (rotation around the y-axis), in radians.
BoolProperty * invert_z_
Ogre::Camera * camera_
Property specialized to enforce floating point max/min.
Ogre::Quaternion getOrientation(float yaw, float pitch, float roll)
bool add(const Ogre::Vector3 &offset)
void onInitialize() override
Do subclass-specific initialization.
VectorProperty * position_property_
The camera&#39;s position.
void updateTargetSceneNode() override
Update the position of the target_scene_node_ from the TF frame specified in the Target Frame propert...
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
FloatProperty * roll_property_
The camera&#39;s roll (rotation around the x-axis), in radians.
virtual void addOption(const QString &option, int value=0)
FloatProperty * yaw_property_
The camera&#39;s yaw (rotation around the z-axis), in radians.
void handleMouseEvent(ViewportMouseEvent &event) override
void setStatus(const QString &message)
void _rotate(FloatProperty *prop, float angle)
void setPropertiesFromCamera()
set yaw, pitch, roll, position properties from camera
EnumProperty * axis_property_
The axis that the camera aligns to.
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 onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
A camera tied to a given frame.
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
virtual float getFloat() const
void onTargetFrameChanged(const Ogre::Vector3 &, const Ogre::Quaternion &) override
Override to implement the change in properties which nullifies the change in target frame...
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
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...
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
virtual bool getBool() const
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
DisplayContext * context_
void setAxisFromCamera()
set axis_property_ from camera
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION
virtual void setString(const QString &str)
Set the value of this property to the given string. Does not force the value to be one of the list of...
Enum property.
Definition: enum_property.h:46
static const QString ANY_AXIS("arbitrary")


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