interactive_marker_control.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, 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 <OgreCamera.h>
32 #include <OgreSceneNode.h>
33 #include <OgreSceneManager.h>
34 #include <OgrePass.h>
35 #include <OgreMaterial.h>
36 #include <OgreEntity.h>
37 #include <OgreSubEntity.h>
38 #include <OgreSharedPtr.h>
39 #include <OgreTechnique.h>
40 
41 #include "rviz/display_context.h"
43 #include "rviz/render_panel.h"
44 #include "rviz/load_resource.h"
46 #include "rviz/geometry.h"
47 #include "rviz/frame_manager.h"
48 
49 #include "rviz/ogre_helpers/line.h"
50 
53 
56 
57 #define NO_HIGHLIGHT_VALUE 0.0
58 #define ACTIVE_HIGHLIGHT_VALUE 0.5
59 #define HOVER_HIGHLIGHT_VALUE 0.3
60 
61 namespace rviz
62 {
63 
65  Ogre::SceneNode *reference_node,
66  InteractiveMarker *parent )
67 : mouse_dragging_(false)
68 , drag_viewport_( NULL )
69 , context_( context )
70 , reference_node_(reference_node)
71 , control_frame_node_(reference_node_->createChildSceneNode())
72 , markers_node_(reference_node_->createChildSceneNode())
73 , parent_(parent)
74 , rotation_(0)
75 , grab_point_in_reference_frame_(0,0,0)
76 , interaction_enabled_(false)
77 , visible_(true)
78 , view_facing_( false )
79 , mouse_down_(false)
80 , show_visual_aids_(false)
81 , line_(new Line(context->getSceneManager(),control_frame_node_))
82 {
83  line_->setVisible(false);
84 }
85 
86 void InteractiveMarkerControl::makeMarkers( const visualization_msgs::InteractiveMarkerControl& message )
87 {
88  for (unsigned i = 0; i < message.markers.size(); i++)
89  {
90  // create a marker with the given type
91  MarkerBasePtr marker(createMarker(message.markers[i].type, 0, context_, markers_node_));
92  if (!marker) {
93  ROS_ERROR( "Unknown marker type: %d", message.markers[i].type );
94  }
95 
96  PointsMarkerPtr points_marker = boost::dynamic_pointer_cast<PointsMarker>(marker);
97  if (points_marker) {
98  points_markers_.push_back( points_marker );
99  }
100 
101  visualization_msgs::MarkerPtr marker_msg( new visualization_msgs::Marker(message.markers[ i ]) );
102 
103  if ( marker_msg->header.frame_id.empty() )
104  {
105  // Put Marker into fixed frame, so the constructor does not apply any tf transform.
106  // This effectively discards any tf information in the Marker and interprets its pose
107  // as relative to the Interactive Marker.
108  marker_msg->header.frame_id = context_->getFrameManager()->getFixedFrame();
109  marker->setMessage( marker_msg );
110  }
111  else
112  {
113  marker->setMessage( marker_msg );
114  // The marker will set its position relative to the fixed frame,
115  // but we have attached it our own scene node, so we will have to
116  // correct for that.
117  marker->setPosition( markers_node_->convertWorldToLocalPosition( marker->getPosition() ) );
118  marker->setOrientation( markers_node_->convertWorldToLocalOrientation( marker->getOrientation() ) );
119  }
120  marker->setInteractiveObject( shared_from_this() );
121 
122  addHighlightPass(marker->getMaterials());
123 
124  markers_.push_back(marker);
125  }
126 }
127 
129 {
130  context_->getSceneManager()->destroySceneNode(control_frame_node_);
131  context_->getSceneManager()->destroySceneNode(markers_node_);
132 
133  if( view_facing_ )
134  {
135  context_->getSceneManager()->removeListener(this);
136  }
137 }
138 
139 void InteractiveMarkerControl::processMessage( const visualization_msgs::InteractiveMarkerControl &message )
140 {
141  name_ = message.name;
142  description_ = QString::fromStdString( message.description );
143  interaction_mode_ = message.interaction_mode;
144  always_visible_ = message.always_visible;
145  orientation_mode_ = message.orientation_mode;
146 
147  control_orientation_ = Ogre::Quaternion(message.orientation.w,
148  message.orientation.x, message.orientation.y, message.orientation.z);
149  control_orientation_.normalise();
150 
151  bool new_view_facingness = (message.orientation_mode == visualization_msgs::InteractiveMarkerControl::VIEW_FACING);
152  if( new_view_facingness != view_facing_ )
153  {
154  if( new_view_facingness )
155  {
156  context_->getSceneManager()->addListener(this);
157  }
158  else
159  {
160  context_->getSceneManager()->removeListener(this);
161  }
162  view_facing_ = new_view_facingness;
163  }
164 
165  independent_marker_orientation_ = message.independent_marker_orientation;
166 
167  // highlight_passes_ have raw pointers into the markers_, so must
168  // clear them at the same time.
169  highlight_passes_.clear();
170  markers_.clear();
171  points_markers_.clear();
172 
173  // Initially, the pose of this marker's node and the interactive
174  // marker are identical, but that may change.
175  control_frame_node_->setPosition(parent_->getPosition());
176  markers_node_->setPosition(parent_->getPosition());
177 
178  if ( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::INHERIT )
179  {
180  control_frame_node_->setOrientation(parent_->getOrientation());
181  markers_node_->setOrientation(parent_->getOrientation());
182  }
183  else
184  {
185  control_frame_node_->setOrientation( Ogre::Quaternion::IDENTITY );
186  markers_node_->setOrientation( Ogre::Quaternion::IDENTITY );
187  }
188 
189  makeMarkers( message );
190 
192 
193  Ogre::Vector3 control_dir = control_orientation_.xAxis()*10000.0;
194  line_->setPoints( control_dir, -1*control_dir );
195  line_->setVisible(false);
196 
197  // Create our own custom cursor
198  switch( interaction_mode_ )
199  {
200  case visualization_msgs::InteractiveMarkerControl::NONE:
202  break;
203  case visualization_msgs::InteractiveMarkerControl::MENU:
204  cursor_ = rviz::makeIconCursor( "package://rviz/icons/menu.svg" );
205  status_msg_ += "<b>Left-Click:</b> Show menu.";
206  break;
207  case visualization_msgs::InteractiveMarkerControl::BUTTON:
209  status_msg_ += "<b>Left-Click:</b> Activate. ";
210  break;
211  case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
212  cursor_ = rviz::makeIconCursor( "package://rviz/icons/move1d.svg" );
213  status_msg_ += "<b>Left-Click:</b> Move. ";
214  break;
215  case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
216  cursor_ = rviz::makeIconCursor( "package://rviz/icons/move2d.svg" );
217  status_msg_ += "<b>Left-Click:</b> Move. ";
218  break;
219  case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
220  cursor_ = rviz::makeIconCursor( "package://rviz/icons/rotate.svg" );
221  status_msg_ += "<b>Left-Click:</b> Rotate. ";
222  break;
223  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
224  cursor_ = rviz::makeIconCursor( "package://rviz/icons/moverotate.svg" );
225  status_msg_ += "<b>Left-Click:</b> Move / Rotate. ";
226  break;
227  case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
228  cursor_ = rviz::makeIconCursor( "package://rviz/icons/move2d.svg" );
229  status_msg_ += "<b>Left-Click:</b> Move X/Y. <b>Shift + Left-Click / Left-Click + Wheel:</b> Move Z. ";
230  break;
231  case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
232  cursor_ = rviz::makeIconCursor( "package://rviz/icons/rotate.svg" );
233  status_msg_ += "<b>Left-Click:</b> Rotate around X/Y. <b>Shift-Left-Click:</b> Rotate around Z. ";
234  break;
235  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
236  cursor_ = rviz::makeIconCursor( "package://rviz/icons/moverotate.svg" );
237  status_msg_ += "<b>Left-Click:</b> Move X/Y. <b>Shift + Left-Click / Left-Click + Wheel:</b> Move Z. <b>Ctrl + Left-Click:</b> Rotate around X/Y. <b>Ctrl + Shift + Left-Click:</b> Rotate around Z. ";
238  break;
239  }
240 
241  if ( parent_->hasMenu() && interaction_mode_ != visualization_msgs::InteractiveMarkerControl::MENU )
242  {
243  status_msg_ += "<b>Right-Click:</b> Show context menu.";
244  }
245 
246  // It's not clear to me why this one setOrientation() call needs to
247  // be here and not above makeMarkers() with the other
248  // setOrientation() calls, but it works correctly when here and
249  // incorrectly when there. Sorry. -hersh
250  if( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
252  {
253  markers_node_->setOrientation( parent_->getOrientation() );
254  }
255 
257 }
258 
259 // This is an Ogre::SceneManager::Listener function, and is configured
260 // to be called only if this is a VIEW_FACING control.
262  Ogre::SceneManager *source,
263  Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v )
264 {
266 }
267 
269 {
270  Ogre::Quaternion x_view_facing_rotation =
271  control_orientation_.xAxis().getRotationTo( v->getCamera()->getDerivedDirection());
272 
273  // rotate so z axis is up
274  Ogre::Vector3 z_axis_2 = x_view_facing_rotation * control_orientation_.zAxis();
275  Ogre::Quaternion align_yz_rotation = z_axis_2.getRotationTo(v->getCamera()->getDerivedUp());
276 
277  // rotate
278  Ogre::Quaternion rotate_around_x = Ogre::Quaternion(rotation_, v->getCamera()->getDerivedDirection());
279 
280  Ogre::Quaternion rotation = reference_node_->convertWorldToLocalOrientation(
281  rotate_around_x * align_yz_rotation * x_view_facing_rotation );
282 
283  control_frame_node_->setOrientation( rotation );
284 
286  {
287  markers_node_->setOrientation( rotation );
288  // we need to refresh the node manually, since the scene manager will only do this one frame
289  // later otherwise
290  markers_node_->_update(true, false);
291  }
292 }
293 
295 {
296  return visible_ || always_visible_;
297 }
298 
300 {
301  visible_ = visible;
302 
303  if (always_visible_)
304  {
305  markers_node_->setVisible(visible_);
306  } else
307  {
309  }
310 }
311 
313 {
314  if( mouse_dragging_ )
315  {
317  }
318 }
319 
321 {
322  if (mouse_down_)
323  {
324  return;
325  }
326 
327  interaction_enabled_ = enable;
329  if (!enable)
330  {
332  }
333 }
334 
336  Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation )
337 {
338  control_frame_node_->setPosition(int_marker_position);
339  markers_node_->setPosition(int_marker_position);
340 
341  switch (orientation_mode_)
342  {
343  case visualization_msgs::InteractiveMarkerControl::INHERIT:
344  control_frame_node_->setOrientation(int_marker_orientation);
345  markers_node_->setOrientation(control_frame_node_->getOrientation());
346  break;
347 
348  case visualization_msgs::InteractiveMarkerControl::FIXED:
349  {
350  control_frame_node_->setOrientation( Ogre::Quaternion( rotation_, control_orientation_.xAxis() ));
351  markers_node_->setOrientation(control_frame_node_->getOrientation());
352  break;
353  }
354 
355  case visualization_msgs::InteractiveMarkerControl::VIEW_FACING:
356  if( drag_viewport_ )
357  {
359  }
361  {
362  markers_node_->setOrientation(int_marker_orientation);
363  }
364  break;
365 
366  default:
367  break;
368  }
369 }
370 
371 Ogre::Vector3 InteractiveMarkerControl::closestPointOnLineToPoint( const Ogre::Vector3& line_start,
372  const Ogre::Vector3& line_dir,
373  const Ogre::Vector3& test_point )
374 {
375  // Find closest point on projected ray to mouse point
376  // Math: if P is the start of the ray, v is the direction vector of
377  // the ray (not normalized), and X is the test point, then the
378  // closest point on the line to X is given by:
379  //
380  // (X-P).v
381  // P + v * -------
382  // v.v
383  // where "." is the dot product.
384  double factor = ( test_point - line_start ).dotProduct( line_dir ) / line_dir.dotProduct( line_dir );
385  Ogre::Vector3 closest_point = line_start + line_dir * factor;
386  return closest_point;
387 }
388 
389 void InteractiveMarkerControl::rotate( Ogre::Ray &mouse_ray )
390 {
391  Ogre::Vector3 intersection_3d;
392  Ogre::Vector2 intersection_2d;
393  float ray_t;
394 
395  Ogre::Vector3 rotation_axis = control_frame_orientation_at_mouse_down_ * control_orientation_.xAxis();
396 
397  // Find rotation_center = 3D point closest to grab_point_ which is
398  // on the rotation axis, relative to the reference frame.
399  Ogre::Vector3 rotation_center = closestPointOnLineToPoint( control_frame_node_->getPosition(),
400  rotation_axis,
402 
403  // Find intersection of mouse_ray with plane centered at rotation_center.
404  if( intersectSomeYzPlane( mouse_ray, rotation_center, control_frame_orientation_at_mouse_down_,
405  intersection_3d, intersection_2d, ray_t ))
406  {
407  // Not that efficient, but reduces code duplication...
408  rotate(intersection_3d);
409  }
410 }
411 
412 void InteractiveMarkerControl::rotate( const Ogre::Vector3& cursor_in_reference_frame )
413 {
414  Ogre::Vector3 rotation_axis = control_frame_orientation_at_mouse_down_ * control_orientation_.xAxis();
415 
416  // Find rotation_center = 3D point closest to grab_point_ which is
417  // on the rotation axis, relative to the reference frame.
418  Ogre::Vector3 rotation_center = closestPointOnLineToPoint( control_frame_node_->getPosition(),
419  rotation_axis,
421 
422 
423  Ogre::Vector3 grab_rel_center = grab_point_in_reference_frame_ - rotation_center;
424  Ogre::Vector3 center_to_cursor = cursor_in_reference_frame - rotation_center;
425  Ogre::Vector3 center_to_cursor_radial = center_to_cursor - center_to_cursor.dotProduct(rotation_axis)*rotation_axis;
426 
427  Ogre::Quaternion orientation_change_since_mouse_down =
428  grab_rel_center.getRotationTo( center_to_cursor_radial, rotation_axis );
429 
430  Ogre::Radian rot;
431  Ogre::Vector3 axis;
432  orientation_change_since_mouse_down.ToAngleAxis( rot, axis );
433  // Quaternion::ToAngleAxis() always gives a positive angle. The
434  // axis it emits (in this case) will either be equal to
435  // rotation_axis or will be the negative of it. Doing the
436  // dot-product then gives either 1.0 or -1.0, which is just what
437  // we need to get the sign for our angle.
438  Ogre::Radian rotation_since_mouse_down = rot * axis.dotProduct( rotation_axis );
439 
440  rotation_ = rotation_at_mouse_down_ + rotation_since_mouse_down;
442  orientation_change_since_mouse_down * parent_orientation_at_mouse_down_,
443  name_ );
444 }
445 
447 {
448  float width = event.viewport->getActualWidth() - 1;
449  float height = event.viewport->getActualHeight() - 1;
450 
451  Ogre::Ray mouse_ray = event.viewport->getCamera()->getCameraToViewportRay( (x + .5) / width,
452  (y + .5) / height );
453 
454  // convert ray into reference frame
455  mouse_ray.setOrigin( reference_node_->convertWorldToLocalPosition( mouse_ray.getOrigin() ) );
456  mouse_ray.setDirection( reference_node_->convertWorldToLocalOrientation( Ogre::Quaternion::IDENTITY ) * mouse_ray.getDirection() );
457 
458  return mouse_ray;
459 }
460 
462 {
463  mouse_x_at_drag_begin_ = event.x;
464  mouse_y_at_drag_begin_ = event.y;
465  modifiers_at_drag_begin_ = event.modifiers;
466 
467  mouse_ray_at_drag_begin_ = getMouseRayInReferenceFrame( event, event.x, event.y );
468 
469  // ensure direction is unit vector
470  mouse_ray_at_drag_begin_.setDirection(mouse_ray_at_drag_begin_.getDirection().normalisedCopy());
471 }
472 
474 {
475  dx = event.x - mouse_x_at_drag_begin_;
476  dy = event.y - mouse_y_at_drag_begin_;
477  if (dx == 0 && dy == 0)
478  return false;
479 
482  return true;
483 }
484 
486 {
487  int dx;
488  int dy;
489 
490  if (!getRelativeMouseMotion( event, dx, dy ))
491  return;
492 
493  static const double MOUSE_SCALE = 2 * 3.14 / 300; // 300 pixels = 360deg
494  Ogre::Radian rx(dx * MOUSE_SCALE);
495  Ogre::Radian ry(dy * MOUSE_SCALE);
496 
497  Ogre::Quaternion up_rot(rx, event.viewport->getCamera()->getRealUp());
498  Ogre::Quaternion right_rot(ry, event.viewport->getCamera()->getRealRight());
499 
501  up_rot * right_rot * parent_->getOrientation(),
502  name_ );
503 }
504 
506 {
507  int dx;
508  int dy;
509 
510  getRelativeMouseMotion( event, dx, dy );
511  if (std::abs(dy) > std::abs(dx))
512  dx = dy;
513  if (dx == 0)
514  return;
515 
516  static const double MOUSE_SCALE = 2 * 3.14 / 300; // 300 pixels = 360deg
517  Ogre::Radian rx(dx * MOUSE_SCALE);
518 
519  Ogre::Quaternion rot(rx, event.viewport->getCamera()->getRealDirection());
520 
522  rot * parent_->getOrientation(),
523  name_ );
524 }
525 
527 {
528  int dx;
529  int dy;
530 
531  getRelativeMouseMotion( event, dx, dy );
532  if (std::abs(dx) > std::abs(dy))
533  dy = -dx;
534  if (dy == 0)
535  return;
536 
537  double distance = -dy * mouse_z_scale_;
538  Ogre::Vector3 delta = distance * mouse_ray_at_drag_begin_.getDirection();
539 
540  parent_->setPose( parent_->getPosition() + delta,
542  name_ );
543 
545 }
546 
548 {
549  // wheel_delta is in 1/8 degree and usually jumps 15 degrees at a time
550  static const double WHEEL_TO_PIXEL_SCALE = (1.0/8.0) * (2.0/15.0); // 2 pixels per click
551 
552  double distance = event.wheel_delta * WHEEL_TO_PIXEL_SCALE;
553  Ogre::Vector3 delta = distance * mouse_ray_at_drag_begin_.getDirection();
554 
555  parent_->setPose( parent_->getPosition() + delta,
557  name_ );
558 
560 }
561 
562 void InteractiveMarkerControl::moveViewPlane( Ogre::Ray &mouse_ray, const ViewportMouseEvent& event )
563 {
564  // find plane on which mouse is moving
565  Ogre::Plane plane( event.viewport->getCamera()->getRealDirection(),
567 
568  // find intersection of mouse with the plane
569  std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(plane);
570  if (!intersection.first)
571  return;
572  Ogre::Vector3 mouse_position_on_plane = mouse_ray.getPoint(intersection.second);
573 
574  // move parent so grab position relative to parent coincides with new mouse position.
577  name_ );
578 }
579 
580 void InteractiveMarkerControl::movePlane( Ogre::Ray &mouse_ray )
581 {
582  if( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
584  {
586  }
587 
588  Ogre::Vector3 intersection_3d;
589  Ogre::Vector2 intersection_2d;
590  float ray_t;
591 
593  intersection_3d, intersection_2d, ray_t ))
594  {
596  }
597 }
598 
599 void InteractiveMarkerControl::movePlane( const Ogre::Vector3& cursor_position_in_reference_frame )
600 {
601  if( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
603  {
605  }
606 
607  Ogre::Vector3 plane_normal = (control_frame_node_->getOrientation() * control_orientation_.xAxis());
608  Ogre::Vector3 displacement = (cursor_position_in_reference_frame - grab_point_in_reference_frame_);
609  Ogre::Vector3 displacement_on_plane = displacement - displacement.dotProduct(plane_normal) * plane_normal;
610 
611  // set position of parent to parent_position_at_mouse_down_ + displacement_on_plane.
612  parent_->setPose( parent_position_at_mouse_down_ + displacement_on_plane,
614 }
615 
618 void InteractiveMarkerControl::worldToScreen( const Ogre::Vector3& pos_rel_reference,
619  const Ogre::Viewport* viewport,
620  Ogre::Vector2& screen_pos )
621 {
622  Ogre::Vector3 world_pos = reference_node_->convertLocalToWorldPosition( pos_rel_reference );
623 
624  const Ogre::Camera* cam = viewport->getCamera();
625  Ogre::Vector3 homogeneous_screen_position = cam->getProjectionMatrix() * (cam->getViewMatrix() * world_pos);
626 
627  double half_width = viewport->getActualWidth() / 2.0;
628  double half_height = viewport->getActualHeight() / 2.0;
629 
630  screen_pos.x = half_width + (half_width * homogeneous_screen_position.x) - .5;
631  screen_pos.y = half_height + (half_height * -homogeneous_screen_position.y) - .5;
632 }
633 
637 bool InteractiveMarkerControl::findClosestPoint( const Ogre::Ray& target_ray,
638  const Ogre::Ray& mouse_ray,
639  Ogre::Vector3& closest_point )
640 {
641  // Find the closest point on target_ray to any point on mouse_ray.
642  //
643  // Math taken from http://paulbourke.net/geometry/lineline3d/
644  // line P1->P2 is target_ray
645  // line P3->P4 is mouse_ray
646 
647  Ogre::Vector3 v13 = target_ray.getOrigin() - mouse_ray.getOrigin();
648  Ogre::Vector3 v43 = mouse_ray.getDirection();
649  Ogre::Vector3 v21 = target_ray.getDirection();
650  double d1343 = v13.dotProduct( v43 );
651  double d4321 = v43.dotProduct( v21 );
652  double d1321 = v13.dotProduct( v21 );
653  double d4343 = v43.dotProduct( v43 );
654  double d2121 = v21.dotProduct( v21 );
655 
656  double denom = d2121 * d4343 - d4321 * d4321;
657  if( fabs( denom ) <= Ogre::Matrix3::EPSILON )
658  {
659  return false;
660  }
661  double numer = d1343 * d4321 - d1321 * d4343;
662 
663  double mua = numer / denom;
664  closest_point = target_ray.getPoint( mua );
665  return true;
666 }
667 
668 void InteractiveMarkerControl::moveAxis( const Ogre::Ray& mouse_ray, const ViewportMouseEvent& event )
669 {
670  // compute control-axis ray based on grab_point_, etc.
671  Ogre::Ray control_ray;
672  control_ray.setOrigin( grab_point_in_reference_frame_ );
673  control_ray.setDirection( control_frame_node_->getOrientation() * control_orientation_.xAxis() );
674 
675  // project control-axis ray onto screen.
676  Ogre::Vector2 control_ray_screen_start, control_ray_screen_end;
677  worldToScreen( control_ray.getOrigin(), event.viewport, control_ray_screen_start );
678  worldToScreen( control_ray.getPoint( 1 ), event.viewport, control_ray_screen_end );
679 
680  Ogre::Vector2 mouse_point( event.x, event.y );
681 
682  // Find closest point on projected ray to mouse point
683  // Math: if P is the start of the ray, v is the direction vector of
684  // the ray (not normalized), and X is the test point, then the
685  // closest point on the line to X is given by:
686  //
687  // (X-P).v
688  // P + v * -------
689  // v.v
690  // where "." is the dot product.
691  Ogre::Vector2 control_ray_screen_dir = control_ray_screen_end - control_ray_screen_start;
692  double denominator = control_ray_screen_dir.dotProduct( control_ray_screen_dir );
693  if( fabs( denominator ) > Ogre::Matrix3::EPSILON ) // If the control ray is not straight in line with the view.
694  {
695  double factor =
696  ( mouse_point - control_ray_screen_start ).dotProduct( control_ray_screen_dir ) / denominator;
697 
698  Ogre::Vector2 closest_screen_point = control_ray_screen_start + control_ray_screen_dir * factor;
699 
700  // make a new "mouse ray" for the point on the projected ray
701  Ogre::Ray new_mouse_ray = getMouseRayInReferenceFrame( event, closest_screen_point.x, closest_screen_point.y );
702 
703  // find closest point on control-axis ray to new mouse ray (should intersect actually)
704  Ogre::Vector3 closest_point;
705  if( findClosestPoint( control_ray, new_mouse_ray, closest_point ))
706  {
707  // set position of parent to closest_point - grab_point_ + parent_position_at_mouse_down_.
710  }
711  }
712 }
713 
714 void InteractiveMarkerControl::moveAxis( const Ogre::Vector3& cursor_position_in_reference_frame )
715 {
716  Ogre::Vector3 control_unit_direction = (control_frame_node_->getOrientation() * control_orientation_.xAxis());
717  Ogre::Vector3 displacement_along_axis = (cursor_position_in_reference_frame - grab_point_in_reference_frame_).dotProduct(control_unit_direction) * control_unit_direction;
718 
719  // set position of parent to closest_point - grab_point_ + parent_position_at_mouse_down_.
720  parent_->setPose( parent_position_at_mouse_down_ + displacement_along_axis,
722 
723 }
724 
725 void InteractiveMarkerControl::moveRotate( Ogre::Ray &mouse_ray )
726 {
727  if( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
729  {
731  }
732 
733  Ogre::Vector3 new_drag_rel_ref;
734  Ogre::Vector2 intersection_2d;
735  float ray_t;
736 
737  // get rotation axis rel ref (constant for entire drag)
738  // - rotation_axis_
739 
740  // get current rotation center rel ref
741  // - compute rotation center rel control frame at mouse-down (constant for entire drag)
742  // - current rotation center rel ref = current control frame * above
743  Ogre::Matrix4 control_rel_ref;
744  control_rel_ref.makeTransform( control_frame_node_->getPosition(),
745  Ogre::Vector3::UNIT_SCALE,
746  control_frame_node_->getOrientation() );
747  Ogre::Vector3 rotation_center = control_rel_ref * rotation_center_rel_control_;
748 
749  // get previous 3D drag point rel ref
750  // - compute grab point rel control frame at mouse-down (constant for entire drag)
751  // - prev_drag_rel_ref = current control frame + above
752  Ogre::Vector3 prev_drag_rel_ref = control_rel_ref * grab_point_rel_control_;
753 
754  // get new 3D drag point rel ref (this is "intersection_3d" in rotate().)
755  // - intersectSomeYzPlane( mouse_ray, rotation_center, control_frame_orientation )
756  if( intersectSomeYzPlane( mouse_ray, rotation_center, control_frame_node_->getOrientation(),
757  new_drag_rel_ref, intersection_2d, ray_t ))
758  {
759  // compute rotation angle from old drag point to new.
760  // - prev_rel_center = prev_drag_rel_ref - rotation_center
761  // - new_rel_center = new_drag_rel_ref - rotation_center
762  // - rotation_change = prev_rel_center.getRotationTo( new_rel_center, rotation_axis )
763  // - get Radians of angle change
764  // - rotation_ += angle_change
765  // - parent_->rotate(rotation_change)
766  Ogre::Vector3 prev_rel_center = prev_drag_rel_ref - rotation_center;
767  Ogre::Vector3 new_rel_center = new_drag_rel_ref - rotation_center;
768  if( new_rel_center.length() > Ogre::Matrix3::EPSILON )
769  {
770  Ogre::Quaternion rotation_change = prev_rel_center.getRotationTo( new_rel_center, rotation_axis_ );
771  Ogre::Radian rot;
772  Ogre::Vector3 axis;
773  rotation_change.ToAngleAxis( rot, axis );
774  // Quaternion::ToAngleAxis() always gives a positive angle. The
775  // axis it emits (in this case) will either be equal to
776  // rotation_axis or will be the negative of it. Doing the
777  // dot-product then gives either 1.0 or -1.0, which is just what
778  // we need to get the sign for our angle.
779  Ogre::Radian angle_change = rot * axis.dotProduct( rotation_axis_ );
780  rotation_ += angle_change;
781  parent_->rotate( rotation_change, name_ );
782 
783  // compute translation from rotated old drag point to new drag point.
784  // - pos_change = new_rel_center * (1.0 - prev_rel_center.length() / new_rel_center.length())
785  // - parent_->translate(pos_change)
786  parent_->translate( new_rel_center * (1.0 - prev_rel_center.length() / new_rel_center.length()), name_ );
787  }
788  }
789 }
790 
791 void InteractiveMarkerControl::moveRotate( const Ogre::Vector3& cursor_position_in_reference_frame, bool lock_axis )
792 {
793  if( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
795  {
797  }
798 
799  // get rotation axis rel ref (constant for entire drag)
800  // - rotation_axis_
801 
802  // get current rotation center rel ref
803  // - compute rotation center rel control frame at mouse-down (constant for entire drag)
804  // - current rotation center rel ref = current control frame * above
805  Ogre::Matrix4 control_rel_ref;
806  control_rel_ref.makeTransform( control_frame_node_->getPosition(),
807  Ogre::Vector3::UNIT_SCALE,
808  control_frame_node_->getOrientation() );
809  Ogre::Vector3 rotation_center = control_rel_ref * rotation_center_rel_control_;
810 
811  // get previous 3D drag point rel ref
812  // - compute grab point rel control frame at mouse-down (constant for entire drag)
813  // - prev_drag_rel_ref = current control frame + above
814  Ogre::Vector3 prev_drag_rel_ref = control_rel_ref * grab_point_rel_control_;
815 
816 
817  Ogre::Vector3 new_drag_rel_ref = cursor_position_in_reference_frame;
818  if (lock_axis)
819  {
820  Ogre::Vector3 plane_normal = (control_frame_node_->getOrientation() * control_orientation_.xAxis());
821  Ogre::Vector3 perpendicular_offset = (new_drag_rel_ref - prev_drag_rel_ref)
822  .dotProduct(plane_normal)*plane_normal;
823  new_drag_rel_ref -= perpendicular_offset;
824  }
825 
826  //Ogre::Vector3 new_drag_rel_ref = cursor_position_in_reference_frame;
827  // compute rotation angle from old drag point to new.
828  // - prev_rel_center = prev_drag_rel_ref - rotation_center
829  // - new_rel_center = new_drag_rel_ref - rotation_center
830  // - rotation_change = prev_rel_center.getRotationTo( new_rel_center, rotation_axis )
831  // - get Radians of angle change
832  // - rotation_ += angle_change
833  // - parent_->rotate(rotation_change)
834  Ogre::Vector3 prev_rel_center = prev_drag_rel_ref - rotation_center;
835  Ogre::Vector3 new_rel_center = new_drag_rel_ref - rotation_center;
836  if( new_rel_center.length() > Ogre::Matrix3::EPSILON )
837  {
838  Ogre::Quaternion rotation_change = prev_rel_center.getRotationTo( new_rel_center, rotation_axis_ );
839  Ogre::Radian rot;
840  Ogre::Vector3 axis;
841  rotation_change.ToAngleAxis( rot, axis );
842  // Quaternion::ToAngleAxis() always gives a positive angle. The
843  // axis it emits (in this case) will either be equal to
844  // rotation_axis or will be the negative of it. Doing the
845  // dot-product then gives either 1.0 or -1.0, which is just what
846  // we need to get the sign for our angle.
847  Ogre::Radian angle_change = rot * axis.dotProduct( rotation_axis_ );
848  rotation_ += angle_change;
849  parent_->rotate( rotation_change, name_ );
850 
851  // compute translation from rotated old drag point to new drag point.
852  // - pos_change = new_rel_center * (1.0 - prev_rel_center.length() / new_rel_center.length())
853  // - parent_->translate(pos_change)
854  parent_->translate( new_rel_center * (1.0 - prev_rel_center.length() / new_rel_center.length()), name_ );
855  }
856 }
857 
858 void InteractiveMarkerControl::move3D( const Ogre::Vector3& cursor_position_in_reference_frame,
859  const Ogre::Quaternion& cursor_orientation_in_reference_frame )
860 {
861  if( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
863  {
865  }
866 
867  //parent_to_cursor_in_cursor_frame_at_grab_ = cursor_3D_orientation.Inverse()*(cursor_3D_pos - parent_->getPosition());
868  //rotation_cursor_to_parent_at_grab_ = cursor_3D_orientation.Inverse()*parent->getOrientation();
869 
870 
871  Ogre::Vector3 world_to_cursor_in_world_frame = reference_node_->convertLocalToWorldPosition(cursor_position_in_reference_frame);
872  Ogre::Quaternion rotation_world_to_cursor = reference_node_->convertLocalToWorldOrientation(cursor_orientation_in_reference_frame);
873 
874  //Ogre::Vector3 marker_to_cursor_in_cursor_frame = orientation_world_to_cursor.Inverse()*reference_node_->getOrientation()*grab_point_in_reference_frame_;
875 
876  Ogre::Vector3 world_to_cursor_in_cursor_frame = rotation_world_to_cursor.Inverse()*world_to_cursor_in_world_frame;
877  Ogre::Vector3 world_to_marker_in_world_frame = rotation_world_to_cursor*(world_to_cursor_in_cursor_frame - parent_to_cursor_in_cursor_frame_at_grab_);
878  Ogre::Vector3 marker_position_in_reference_frame = reference_node_->convertWorldToLocalPosition(world_to_marker_in_world_frame);
879  //Ogre::Quaternion marker_orientation_in_reference_frame = reference_node_->convertWorldToLocalOrientation(rotation_world_to_cursor*rotation_cursor_to_parent_at_grab_);
880 
881  parent_->setPose( marker_position_in_reference_frame,
883 }
884 
885 void InteractiveMarkerControl::rotate3D( const Ogre::Vector3& cursor_position_in_reference_frame,
886  const Ogre::Quaternion& cursor_orientation_in_reference_frame )
887 {
888  if( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
890  {
892  }
893 
894  //parent_to_cursor_in_cursor_frame_at_grab_ = cursor_3D_orientation.Inverse()*(cursor_3D_pos - parent_->getPosition());
895  //rotation_cursor_to_parent_at_grab_ = cursor_3D_orientation.Inverse()*parent->getOrientation();
896 
897 
898  Ogre::Vector3 world_to_cursor_in_world_frame = reference_node_->convertLocalToWorldPosition(cursor_position_in_reference_frame);
899  Ogre::Quaternion rotation_world_to_cursor = reference_node_->convertLocalToWorldOrientation(cursor_orientation_in_reference_frame);
900 
901  //Ogre::Vector3 marker_to_cursor_in_cursor_frame = orientation_world_to_cursor.Inverse()*reference_node_->getOrientation()*grab_point_in_reference_frame_;
902 
903  Ogre::Vector3 world_to_cursor_in_cursor_frame = rotation_world_to_cursor.Inverse()*world_to_cursor_in_world_frame;
904  Ogre::Vector3 world_to_marker_in_world_frame = rotation_world_to_cursor*(world_to_cursor_in_cursor_frame - parent_to_cursor_in_cursor_frame_at_grab_);
905  Ogre::Vector3 marker_position_in_reference_frame = reference_node_->convertWorldToLocalPosition(world_to_marker_in_world_frame);
906  Ogre::Quaternion marker_orientation_in_reference_frame = reference_node_->convertWorldToLocalOrientation(rotation_world_to_cursor*rotation_cursor_to_parent_at_grab_);
907 
909  marker_orientation_in_reference_frame, name_ );
910 }
911 
912 
913 void InteractiveMarkerControl::moveRotate3D( const Ogre::Vector3& cursor_position_in_reference_frame,
914  const Ogre::Quaternion& cursor_orientation_in_reference_frame )
915 {
916  if( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
918  {
920  }
921 
922  //parent_to_cursor_in_cursor_frame_at_grab_ = cursor_3D_orientation.Inverse()*(cursor_3D_pos - parent_->getPosition());
923  //rotation_cursor_to_parent_at_grab_ = cursor_3D_orientation.Inverse()*parent->getOrientation();
924 
925 
926  Ogre::Vector3 world_to_cursor_in_world_frame = reference_node_->convertLocalToWorldPosition(cursor_position_in_reference_frame);
927  Ogre::Quaternion rotation_world_to_cursor = reference_node_->convertLocalToWorldOrientation(cursor_orientation_in_reference_frame);
928 
929  //Ogre::Vector3 marker_to_cursor_in_cursor_frame = orientation_world_to_cursor.Inverse()*reference_node_->getOrientation()*grab_point_in_reference_frame_;
930 
931  Ogre::Vector3 world_to_cursor_in_cursor_frame = rotation_world_to_cursor.Inverse()*world_to_cursor_in_world_frame;
932  Ogre::Vector3 world_to_marker_in_world_frame = rotation_world_to_cursor*(world_to_cursor_in_cursor_frame - parent_to_cursor_in_cursor_frame_at_grab_);
933  Ogre::Vector3 marker_position_in_reference_frame = reference_node_->convertWorldToLocalPosition(world_to_marker_in_world_frame);
934  Ogre::Quaternion marker_orientation_in_reference_frame = reference_node_->convertWorldToLocalOrientation(rotation_world_to_cursor*rotation_cursor_to_parent_at_grab_);
935 
936  parent_->setPose( marker_position_in_reference_frame,
937  marker_orientation_in_reference_frame, name_ );
938 }
939 
944 }
945 
947 {
948  std::set<Ogre::Pass*>::iterator it;
949  for (it = highlight_passes_.begin(); it != highlight_passes_.end(); it++)
950  {
951  (*it)->setAmbient(a,a,a);
952  }
953 
954  std::vector<PointsMarkerPtr>::iterator pm_it;
955  for( pm_it = points_markers_.begin(); pm_it != points_markers_.end(); pm_it++ )
956  {
957  (*pm_it)->setHighlightColor( a, a, a );
958  }
959 }
960 
962 {
963  dragging_in_place_event_ = event;
964  dragging_in_place_event_.type = QEvent::MouseMove;
965 }
966 
968 {
969  // aleeper: Why is this check here? What happens when this mouse_dragging_ check isn't done at all?
970  // Or as an alternative to this minor API change, we could just manually set mouse_dragging_
971  // to true before calling this function from the 3D cursor code.
972  // BUT that would be a hack...
973  if ( mouse_dragging_ || force )
974  {
975  line_->setVisible(false);
976  mouse_dragging_ = false;
979  }
980 }
981 
982 // Almost a wholesale copy of the mouse event code... can these be combined?
984  const Ogre::Vector3& cursor_3D_pos,
985  const Ogre::Quaternion& cursor_3D_orientation)
986 {
987  // change dragging state
988  switch( interaction_mode_ )
989  {
990  case visualization_msgs::InteractiveMarkerControl::BUTTON:
991  if( event.leftUp() )
992  {
993  Ogre::Vector3 point_rel_world = cursor_3D_pos;
994  bool got_3D_point = true;
995 
996  visualization_msgs::InteractiveMarkerFeedback feedback;
997  feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK;
998  feedback.control_name = name_;
999  feedback.marker_name = parent_->getName();
1000  parent_->publishFeedback( feedback, got_3D_point, point_rel_world );
1001  }
1002  break;
1003 
1004  case visualization_msgs::InteractiveMarkerControl::MENU:
1005  if( event.leftUp() )
1006  {
1007  // Save the 3D mouse point to send with the menu feedback, if any.
1008  Ogre::Vector3 three_d_point = cursor_3D_pos;
1009  bool valid_point = true;
1010  Ogre::Vector2 mouse_pos = project3DPointToViewportXY(event.viewport, three_d_point);
1011  QCursor::setPos(event.panel->mapToGlobal(QPoint(mouse_pos.x, mouse_pos.y)));
1012  parent_->showMenu( event, name_, three_d_point, valid_point );
1013  }
1014  break;
1015 
1016  case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1017  case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1018  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1019  case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1020  case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1021  case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1022  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1023  if( event.leftDown() )
1024  {
1026  drag_viewport_ = event.viewport;
1027 
1028  //recordDraggingInPlaceEvent( event );
1029  grab_point_in_reference_frame_ = reference_node_->convertWorldToLocalPosition( cursor_3D_pos );
1030  grab_orientation_in_reference_frame_ = reference_node_->convertWorldToLocalOrientation( cursor_3D_orientation );
1031 
1032  parent_to_cursor_in_cursor_frame_at_grab_ = cursor_3D_orientation.Inverse()*(cursor_3D_pos - reference_node_->convertLocalToWorldPosition(parent_->getPosition()));
1033  rotation_cursor_to_parent_at_grab_ = cursor_3D_orientation.Inverse()*reference_node_->convertLocalToWorldOrientation(parent_->getOrientation());
1034 
1037 
1038  if( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
1039  drag_viewport_ )
1040  {
1042  }
1045 
1046  rotation_axis_ = control_frame_node_->getOrientation() * control_orientation_.xAxis();
1047 
1048  // Find rotation_center = 3D point closest to grab_point_ which is
1049  // on the rotation axis, relative to the reference frame.
1050  Ogre::Vector3 rotation_center_rel_ref = closestPointOnLineToPoint( parent_->getPosition(),
1053  Ogre::Matrix4 reference_rel_control_frame;
1054  reference_rel_control_frame.makeInverseTransform( control_frame_node_->getPosition(),
1055  Ogre::Vector3::UNIT_SCALE,
1056  control_frame_node_->getOrientation() );
1057  rotation_center_rel_control_ = reference_rel_control_frame * rotation_center_rel_ref;
1058  grab_point_rel_control_ = reference_rel_control_frame * grab_point_in_reference_frame_;
1059  }
1060  if( event.leftUp() )
1061  {
1062  // Alternatively, could just manually set mouse_dragging_ to true.
1063  stopDragging( true );
1064  }
1065  break;
1066 
1067  default:
1068  break;
1069  }
1070 
1071  if( event.leftDown() )
1072  {
1074  }
1075  else if( event.leftUp() )
1076  {
1078  }
1079 
1080  if (!parent_->handle3DCursorEvent(event, cursor_3D_pos, cursor_3D_orientation, name_))
1081  {
1082  if( event.type == QEvent::MouseMove && event.left()) // && mouse_dragging_)
1083  {
1084  Ogre::Vector3 cursor_position_in_reference_frame = reference_node_->convertWorldToLocalPosition( cursor_3D_pos );
1085  Ogre::Quaternion cursor_orientation_in_reference_frame = reference_node_->convertWorldToLocalOrientation( cursor_3D_orientation );
1086 
1087  switch (interaction_mode_)
1088  {
1089  case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1090  rotate( cursor_position_in_reference_frame );
1091  break;
1092 
1093  case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1094  moveAxis( cursor_position_in_reference_frame );
1095  break;
1096 
1097  case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1098  movePlane( cursor_position_in_reference_frame );
1099  break;
1100 
1101  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1102  moveRotate( cursor_position_in_reference_frame, true );
1103  break;
1104 
1105  case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1106  move3D( cursor_position_in_reference_frame, cursor_orientation_in_reference_frame );
1107  break;
1108 
1109  case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1110  rotate3D( cursor_position_in_reference_frame, cursor_orientation_in_reference_frame );
1111  break;
1112 
1113  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1114  moveRotate3D( cursor_position_in_reference_frame, cursor_orientation_in_reference_frame );
1115  break;
1116 
1117  default:
1118  break;
1119  }
1120  }
1121  }
1122 }
1123 
1125 {
1126  // REMOVE ME ROS_INFO("Mouse event!");
1127  // * check if this is just a receive/lost focus event
1128  // * try to hand over the mouse event to the parent interactive marker
1129  // * otherwise, execute mouse move handling
1130 
1131  // handle receive/lose focus
1132  if( event.type == QEvent::FocusIn )
1133  {
1134  has_focus_ = true;
1135  std::set<Ogre::Pass*>::iterator it;
1138  }
1139  else if( event.type == QEvent::FocusOut )
1140  {
1141  stopDragging();
1142  has_focus_ = false;
1143  setHighlight(0.0);
1144  return;
1145  }
1146 
1147  mouse_down_ = event.left() || event.middle() || event.right();
1148 
1149  // change dragging state
1150  switch( interaction_mode_ )
1151  {
1152  case visualization_msgs::InteractiveMarkerControl::BUTTON:
1153  if( event.leftUp() )
1154  {
1155  Ogre::Vector3 point_rel_world;
1156  bool got_3D_point = context_->getSelectionManager()->get3DPoint( event.viewport, event.x, event.y, point_rel_world );
1157 
1158  visualization_msgs::InteractiveMarkerFeedback feedback;
1159  feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK;
1160  feedback.control_name = name_;
1161  feedback.marker_name = parent_->getName();
1162  parent_->publishFeedback( feedback, got_3D_point, point_rel_world );
1163  }
1164  break;
1165 
1166  case visualization_msgs::InteractiveMarkerControl::MENU:
1167  if( event.leftUp() )
1168  {
1169  Ogre::Vector3 point_rel_world;
1170  bool got_3D_point = context_->getSelectionManager()->get3DPoint( event.viewport, event.x, event.y, point_rel_world );
1171  parent_->showMenu( event, name_, point_rel_world, got_3D_point );
1172  }
1173  break;
1174 
1175  case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1176  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1177  case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1178  if ( event.leftDown() )
1179  beginMouseMovement( event,
1181  orientation_mode_ != visualization_msgs::InteractiveMarkerControl::VIEW_FACING);
1182  break;
1183 
1184  case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1185  if( event.leftDown() )
1186  beginMouseMovement( event, false);
1187  break;
1188 
1189  case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1190  case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1191  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1192  if ( event.leftDown() )
1193  {
1194  // aleeper: This line was causing badness
1195  //orientation_mode_ = visualization_msgs::InteractiveMarkerControl::VIEW_FACING;
1196  beginMouseMovement( event, false );
1197  }
1198  else if ( event.left() &&
1199  ((modifiers_at_drag_begin_ ^ event.modifiers) & (Qt::ShiftModifier | Qt::ControlModifier)) )
1200  {
1201  // modifier buttons changed. Restart the drag.
1202  beginRelativeMouseMotion( event );
1203  }
1204  break;
1205 
1206  default:
1207  break;
1208  }
1209 
1210  if (!parent_->handleMouseEvent(event, name_))
1211  {
1212  if( event.type == QEvent::MouseMove && event.left() && mouse_dragging_)
1213  {
1214  recordDraggingInPlaceEvent( event );
1215  handleMouseMovement( event );
1216  }
1217  else if( event.type == QEvent::Wheel && event.left() && mouse_dragging_)
1218  {
1219  handleMouseWheelMovement( event );
1220  }
1221  }
1222 
1223  if( event.leftDown() )
1224  {
1226  }
1227  else if( event.leftUp() )
1228  {
1230  stopDragging();
1231  }
1232 }
1233 
1235 {
1236  line_->setVisible(line_visible);
1237 
1239  mouse_dragging_ = true;
1240  drag_viewport_ = event.viewport;
1241 
1242  recordDraggingInPlaceEvent( event );
1243  Ogre::Vector3 grab_point_in_world_frame;
1244  if( ! context_->getSelectionManager()->get3DPoint( event.viewport, event.x, event.y, grab_point_in_world_frame ))
1245  {
1246  // If we couldn't get a 3D point for the grab, just use the
1247  // current relative position of the control frame.
1249  }
1250  else
1251  {
1252  // If we could get a 3D point for the grab, convert it from
1253  // the world frame to the reference frame (in case those are different).
1254  grab_point_in_reference_frame_ = reference_node_->convertWorldToLocalPosition(grab_point_in_world_frame);
1255  }
1258 
1259  QPoint absolute_mouse = QCursor::pos();
1260  mouse_relative_to_absolute_x_ = absolute_mouse.x() - event.x;
1261  mouse_relative_to_absolute_y_ = absolute_mouse.y() - event.y;
1262  beginRelativeMouseMotion( event );
1263 
1264  if( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING &&
1265  drag_viewport_ )
1266  {
1268  }
1271 
1272  rotation_axis_ = control_frame_node_->getOrientation() * control_orientation_.xAxis();
1273 
1274  // Find rotation_center = 3D point closest to grab_point_ which is
1275  // on the rotation axis, relative to the reference frame.
1276  Ogre::Vector3 rotation_center_rel_ref = closestPointOnLineToPoint( parent_->getPosition(),
1279  Ogre::Matrix4 reference_rel_control_frame;
1280  reference_rel_control_frame.makeInverseTransform( control_frame_node_->getPosition(),
1281  Ogre::Vector3::UNIT_SCALE,
1282  control_frame_node_->getOrientation() );
1283  rotation_center_rel_control_ = reference_rel_control_frame * rotation_center_rel_ref;
1284  grab_point_rel_control_ = reference_rel_control_frame * grab_point_in_reference_frame_;
1285 
1286 
1287  // find mouse_z_scale_
1288  static const double DEFAULT_MOUSE_Z_SCALE = 0.001; // default to 1mm per pixel
1289  mouse_z_scale_ = DEFAULT_MOUSE_Z_SCALE;
1290 
1291  Ogre::Ray mouse_ray = getMouseRayInReferenceFrame( event, event.x, event.y );
1292  Ogre::Ray mouse_ray_10 = getMouseRayInReferenceFrame( event, event.x, event.y + 10 );
1293 
1294  Ogre::Vector3 intersection_3d;
1295  Ogre::Vector3 intersection_3d_10;
1296  Ogre::Vector2 intersection_2d;
1297  float ray_t;
1298 
1299  if( intersectSomeYzPlane( mouse_ray,
1300  grab_point_in_reference_frame_,
1301  control_frame_node_->getOrientation(),
1302  intersection_3d,
1303  intersection_2d,
1304  ray_t ))
1305  {
1306  if( intersectSomeYzPlane( mouse_ray_10,
1307  grab_point_in_reference_frame_,
1308  control_frame_node_->getOrientation(),
1309  intersection_3d_10,
1310  intersection_2d,
1311  ray_t ))
1312  {
1313  mouse_z_scale_ = (intersection_3d_10 - intersection_3d).length() / 10.0;
1314  if (mouse_z_scale_ < std::numeric_limits<float>::min() * 100.0)
1315  mouse_z_scale_ = DEFAULT_MOUSE_Z_SCALE;
1316  }
1317  }
1318 }
1319 
1321 {
1322  Ogre::Ray mouse_ray = getMouseRayInReferenceFrame( event, event.x, event.y );
1323  Ogre::Ray last_mouse_ray = getMouseRayInReferenceFrame( event, event.last_x, event.last_y );
1324 
1325  bool do_rotation = false;
1326  switch (interaction_mode_)
1327  {
1328  case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS:
1329  moveAxis( mouse_ray, event );
1330  break;
1331 
1332  case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE:
1333  movePlane( mouse_ray );
1334  break;
1335 
1336  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE:
1337  moveRotate( mouse_ray );
1338  break;
1339 
1340  case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS:
1341  rotate( mouse_ray );
1342  break;
1343 
1344  case visualization_msgs::InteractiveMarkerControl::ROTATE_3D:
1345  do_rotation = true;
1346  // fall through
1347  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1348  if ( event.control() )
1349  do_rotation = true;
1350  // fall through
1351  case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1352  if ( do_rotation )
1353  {
1354  if (event.shift())
1355  rotateZRelative( event );
1356  else
1357  rotateXYRelative( event );
1358  }
1359  else
1360  {
1361  if (event.shift())
1362  moveZAxisRelative( event );
1363  else
1364  moveViewPlane( mouse_ray, event );
1365  }
1366  break;
1367 
1368  default:
1369  break;
1370  }
1371 }
1372 
1374 {
1375  switch (interaction_mode_)
1376  {
1377  case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D:
1378  case visualization_msgs::InteractiveMarkerControl::MOVE_3D:
1379  moveZAxisWheel( event );
1380  break;
1381 
1382  default:
1383  break;
1384  }
1385 }
1386 
1387 bool InteractiveMarkerControl::intersectYzPlane( const Ogre::Ray& mouse_ray,
1388  Ogre::Vector3& intersection_3d,
1389  Ogre::Vector2& intersection_2d,
1390  float &ray_t )
1391 {
1392  return intersectSomeYzPlane( mouse_ray,
1393  control_frame_node_->getPosition(),
1394  control_frame_node_->getOrientation(),
1395  intersection_3d, intersection_2d, ray_t );
1396 }
1397 
1398 bool InteractiveMarkerControl::intersectSomeYzPlane( const Ogre::Ray& mouse_ray,
1399  const Ogre::Vector3& point_on_plane,
1400  const Ogre::Quaternion& plane_orientation,
1401  Ogre::Vector3& intersection_3d,
1402  Ogre::Vector2& intersection_2d,
1403  float& ray_t )
1404 {
1405  Ogre::Vector3 normal = plane_orientation * control_orientation_.xAxis();
1406  Ogre::Vector3 axis_1 = plane_orientation * control_orientation_.yAxis();
1407  Ogre::Vector3 axis_2 = plane_orientation * control_orientation_.zAxis();
1408 
1409  Ogre::Plane plane(normal, point_on_plane);
1410 
1411  Ogre::Vector2 origin_2d(point_on_plane.dotProduct(axis_1), point_on_plane.dotProduct(axis_2));
1412 
1413  std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(plane);
1414  if (intersection.first)
1415  {
1416  intersection_3d = mouse_ray.getPoint(intersection.second);
1417  intersection_2d = Ogre::Vector2(intersection_3d.dotProduct(axis_1), intersection_3d.dotProduct(axis_2));
1418  intersection_2d -= origin_2d;
1419 
1420  ray_t = intersection.second;
1421  return true;
1422  }
1423 
1424  ray_t = 0;
1425  return false;
1426 }
1427 
1429 {
1430  S_MaterialPtr::iterator it;
1431 
1432  for (it = materials.begin(); it != materials.end(); it++)
1433  {
1434  Ogre::MaterialPtr material = *it;
1435  Ogre::Pass *original_pass = material->getTechnique(0)->getPass(0);
1436  Ogre::Pass *pass = material->getTechnique(0)->createPass();
1437 
1438  pass->setSceneBlending(Ogre::SBT_ADD);
1439  pass->setDepthWriteEnabled(false);
1440  pass->setDepthCheckEnabled(true);
1441  pass->setLightingEnabled(true);
1442  pass->setAmbient(0, 0, 0);
1443  pass->setDiffuse(0, 0, 0, 0);
1444  pass->setSpecular(0, 0, 0, 0);
1445  pass->setCullingMode(original_pass->getCullingMode());
1446 
1447  highlight_passes_.insert(pass);
1448  }
1449 }
1450 
1451 }
virtual void setStatus(const QString &message)=0
void translate(Ogre::Vector3 delta_position, const std::string &control_name)
#define NULL
Definition: global.h:37
virtual void handleMouseEvent(ViewportMouseEvent &event)
const Ogre::Quaternion & getOrientation()
QCursor makeIconCursor(QString url, bool fill_cache)
void rotate(Ogre::Quaternion delta_orientation, const std::string &control_name)
void handleMouseWheelMovement(ViewportMouseEvent &event)
void interactiveMarkerPoseChanged(Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation)
void beginMouseMovement(ViewportMouseEvent &event, bool line_visible)
void updateControlOrientationForViewFacing(Ogre::Viewport *v)
std::set< Ogre::Pass * > highlight_passes_
void addHighlightPass(S_MaterialPtr materials)
take all the materials, add a highlight pass and store a pointer to the pass for later use ...
void move3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
bool intersectYzPlane(const Ogre::Ray &mouse_ray, Ogre::Vector3 &intersection_3d, Ogre::Vector2 &intersection_2d, float &ray_t)
compute intersection between mouse ray and y-z plane given in local coordinates
void moveViewPlane(Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
virtual void handle3DCursorEvent(ViewportMouseEvent event, const Ogre::Vector3 &cursor_3D_pos, const Ogre::Quaternion &cursor_3D_orientation)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
#define NO_HIGHLIGHT_VALUE
#define HOVER_HIGHLIGHT_VALUE
InteractiveMarkerControl(DisplayContext *context, Ogre::SceneNode *reference_node, InteractiveMarker *parent)
Constructor.
virtual void preFindVisibleObjects(Ogre::SceneManager *source, Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v)
void makeMarkers(const visualization_msgs::InteractiveMarkerControl &message)
Create marker objects from the message and add them to the internal marker arrays.
Ogre::Vector3 closestPointOnLineToPoint(const Ogre::Vector3 &line_start, const Ogre::Vector3 &line_dir, const Ogre::Vector3 &test_point)
std::vector< PointsMarkerPtr > points_markers_
MarkerBase * createMarker(int marker_type, MarkerDisplay *owner, DisplayContext *context, Ogre::SceneNode *parent_node)
const Ogre::Vector3 & getPosition()
Ogre::Vector2 project3DPointToViewportXY(const Ogre::Viewport *view, const Ogre::Vector3 &pos)
Given a viewport and a 3D position in world coordinates, project that point into the view plane...
Definition: geometry.cpp:75
void publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback, bool mouse_point_valid=false, const Ogre::Vector3 &mouse_point_rel_world=Ogre::Vector3(0, 0, 0))
Pure-virtual base class for objects which give Display subclasses context in which to work...
const std::string & getName()
void recordDraggingInPlaceEvent(ViewportMouseEvent &event)
bool handle3DCursorEvent(ViewportMouseEvent &event, const Ogre::Vector3 &cursor_pos, const Ogre::Quaternion &cursor_rot, const std::string &control_name)
Ogre::Ray getMouseRayInReferenceFrame(const ViewportMouseEvent &event, int x, int y)
void beginRelativeMouseMotion(const ViewportMouseEvent &event)
void setHighlight(const ControlHighlight &hl)
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
QCursor getDefaultCursor(bool fill_cache)
void moveRotate3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
virtual SelectionManager * getSelectionManager() const =0
Return a pointer to the SelectionManager.
void showMenu(ViewportMouseEvent &event, const std::string &control_name, const Ogre::Vector3 &three_d_point, bool valid_point)
void rotate3D(const Ogre::Vector3 &cursor_position_in_reference_frame, const Ogre::Quaternion &cursor_orientation_in_reference_frame)
void processMessage(const visualization_msgs::InteractiveMarkerControl &message)
Set up or update the contents of this control to match the specification in the message.
bool findClosestPoint(const Ogre::Ray &target_ray, const Ogre::Ray &mouse_ray, Ogre::Vector3 &closest_point)
const std::string & getFixedFrame()
Return the current fixed frame name.
bool getRelativeMouseMotion(const ViewportMouseEvent &event, int &dx, int &dy)
void moveZAxisWheel(const ViewportMouseEvent &event)
std::vector< MarkerBasePtr > markers_
void worldToScreen(const Ogre::Vector3 &pos_rel_reference, const Ogre::Viewport *viewport, Ogre::Vector2 &screen_pos)
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
#define ACTIVE_HIGHLIGHT_VALUE
bool intersectSomeYzPlane(const Ogre::Ray &mouse_ray, const Ogre::Vector3 &point_in_plane, const Ogre::Quaternion &plane_orientation, Ogre::Vector3 &intersection_3d, Ogre::Vector2 &intersection_2d, float &ray_t)
compute intersection between mouse ray and a y-z plane.
void moveZAxisRelative(const ViewportMouseEvent &event)
void setPose(Ogre::Vector3 position, Ogre::Quaternion orientation, const std::string &control_name)
void rotateXYRelative(const ViewportMouseEvent &event)
void handleMouseMovement(ViewportMouseEvent &event)
void moveAxis(const Ogre::Ray &mouse_ray, const ViewportMouseEvent &event)
std::set< Ogre::MaterialPtr > S_MaterialPtr
Definition: marker_base.h:57
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
bool handleMouseEvent(ViewportMouseEvent &event, const std::string &control_name)
bool get3DPoint(Ogre::Viewport *viewport, const int x, const int y, Ogre::Vector3 &result_point)
#define ROS_ERROR(...)
void rotateZRelative(const ViewportMouseEvent &event)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51