tablet_view_controller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, JSK Lab, 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 JSK Lab, 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  * Author: Adam Leeper
30  * Author: Ryohei Ueda
31  */
32 
33 #include "tablet_view_controller.h"
34 
35 #include "rviz/load_resource.h"
37 #include "rviz/display_context.h"
39 #include "rviz/frame_manager.h"
40 #include "rviz/geometry.h"
48 
49 #include "view_controller_msgs/CameraPlacement.h"
50 #include "geometry_msgs/PointStamped.h"
51 
52 #include <OGRE/OgreViewport.h>
53 #include <OGRE/OgreQuaternion.h>
54 #include <OGRE/OgreVector3.h>
55 #include <OGRE/OgreSceneNode.h>
56 #include <OGRE/OgreSceneManager.h>
57 #include <OGRE/OgreCamera.h>
58 
59 #include <rviz/render_panel.h>
60 #include <rviz/view_manager.h>
62 #include <OGRE/OgreRenderWindow.h>
63 
64 namespace jsk_rviz_plugins
65 {
66 using namespace view_controller_msgs;
67 using namespace rviz;
68 
69 // Strings for selecting control mode styles
70 static const std::string MODE_ORBIT = "Orbit";
71 static const std::string MODE_FPS = "FPS";
72 
73 // Limits to prevent orbit controller singularity, but not currently used.
74 //static const Ogre::Radian PITCH_LIMIT_LOW = Ogre::Radian(-Ogre::Math::HALF_PI + 0.02);
75 //static const Ogre::Radian PITCH_LIMIT_HIGH = Ogre::Radian( Ogre::Math::HALF_PI - 0.02);
76 static const Ogre::Radian PITCH_LIMIT_LOW = Ogre::Radian( 0.02 );
77 static const Ogre::Radian PITCH_LIMIT_HIGH = Ogre::Radian( Ogre::Math::PI - 0.02);
78 
79 
80 // Some convenience functions for Ogre / geometry_msgs conversions
81 static inline Ogre::Vector3 vectorFromMsg(const geometry_msgs::Point &m) { return Ogre::Vector3(m.x, m.y, m.z); }
82 static inline Ogre::Vector3 vectorFromMsg(const geometry_msgs::Vector3 &m) { return Ogre::Vector3(m.x, m.y, m.z); }
83 static inline geometry_msgs::Point pointOgreToMsg(const Ogre::Vector3 &o)
84 {
85  geometry_msgs::Point m;
86  m.x = o.x; m.y = o.y; m.z = o.z;
87  return m;
88 }
89 static inline void pointOgreToMsg(const Ogre::Vector3 &o, geometry_msgs::Point &m) { m.x = o.x; m.y = o.y; m.z = o.z; }
90 
91 static inline geometry_msgs::Vector3 vectorOgreToMsg(const Ogre::Vector3 &o)
92 {
93  geometry_msgs::Vector3 m;
94  m.x = o.x; m.y = o.y; m.z = o.z;
95  return m;
96 }
97 static inline void vectorOgreToMsg(const Ogre::Vector3 &o, geometry_msgs::Vector3 &m) { m.x = o.x; m.y = o.y; m.z = o.z; }
98 
99 // -----------------------------------------------------------------------------
100 
101 
103  : nh_(""), animate_(false), dragging_( false )
104 {
105  interaction_disabled_cursor_ = makeIconCursor( "package://rviz/icons/forbidden.svg" );
106 
107  mouse_enabled_property_ = new BoolProperty("Mouse Enabled", true,
108  "Enables mouse control of the camera.",
109  this);
110  interaction_mode_property_ = new EditableEnumProperty("Control Mode", QString::fromStdString(MODE_ORBIT),
111  "Select the style of mouse interaction.",
112  this);
116 
117  fixed_up_property_ = new BoolProperty( "Maintain Vertical Axis", true,
118  "If enabled, the camera is not allowed to roll side-to-side.",
119  this);
120  attached_frame_property_ = new TfFrameProperty("Target Frame",
122  "TF frame the camera is attached to.",
123  this, NULL, true );
124  eye_point_property_ = new VectorProperty( "Eye", Ogre::Vector3( 5, 5, 10 ),
125  "Position of the camera.", this );
126  focus_point_property_ = new VectorProperty( "Focus", Ogre::Vector3::ZERO,
127  "Position of the focus/orbit point.", this );
128  up_vector_property_ = new VectorProperty( "Up", Ogre::Vector3::UNIT_Z,
129  "The vector which maps to \"up\" in the camera image plane.", this );
131  "The distance between the camera position and the focus point.",
132  this );
133  distance_property_->setMin( 0.01 );
134  default_transition_time_property_ = new FloatProperty( "Transition Time", 0.5,
135  "The default time to use for camera transitions.",
136  this );
137  camera_placement_topic_property_ = new RosTopicProperty("Placement Topic", "/rviz/camera_placement",
138  QString::fromStdString(ros::message_traits::datatype<view_controller_msgs::CameraPlacement>() ),
139  "Topic for CameraPlacement messages", this, SLOT(updateTopics()));
140 
141  camera_placement_publish_topic_property_ = new RosTopicProperty("Placement Publish Topic", "/rviz/current_camera_placement",
142  QString::fromStdString(ros::message_traits::datatype<view_controller_msgs::CameraPlacement>() ),
143  "Publishing Topic for CameraPlacement messages", this, SLOT(updatePublishTopics()));
144 
145  mouse_point_publish_topic_property_ = new RosTopicProperty("Placement Mouse Point", "/rviz/current_mouse_point",
146  QString::fromStdString(ros::message_traits::datatype<geometry_msgs::PointStamped>() ),
147  "Publishing position of mouse", this, SLOT(updateMousePointPublishTopics()));
148 
149 // camera_placement_trajectory_topic_property_ = new RosTopicProperty("Trajectory Topic", "/rviz/camera_placement_trajectory",
150 // QString::fromStdString(ros::message_traits::datatype<view_controller_msgs::CameraPlacementTrajectory>() ),
151 // "Topic for CameraPlacementTrajectory messages", this, SLOT(updateTopics()));
152 }
153 
155 {
156  delete focal_shape_;
157  context_->getSceneManager()->destroySceneNode( attached_scene_node_ );
158 }
159 
161 {
162  placement_publisher_ = nh_.advertise<view_controller_msgs::CameraPlacement>
164 }
165 
167 {
168  mouse_point_publisher_ = nh_.advertise<geometry_msgs::PointStamped>
170 }
171 
173 {
174  geometry_msgs::PointStamped msg;
175  msg.header.frame_id = context_->getFixedFrame().toStdString();
176  msg.header.stamp = ros::Time::now();
178  rviz::RenderPanel* panel = manager->getRenderPanel();
179  Ogre::RenderWindow* window = panel->getRenderWindow();
180  msg.point.x = (double)event.x / window->getWidth();
181  msg.point.y = (double)event.y / window->getHeight();
182  msg.point.z = 0;
184 }
185 
187 {
188  view_controller_msgs::CameraPlacement msg;
190  msg.target_frame = attached_frame_property_->getFrameStd();
191  std::string fixed_frame = context_->getFixedFrame().toStdString();
192  // eye
193  msg.eye.header.stamp = now;
194  msg.eye.header.frame_id = fixed_frame;
195  Ogre::Vector3 eye = eye_point_property_->getVector();
196  msg.eye.point.x = eye[0];
197  msg.eye.point.y = eye[1];
198  msg.eye.point.z = eye[2];
199  // focus
200  msg.focus.header.stamp = now;
201  msg.focus.header.frame_id = fixed_frame;
202  Ogre::Vector3 focus = focus_point_property_->getVector();
203  msg.focus.point.x = focus[0];
204  msg.focus.point.y = focus[1];
205  msg.focus.point.z = focus[2];
206  // up
207  msg.up.header.stamp = now;
208  msg.up.header.frame_id = fixed_frame;
209  Ogre::Vector3 up = up_vector_property_->getVector();
210  msg.up.vector.x = up[0];
211  msg.up.vector.y = up[1];
212  msg.up.vector.z = up[2];
213 
215 }
216 
218 {
219 // trajectory_subscriber_ = nh_.subscribe<view_controller_msgs::CameraPlacementTrajectory>
220 // (camera_placement_trajectory_topic_property_->getStdString(), 1,
221 // boost::bind(&TabletViewController::cameraPlacementTrajectoryCallback, this, _1));
222  placement_subscriber_ = nh_.subscribe<view_controller_msgs::CameraPlacement>
225 }
226 
228 {
230  attached_scene_node_ = context_->getSceneManager()->getRootSceneNode()->createChildSceneNode();
231  camera_->detachFromParent();
232  attached_scene_node_->attachObject( camera_ );
233 
234  camera_->setProjectionType( Ogre::PT_PERSPECTIVE );
235 
237  focal_shape_->setScale(Ogre::Vector3(0.05f, 0.05f, 0.01f));
238  focal_shape_->setColor(1.0f, 1.0f, 0.0f, 0.5f);
239  focal_shape_->getRootNode()->setVisible(false);
240 
241 }
242 
244 {
246 
247  // Before activation, changes to target frame property should have
248  // no side-effects. After activation, changing target frame
249  // property has the side effect (typically) of changing an offset
250  // property so that the view does not jump. Therefore we make the
251  // signal/slot connection from the property here in onActivate()
252  // instead of in the constructor.
253  connect( attached_frame_property_, SIGNAL( changed() ), this, SLOT( updateAttachedFrame() ));
254  connect( fixed_up_property_, SIGNAL( changed() ), this, SLOT( onUpPropertyChanged() ));
256 
257  // Only do this once activated!
258  updateTopics();
261 }
262 
264 {
265  connect( distance_property_, SIGNAL( changed() ), this, SLOT( onDistancePropertyChanged() ), Qt::UniqueConnection);
266  connect( eye_point_property_, SIGNAL( changed() ), this, SLOT( onEyePropertyChanged() ), Qt::UniqueConnection);
267  connect( focus_point_property_, SIGNAL( changed() ), this, SLOT( onFocusPropertyChanged() ), Qt::UniqueConnection);
268  connect( up_vector_property_, SIGNAL( changed() ), this, SLOT( onUpPropertyChanged() ), Qt::UniqueConnection);
269 }
270 
272 {
273  disconnect( distance_property_, SIGNAL( changed() ), this, SLOT( onDistancePropertyChanged() ));
274  disconnect( eye_point_property_, SIGNAL( changed() ), this, SLOT( onEyePropertyChanged() ));
275  disconnect( focus_point_property_, SIGNAL( changed() ), this, SLOT( onFocusPropertyChanged() ));
276  disconnect( up_vector_property_, SIGNAL( changed() ), this, SLOT( onUpPropertyChanged() ));
277 }
278 
280 {
282 }
283 
285 {
287 }
288 
290 {
292  Ogre::Vector3 new_eye_position = focus_point_property_->getVector() + distance_property_->getFloat()* camera_->getOrientation().zAxis();
293  eye_point_property_->setVector(new_eye_position);
295 }
296 
298 {
299  disconnect( up_vector_property_, SIGNAL( changed() ), this, SLOT( onUpPropertyChanged() ));
301  up_vector_property_->setVector(Ogre::Vector3::UNIT_Z);
302  camera_->setFixedYawAxis(true, reference_orientation_ * Ogre::Vector3::UNIT_Z);
303  }
304  else {
305  // force orientation to match up vector; first call doesn't actually change the quaternion
306  camera_->setFixedYawAxis(true, reference_orientation_ * up_vector_property_->getVector());
308  // restore normal behavior
309  camera_->setFixedYawAxis(false);
310  }
311  connect( up_vector_property_, SIGNAL( changed() ), this, SLOT( onUpPropertyChanged() ), Qt::UniqueConnection);
312 }
313 
315 {
316  Ogre::Vector3 old_position = attached_scene_node_->getPosition();
317  Ogre::Quaternion old_orientation = attached_scene_node_->getOrientation();
318 
320 
321  onAttachedFrameChanged( old_position, old_orientation );
322 }
323 
325 {
326  Ogre::Vector3 new_reference_position;
327  Ogre::Quaternion new_reference_orientation;
328 
329  bool queue = false;
331  new_reference_position, new_reference_orientation ))
332  {
333  attached_scene_node_->setPosition( new_reference_position );
334  attached_scene_node_->setOrientation( new_reference_orientation );
335  reference_position_ = new_reference_position;
336  reference_orientation_ = new_reference_orientation;
337  queue = true;
338  }
339  if(queue) context_->queueRender();
340 }
341 
342 void TabletViewController::onAttachedFrameChanged(const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation)
343 {
344  Ogre::Vector3 fixed_frame_focus_position = old_reference_orientation*focus_point_property_->getVector() + old_reference_position;
345  Ogre::Vector3 fixed_frame_eye_position = old_reference_orientation*eye_point_property_->getVector() + old_reference_position;
346  Ogre::Vector3 new_focus_position = fixedFrameToAttachedLocal(fixed_frame_focus_position);
347  Ogre::Vector3 new_eye_position = fixedFrameToAttachedLocal(fixed_frame_eye_position);
348  Ogre::Vector3 new_up_vector = reference_orientation_.Inverse()*old_reference_orientation*up_vector_property_->getVector();
349 
350  //Ogre::Quaternion new_camera_orientation = reference_orientation_.Inverse()*old_reference_orientation*getOrientation();
351 
352  focus_point_property_->setVector(new_focus_position);
353  eye_point_property_->setVector(new_eye_position);
354  up_vector_property_->setVector(fixed_up_property_->getBool() ? Ogre::Vector3::UNIT_Z : new_up_vector);
356 
357  // force orientation to match up vector; first call doesn't actually change the quaternion
358  camera_->setFixedYawAxis(true, reference_orientation_ * up_vector_property_->getVector());
360 }
361 
363 {
365 }
366 
368 {
369  eye_point_property_->setVector(Ogre::Vector3(5, 5, 10));
370  focus_point_property_->setVector(Ogre::Vector3::ZERO);
371  up_vector_property_->setVector(Ogre::Vector3::UNIT_Z);
375 
376 
377  // Hersh says: why is the following junk necessary? I don't know.
378  // However, without this you need to call reset() twice after
379  // switching from TopDownOrtho to FPS. After the first call the
380  // camera is in the right position but pointing the wrong way.
381  updateCamera();
382  camera_->lookAt( 0, 0, 0 );
384 }
385 
387 {
389  {
391  setStatus( "<b>Mouse interaction is disabled. You can enable it by checking the \"Mouse Enabled\" check-box in the Views panel." );
392  return;
393  }
394  else if ( event.shift() )
395  {
396  setStatus( "TODO: Fix me! <b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z." );
397  }
398  else if ( event.control() )
399  {
400  setStatus( "TODO: Fix me! <b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z." );
401  }
402  else
403  {
404  setStatus( "TODO: Fix me! <b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom. <b>Shift</b>: More options." );
405  }
406  if (event.type == QEvent::MouseButtonPress
407  || event.type == QEvent::MouseButtonRelease
408  || (dragging_ && event.type == QEvent::MouseMove)) {
409  publishMouseEvent(event);
410  }
411  float distance = distance_property_->getFloat();
412  int32_t diff_x = 0;
413  int32_t diff_y = 0;
414  bool moved = false;
415 
416  if( event.type == QEvent::MouseButtonPress )
417  {
418  focal_shape_->getRootNode()->setVisible(true);
419  moved = true;
420  dragging_ = true;
421  cancelTransition(); // Stop any automated movement
422  }
423  else if( event.type == QEvent::MouseButtonRelease )
424  {
425  focal_shape_->getRootNode()->setVisible(false);
426  moved = true;
427  dragging_ = false;
428  }
429  else if( dragging_ && event.type == QEvent::MouseMove )
430  {
431  diff_x = event.x - event.last_x;
432  diff_y = event.y - event.last_y;
433  moved = true;
434  }
435 
436  // regular left-button drag
437  if( event.left() && !event.shift() )
438  {
439  setCursor( Rotate3D );
440  yaw_pitch_roll( -diff_x*0.005, -diff_y*0.005, 0 );
441  }
442  // middle or shift-left drag
443  else if( event.middle() || ( event.shift() && event.left() ))
444  {
445  setCursor( MoveXY );
446  if(interaction_mode_property_->getStdString() == MODE_ORBIT) // Orbit style
447  {
448  float fovY = camera_->getFOVy().valueRadians();
449  float fovX = 2.0f * atan( tan( fovY / 2.0f ) * camera_->getAspectRatio() );
450 
451  int width = camera_->getViewport()->getActualWidth();
452  int height = camera_->getViewport()->getActualHeight();
453 
454  move_focus_and_eye( -((float)diff_x / (float)width) * distance * tan( fovX / 2.0f ) * 2.0f,
455  ((float)diff_y / (float)height) * distance * tan( fovY / 2.0f ) * 2.0f,
456  0.0f );
457  }
458  else if(interaction_mode_property_->getStdString() == MODE_FPS) // Orbit style
459  {
460  move_focus_and_eye( diff_x*0.01, -diff_y*0.01, 0.0f );
461  }
462  }
463  else if( event.right() )
464  {
465  if( event.shift() || (interaction_mode_property_->getStdString() == MODE_FPS) )
466  {
467  setCursor( MoveZ );
468  move_focus_and_eye(0.0f, 0.0f, diff_y * 0.01 * distance);
469  }
470  else
471  {
472  setCursor( Zoom );
473  move_eye( 0, 0, diff_y * 0.01 * distance );
474  }
475  }
476  else
477  {
478  setCursor( event.shift() ? MoveXY : Rotate3D );
479  }
480 
481  if ( event.wheel_delta != 0 )
482  {
483  int diff = event.wheel_delta;
484 
485  if( event.shift() )
486  {
487  move_focus_and_eye(0, 0, -diff * 0.001 * distance );
488  }
489  else if(event.control())
490  {
491  yaw_pitch_roll(0, 0, diff*0.001 );
492  }
493  else
494  {
495  move_eye( 0, 0, -diff * 0.001 * distance );
496  }
497  moved = true;
498  }
499 
500  if(event.type == QEvent::MouseButtonPress && event.left() && event.control() && event.shift())
501  {
502  bool was_orbit = (interaction_mode_property_->getStdString() == MODE_ORBIT);
503  interaction_mode_property_->setStdString(was_orbit ? MODE_FPS : MODE_ORBIT );
504  }
505 
506  if (moved)
507  {
510  }
511 }
512 
513 //void TabletViewController::setUpVectorPropertyModeDependent( const Ogre::Vector3 &vector )
514 //{
515 // if(fixed_up_property_->getBool())
516 // {
517 // //up_vector_property_->setVector(Ogre::Vector3::UNIT_Z);
518 // }
519 // else {
520 // up_vector_property_->setVector(vector);
521 // }
522 //}
523 
524 
525 void TabletViewController::setPropertiesFromCamera( Ogre::Camera* source_camera )
526 {
528  Ogre::Vector3 direction = source_camera->getOrientation() * Ogre::Vector3::NEGATIVE_UNIT_Z;
529  eye_point_property_->setVector( source_camera->getPosition() );
530  focus_point_property_->setVector( source_camera->getPosition() + direction*distance_property_->getFloat());
532  up_vector_property_->setVector(Ogre::Vector3::UNIT_Z);
533  else
534  up_vector_property_->setVector(source_camera->getOrientation().yAxis());
535 
536  //setUpVectorPropertyModeDependent(source_camera->getOrientation().yAxis());
538 }
539 
541 {
542  QVariant target_frame = source_view->subProp( "Target Frame" )->getValue();
543  if( target_frame.isValid() )
544  {
545  attached_frame_property_->setValue( target_frame );
546  }
547 
548  Ogre::Camera* source_camera = source_view->getCamera();
549  Ogre::Vector3 position = source_camera->getPosition();
550  Ogre::Quaternion orientation = source_camera->getOrientation();
551 
552  if( source_view->getClassId() == "rviz/Orbit" )
553  {
554  distance_property_->setFloat( source_view->subProp( "Distance" )->getValue().toFloat() );
555  }
556  else
557  {
558  distance_property_->setFloat( position.length() );
559  }
561 
562  Ogre::Vector3 direction = orientation * (Ogre::Vector3::NEGATIVE_UNIT_Z * distance_property_->getFloat() );
563  focus_point_property_->setVector( position + direction );
564  eye_point_property_->setVector(position);
565  updateCamera();
566 }
567 
569 {
570  TabletViewController* fvc = dynamic_cast<TabletViewController*>(previous_view);
571  if(fvc)
572  {
573  Ogre::Vector3 new_eye = eye_point_property_->getVector();
574  Ogre::Vector3 new_focus = focus_point_property_->getVector();
575  Ogre::Vector3 new_up = up_vector_property_->getVector();
576 
580 
582  }
583 }
584 
585 void TabletViewController::beginNewTransition(const Ogre::Vector3 &eye, const Ogre::Vector3 &focus, const Ogre::Vector3 &up,
586  const ros::Duration &transition_time)
587 {
588  if(ros::Duration(transition_time).isZero())
589  {
594  return;
595  }
596 
598  goal_position_ = eye;
599 
601  goal_focus_ = focus;
602 
603 // start_up_ = fixed_up_property_->getBool() ? (Ogre::Vector3::UNIT_Z) : getOrientation().yAxis();
604 // goal_up_ = fixed_up_property_->getBool() ? (Ogre::Vector3::UNIT_Z) : up;
606  goal_up_ = up;
607 
608  current_transition_duration_ = ros::Duration(transition_time);
610 
611  animate_ = true;
612 }
613 
615 {
616  animate_ = false;
617 }
618 
619 void TabletViewController::cameraPlacementCallback(const CameraPlacementConstPtr &cp_ptr)
620 {
621  CameraPlacement cp = *cp_ptr;
622 
623  // Handle control parameters
624  mouse_enabled_property_->setBool( !cp.interaction_disabled );
625  fixed_up_property_->setBool( !cp.allow_free_yaw_axis );
626  if(cp.mouse_interaction_mode != cp.NO_CHANGE)
627  {
628  std::string name = "";
629  if(cp.mouse_interaction_mode == cp.ORBIT) name = MODE_ORBIT;
630  else if(cp.mouse_interaction_mode == cp.FPS) name = MODE_FPS;
632  }
633 
634  if(cp.target_frame != "")
635  {
636  attached_frame_property_->setStdString(cp.target_frame);
638  }
639 
640  if(cp.time_from_start.toSec() >= 0)
641  {
642  ROS_DEBUG_STREAM("Received a camera placement request! \n" << cp);
644  ROS_DEBUG_STREAM("After transform, we have \n" << cp);
645 
646  Ogre::Vector3 eye = vectorFromMsg(cp.eye.point);
647  Ogre::Vector3 focus = vectorFromMsg(cp.focus.point);
648  Ogre::Vector3 up = vectorFromMsg(cp.up.vector);
649 
650  beginNewTransition(eye, focus, up, cp.time_from_start);
651  }
652 }
653 
654 //void TabletViewController::cameraPlacementTrajectoryCallback(const CameraPlacementTrajectoryConstPtr &cptptr)
655 //{
656 // CameraPlacementTrajectory cpt = *cptptr;
657 // ROS_DEBUG_STREAM("Received a camera placement trajectory request! \n" << cpt);
658 
659 // // Handle control parameters
660 // mouse_enabled_property_->setBool( cpt.interaction_enabled );
661 // fixed_up_property_->setBool( !cpt.allow_free_yaw_axis );
662 // if(cpt.mouse_interaction_mode != cpt.NO_CHANGE)
663 // {
664 // std::string name = "";
665 // if(cpt.mouse_interaction_mode == cpt.ORBIT) name = MODE_ORBIT;
666 // else if(cpt.mouse_interaction_mode == cpt.FPS) name = MODE_FPS;
667 // interaction_mode_property_->setStdString(name);
668 // }
669 
670 // // TODO should transform the interpolated positions (later), or transform info will only reflect the TF tree state at the beginning...
671 // for(size_t i = 0; i<cpt.placements.size(); i++)
672 // {
673 // transformCameraPlacementToAttachedFrame(cpt.placements[i]);
674 // }
675 
676 // // For now, just transition to the first placement until we put in the capacity for a trajectory
677 // CameraPlacement cp = cpt.placements[0];
678 // if(cp.target_frame != "")
679 // {
680 // attached_frame_property_->setStdString(cp.target_frame);
681 // updateAttachedFrame();
682 // }
683 // Ogre::Vector3 eye = vectorFromMsg(cp.eye.point);
684 // Ogre::Vector3 focus = vectorFromMsg(cp.focus.point);
685 // Ogre::Vector3 up = vectorFromMsg(cp.up.vector);
686 
687 // beginNewTransition(eye, focus, up, cp.time_from_start);
688 //}
689 
691 {
692  Ogre::Vector3 position_fixed_eye, position_fixed_focus, position_fixed_up; // position_fixed_attached;
693  Ogre::Quaternion rotation_fixed_eye, rotation_fixed_focus, rotation_fixed_up; // rotation_fixed_attached;
694 
695  context_->getFrameManager()->getTransform(cp.eye.header.frame_id, ros::Time(0), position_fixed_eye, rotation_fixed_eye);
696  context_->getFrameManager()->getTransform(cp.focus.header.frame_id, ros::Time(0), position_fixed_focus, rotation_fixed_focus);
697  context_->getFrameManager()->getTransform(cp.up.header.frame_id, ros::Time(0), position_fixed_up, rotation_fixed_up);
698  //context_->getFrameManager()->getTransform(attached_frame_property_->getStdString(), ros::Time(0), position_fixed_attached, rotation_fixed_attached);
699 
700  Ogre::Vector3 eye = vectorFromMsg(cp.eye.point);
701  Ogre::Vector3 focus = vectorFromMsg(cp.focus.point);
702  Ogre::Vector3 up = vectorFromMsg(cp.up.vector);
703 
704  eye = fixedFrameToAttachedLocal(position_fixed_eye + rotation_fixed_eye*eye);
705  focus = fixedFrameToAttachedLocal(position_fixed_focus + rotation_fixed_focus*focus);
706  up = reference_orientation_.Inverse()*rotation_fixed_up*up;
707  //up = rotation_fixed_up*up;
708 
709  cp.eye.point = pointOgreToMsg(eye);
710  cp.focus.point = pointOgreToMsg(focus);
711  cp.up.vector = vectorOgreToMsg(up);
712  cp.eye.header.frame_id = attached_frame_property_->getStdString();
713  cp.focus.header.frame_id = attached_frame_property_->getStdString();
714  cp.up.header.frame_id = attached_frame_property_->getStdString();
715 }
716 
717 
718 // We must assume that this point is in the Rviz Fixed frame since it came from Rviz...
719 void TabletViewController::lookAt( const Ogre::Vector3& point )
720 {
721  if( !mouse_enabled_property_->getBool() ) return;
722 
723  Ogre::Vector3 new_point = fixedFrameToAttachedLocal(point);
724 
728 
729  // // Just for easily testing the other movement styles:
730  // orbitCameraTo(point);
731  // moveCameraWithFocusTo(point);
732 }
733 
734 void TabletViewController::orbitCameraTo( const Ogre::Vector3& point)
735 {
739 }
740 
741 void TabletViewController::moveEyeWithFocusTo( const Ogre::Vector3& point)
742 {
746 }
747 
748 
749 void TabletViewController::update(float dt, float ros_dt)
750 {
752 
753  if(animate_)
754  {
756  float fraction = time_from_start.toSec()/current_transition_duration_.toSec();
757  // make sure we get all the way there before turning off
758  if(fraction > 1.0f)
759  {
760  fraction = 1.0f;
761  animate_ = false;
762  }
763 
764  // TODO remap progress to progress_out, which can give us a new interpolation profile.
765  float progress = 0.5*(1-cos(fraction*M_PI));
766 
767  Ogre::Vector3 new_position = start_position_ + progress*(goal_position_ - start_position_);
768  Ogre::Vector3 new_focus = start_focus_ + progress*(goal_focus_ - start_focus_);
769  Ogre::Vector3 new_up = start_up_ + progress*(goal_up_ - start_up_);
770 
772  eye_point_property_->setVector( new_position );
773  focus_point_property_->setVector( new_focus );
777 
778  // This needs to happen so that the camera orientation will update properly when fixed_up_property == false
779  camera_->setFixedYawAxis(true, reference_orientation_ * up_vector_property_->getVector());
781  }
782  updateCamera();
783 }
784 
786 {
787  camera_->setPosition( eye_point_property_->getVector() );
790  //camera_->setDirection( (focus_point_property_->getVector() - eye_point_property_->getVector()));
792 }
793 
794 void TabletViewController::yaw_pitch_roll( float yaw, float pitch, float roll )
795 {
796  Ogre::Quaternion old_camera_orientation = camera_->getOrientation();
797  Ogre::Radian old_pitch = old_camera_orientation.getPitch(false);// - Ogre::Radian(Ogre::Math::HALF_PI);
798 
799  if(fixed_up_property_->getBool()) yaw = cos(old_pitch.valueRadians() - Ogre::Math::HALF_PI)*yaw; // helps to reduce crazy spinning!
800 
801  Ogre::Quaternion yaw_quat, pitch_quat, roll_quat;
802  yaw_quat.FromAngleAxis( Ogre::Radian( yaw ), Ogre::Vector3::UNIT_Y );
803  pitch_quat.FromAngleAxis( Ogre::Radian( pitch ), Ogre::Vector3::UNIT_X );
804  roll_quat.FromAngleAxis( Ogre::Radian( roll ), Ogre::Vector3::UNIT_Z );
805  Ogre::Quaternion orientation_change = yaw_quat * pitch_quat * roll_quat;
806  Ogre::Quaternion new_camera_orientation = old_camera_orientation * orientation_change;
807  Ogre::Radian new_pitch = new_camera_orientation.getPitch(false);// - Ogre::Radian(Ogre::Math::HALF_PI);
808 
809  if( fixed_up_property_->getBool() &&
810  ((new_pitch > PITCH_LIMIT_HIGH && new_pitch > old_pitch) || (new_pitch < PITCH_LIMIT_LOW && new_pitch < old_pitch)) )
811  {
812  orientation_change = yaw_quat * roll_quat;
813  new_camera_orientation = old_camera_orientation * orientation_change;
814  }
815 
816 // Ogre::Radian new_roll = new_camera_orientation.getRoll(false);
817 // Ogre::Radian new_yaw = new_camera_orientation.getYaw(false);
818  //ROS_INFO("old_pitch: %.3f, new_pitch: %.3f", old_pitch.valueRadians(), new_pitch.valueRadians());
819 
820  camera_->setOrientation( new_camera_orientation );
822  {
823  // In orbit mode the focal point stays fixed, so we need to compute the new camera position.
824  Ogre::Vector3 new_eye_position = focus_point_property_->getVector() + distance_property_->getFloat()* new_camera_orientation.zAxis();
825  eye_point_property_->setVector(new_eye_position);
826  camera_->setPosition(new_eye_position);
828  }
829  else
830  {
831  // In FPS mode the camera stays fixed, so we can just apply the rotations and then rely on the property update to set the new focal point.
833  }
834 }
835 
836 Ogre::Quaternion TabletViewController::getOrientation() // Do we need this?
837 {
838  return camera_->getOrientation();
839 }
840 
841 void TabletViewController::move_focus_and_eye( float x, float y, float z )
842 {
843  Ogre::Vector3 translate( x, y, z );
844  eye_point_property_->add( getOrientation() * translate );
845  focus_point_property_->add( getOrientation() * translate );
846 }
847 
848 void TabletViewController::move_eye( float x, float y, float z )
849 {
850  Ogre::Vector3 translate( x, y, z );
851  // Only update the camera position if it won't "pass through" the origin
852  Ogre::Vector3 new_position = eye_point_property_->getVector() + getOrientation() * translate;
853  if( (new_position - focus_point_property_->getVector()).length() > distance_property_->getMin() )
854  eye_point_property_->setVector(new_position);
856 }
857 
858 } // end namespace rviz
859 
void setPropertiesFromCamera(Ogre::Camera *source_camera)
msg
#define NULL
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
f
void setMin(float min)
virtual void reset()
Resets the camera parameters to a sane value.
rviz::VectorProperty * focus_point_property_
The point around which the camera "orbits".
virtual void onAttachedFrameChanged(const Ogre::Vector3 &old_reference_position, const Ogre::Quaternion &old_reference_orientation)
Override to implement the change in properties which nullifies the change in attached frame...
An un-constrained "flying" camera, specified by an eye point, focus point, and up vector...
std::string getFrameStd() const
virtual void onUpPropertyChanged()
Called when up vector property is changed (does nothing for now...).
virtual bool setVector(const Ogre::Vector3 &vector)
void publishMouseEvent(rviz::ViewportMouseEvent &event)
void updateCamera()
Updates the Ogre camera properties from the view controller properties.
Ogre::Vector3 reference_position_
Used to store the position of the attached frame relative to <Fixed frame>="">
Ogre::Quaternion getOrientation()
Return a Quaternion.
QCursor makeIconCursor(QString url, bool fill_cache)
void updateAttachedSceneNode()
Update the position of the attached_scene_node_ from the TF frame specified in the Attached Frame pro...
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
void cameraPlacementCallback(const view_controller_msgs::CameraPlacementConstPtr &cp_ptr)
virtual void onActivate()
called by activate().
void disconnectPositionProperties()
Convenience function; disconnects the signals/slots for position properties.
void beginNewTransition(const Ogre::Vector3 &eye, const Ogre::Vector3 &focus, const Ogre::Vector3 &up, const ros::Duration &transition_time)
Begins a camera movement animation to the given goal points.
std::string target_frame
virtual ViewManager * getViewManager() const=0
void setScale(const Ogre::Vector3 &scale) override
void yaw_pitch_roll(float yaw, float pitch, float roll)
Applies a body-fixed-axes sequence of rotations; only accurate for small angles.
void move_eye(float x, float y, float z)
Applies a translation to only the eye point.
void cancelTransition()
Cancels any currently active camera movement.
Ogre::Vector3 fixedFrameToAttachedLocal(const Ogre::Vector3 &v)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void setCursor(CursorType cursor_type)
rviz::BoolProperty * mouse_enabled_property_
If True, most user changes to camera state are disabled.
Ogre::Camera * getCamera() const
virtual Ogre::Vector3 getVector() const
virtual void updateAttachedFrame()
Called when Target Frame property changes while view is active. Purpose is to change values in the vi...
static geometry_msgs::Vector3 vectorOgreToMsg(const Ogre::Vector3 &o)
Ogre::Camera * camera_
width
void addOptionStd(const std::string &option)
void setColor(float r, float g, float b, float a) override
bool setValue(const QVariant &new_value) override
bool add(const Ogre::Vector3 &offset)
static Ogre::Vector3 vectorFromMsg(const geometry_msgs::Point &m)
void orbitCameraTo(const Ogre::Vector3 &point)
Calls beginNewTransition() with the focus point fixed, moving the eye to the point given...
virtual QString getClassId() const
std::string getStdString()
virtual void lookAt(const Ogre::Vector3 &point)
Calls beginNewTransition() to move the focus point to the point provided, assumed to be in the Rviz F...
virtual void handleMouseEvent(rviz::ViewportMouseEvent &evt)
bool setFloat(float new_value)
virtual Property * subProp(const QString &sub_name)
bool dragging_
A flag indicating the dragging state of the mouse.
Ogre::RenderWindow * getRenderWindow()
void publish(const boost::shared_ptr< M > &message) const
rviz::RosTopicProperty * camera_placement_publish_topic_property_
rviz::EditableEnumProperty * interaction_mode_property_
Select between Orbit or FPS control style.
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
virtual void mimic(ViewController *source_view)
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
rviz::RosTopicProperty * camera_placement_topic_property_
rviz::BoolProperty * fixed_up_property_
If True, "up" is fixed to ... up.
RenderPanel * getRenderPanel() const
virtual void transitionFrom(ViewController *previous_view)
Called by ViewManager when this ViewController is being made current.
void setStatus(const QString &message)
virtual FrameManager * getFrameManager() const=0
virtual void update(float dt, float ros_dt)
Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to r...
virtual void onDistancePropertyChanged()
Called when distance property is changed; computes new eye position.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_DEBUG_STREAM(args)
virtual void onFocusPropertyChanged()
Called focus property is changed; computes new distance.
rviz::RosTopicProperty * mouse_point_publish_topic_property_
void setPosition(const Ogre::Vector3 &position) override
rviz::Shape * focal_shape_
A small ellipsoid to show the focus point.
static const Ogre::Radian PITCH_LIMIT_LOW
virtual Ogre::SceneManager * getSceneManager() const=0
virtual void queueRender()=0
void move_focus_and_eye(float x, float y, float z)
Applies a translation to the focus and eye points.
virtual QString getFixedFrame() const=0
static const QString FIXED_FRAME_STRING
virtual float getFloat() const
Ogre::Quaternion reference_orientation_
Used to store the orientation of the attached frame relative to <Fixed frame>=""> ...
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void moveEyeWithFocusTo(const Ogre::Vector3 &point)
Calls beginNewTransition() to move the eye to the point given, keeping the direction fixed...
void setFrameManager(FrameManager *frame_manager)
rviz::VectorProperty * eye_point_property_
The position of the camera.
float getDistanceFromCameraToFocalPoint()
Return the distance between camera and focal point.
static Time now()
static const Ogre::Radian PITCH_LIMIT_HIGH
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
virtual QVariant getValue() const
boost::arg< 1 > _1
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
Ogre::SceneNode * getRootNode()
height
static geometry_msgs::Point pointOgreToMsg(const Ogre::Vector3 &o)
void transformCameraPlacementToAttachedFrame(view_controller_msgs::CameraPlacement &cp)
virtual bool getBool() const
bool setStdString(const std::string &std_str)
DisplayContext * context_
QCursor interaction_disabled_cursor_
A cursor for indicating mouse interaction is disabled.
bool setBool(bool value)
static const std::string MODE_ORBIT
void connectPositionProperties()
Convenience function; connects the signals/slots for position properties.
rviz::FloatProperty * default_transition_time_property_
A default time for any animation requests.
rviz::VectorProperty * up_vector_property_
The up vector for the camera.
rviz::FloatProperty * distance_property_
The camera&#39;s distance from the focal point.
virtual void onEyePropertyChanged()
Called when eye property is changed; computes new distance.
static const std::string MODE_FPS


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Thu Jun 1 2023 02:45:58