$search
00001 /* 00002 * Copyright (c) 2011, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #include "interactive_marker_control.h" 00031 00032 #include "rviz/default_plugin/markers/marker_base.h" 00033 #include "rviz/visualization_manager.h" 00034 #include "rviz/selection/selection_manager.h" 00035 #include "rviz/render_panel.h" 00036 #include "interactive_marker.h" 00037 00038 #include <OGRE/OgreViewport.h> 00039 #include <OGRE/OgreCamera.h> 00040 #include <OGRE/OgreSceneNode.h> 00041 #include <OGRE/OgreSceneManager.h> 00042 #include <OGRE/OgrePass.h> 00043 #include <OGRE/OgreMaterial.h> 00044 #include <OGRE/OgreEntity.h> 00045 #include <OGRE/OgreSubEntity.h> 00046 00047 #include "markers/shape_marker.h" 00048 #include "markers/arrow_marker.h" 00049 #include "markers/line_list_marker.h" 00050 #include "markers/line_strip_marker.h" 00051 #include "markers/points_marker.h" 00052 #include "markers/text_view_facing_marker.h" 00053 #include "markers/mesh_resource_marker.h" 00054 #include "markers/triangle_list_marker.h" 00055 00056 namespace rviz 00057 { 00058 00059 InteractiveMarkerControl::InteractiveMarkerControl( VisualizationManager* vis_manager, 00060 const visualization_msgs::InteractiveMarkerControl &message, 00061 Ogre::SceneNode *reference_node, InteractiveMarker *parent ) 00062 : dragging_(false) 00063 , vis_manager_(vis_manager) 00064 , reference_node_(reference_node) 00065 , control_frame_node_(reference_node_->createChildSceneNode()) 00066 , markers_node_(reference_node_->createChildSceneNode()) 00067 , parent_(parent) 00068 , rotation_(0) 00069 , grab_point_(0,0,0) 00070 , interaction_enabled_(false) 00071 , visible_(true) 00072 { 00073 name_ = message.name; 00074 interaction_mode_ = message.interaction_mode; 00075 always_visible_ = message.always_visible; 00076 00077 orientation_mode_ = message.orientation_mode; 00078 00079 description_ = message.description; 00080 00081 control_orientation_ = Ogre::Quaternion(message.orientation.w, 00082 message.orientation.x, message.orientation.y, message.orientation.z); 00083 control_orientation_.normalise(); 00084 00085 if (message.orientation_mode == visualization_msgs::InteractiveMarkerControl::VIEW_FACING) 00086 { 00087 vis_manager->getSceneManager()->addListener(this); 00088 } 00089 00090 independent_marker_orientation_ = message.independent_marker_orientation; 00091 00092 //initially, the pose of this marker's node and the interactive marker are identical, but that may change 00093 control_frame_node_->setPosition(parent_->getPosition()); 00094 markers_node_->setPosition(parent_->getPosition()); 00095 00096 if ( orientation_mode_ == visualization_msgs::InteractiveMarkerControl::INHERIT ) 00097 { 00098 control_frame_node_->setOrientation(parent_->getOrientation()); 00099 markers_node_->setOrientation(parent_->getOrientation()); 00100 intitial_orientation_ = parent->getOrientation(); 00101 } 00102 00103 for (unsigned i = 0; i < message.markers.size(); i++) 00104 { 00105 MarkerBasePtr marker; 00106 00107 // create a marker with the given type 00108 switch (message.markers[i].type) 00109 { 00110 case visualization_msgs::Marker::CUBE: 00111 case visualization_msgs::Marker::CYLINDER: 00112 case visualization_msgs::Marker::SPHERE: 00113 { 00114 marker.reset(new ShapeMarker(0, vis_manager_, markers_node_)); 00115 } 00116 break; 00117 00118 case visualization_msgs::Marker::ARROW: 00119 { 00120 marker.reset(new ArrowMarker(0, vis_manager_, markers_node_)); 00121 } 00122 break; 00123 00124 case visualization_msgs::Marker::LINE_STRIP: 00125 { 00126 marker.reset(new LineStripMarker(0, vis_manager_, markers_node_)); 00127 } 00128 break; 00129 case visualization_msgs::Marker::LINE_LIST: 00130 { 00131 marker.reset(new LineListMarker(0, vis_manager_, markers_node_)); 00132 } 00133 break; 00134 case visualization_msgs::Marker::SPHERE_LIST: 00135 case visualization_msgs::Marker::CUBE_LIST: 00136 case visualization_msgs::Marker::POINTS: 00137 { 00138 PointsMarkerPtr points_marker; 00139 points_marker.reset(new PointsMarker(0, vis_manager_, markers_node_)); 00140 points_markers_.push_back( points_marker ); 00141 marker = points_marker; 00142 } 00143 break; 00144 case visualization_msgs::Marker::TEXT_VIEW_FACING: 00145 { 00146 marker.reset(new TextViewFacingMarker(0, vis_manager_, markers_node_)); 00147 } 00148 break; 00149 case visualization_msgs::Marker::MESH_RESOURCE: 00150 { 00151 marker.reset(new MeshResourceMarker(0, vis_manager_, markers_node_)); 00152 } 00153 break; 00154 00155 case visualization_msgs::Marker::TRIANGLE_LIST: 00156 { 00157 marker.reset(new TriangleListMarker(0, vis_manager_, markers_node_)); 00158 } 00159 break; 00160 default: 00161 ROS_ERROR( "Unknown marker type: %d", message.markers[i].type ); 00162 } 00163 00164 marker->setMessage(message.markers[i]); 00165 marker->setControl(this); 00166 00167 addHighlightPass(marker->getMaterials()); 00168 00169 // the marker will set it's position relative to the fixed frame, 00170 // but we have attached it our own scene node, 00171 // so we will have to correct for that 00172 marker->setPosition( markers_node_->convertWorldToLocalPosition( marker->getPosition() ) ); 00173 marker->setOrientation( markers_node_->convertWorldToLocalOrientation( marker->getOrientation() ) ); 00174 00175 markers_.push_back(marker); 00176 } 00177 00178 enableInteraction(vis_manager_->getSelectionManager()->getInteractionEnabled()); 00179 } 00180 00181 InteractiveMarkerControl::~InteractiveMarkerControl() 00182 { 00183 vis_manager_->getSceneManager()->destroySceneNode(control_frame_node_); 00184 vis_manager_->getSceneManager()->destroySceneNode(markers_node_); 00185 00186 if (orientation_mode_ == visualization_msgs::InteractiveMarkerControl::VIEW_FACING) 00187 { 00188 vis_manager_->getSceneManager()->removeListener(this); 00189 } 00190 } 00191 00192 // This is an Ogre::SceneManager::Listener function, and is configured 00193 // to be called only if this is a VIEW_FACING control. 00194 void InteractiveMarkerControl::preFindVisibleObjects( 00195 Ogre::SceneManager *source, 00196 Ogre::SceneManager::IlluminationRenderStage irs, Ogre::Viewport *v ) 00197 { 00198 Ogre::Quaternion x_view_facing_rotation = 00199 control_orientation_.xAxis().getRotationTo( v->getCamera()->getDerivedDirection()); 00200 00201 // rotate so z axis is up 00202 Ogre::Vector3 z_axis_2 = x_view_facing_rotation * control_orientation_.zAxis(); 00203 Ogre::Quaternion align_yz_rotation = z_axis_2.getRotationTo(v->getCamera()->getDerivedUp()); 00204 00205 // rotate 00206 Ogre::Quaternion rotate_around_x = Ogre::Quaternion(rotation_, v->getCamera()->getDerivedDirection()); 00207 00208 Ogre::Quaternion rotation = reference_node_->convertWorldToLocalOrientation( 00209 rotate_around_x * align_yz_rotation * x_view_facing_rotation ); 00210 00211 control_frame_node_->setOrientation( rotation ); 00212 00213 if ( !independent_marker_orientation_ ) 00214 { 00215 markers_node_->setOrientation( rotation ); 00216 // we need to refresh the node manually, since the scene manager will only do this one frame 00217 // later otherwise 00218 markers_node_->_update(true, false); 00219 } 00220 } 00221 00222 void InteractiveMarkerControl::setVisible( bool visible ) 00223 { 00224 visible_ = visible; 00225 00226 if (always_visible_) 00227 { 00228 markers_node_->setVisible(visible_); 00229 } else 00230 { 00231 markers_node_->setVisible(interaction_enabled_ && visible_); 00232 } 00233 } 00234 00235 void InteractiveMarkerControl::update() 00236 { 00237 if( dragging_ ) 00238 { 00239 handleMouseMovement( dragging_in_place_event_ ); 00240 } 00241 } 00242 00243 void InteractiveMarkerControl::enableInteraction( bool enable ) 00244 { 00245 interaction_enabled_ = enable; 00246 setVisible(visible_); 00247 if (!enable) 00248 { 00249 setHighlight(0.0); 00250 } 00251 } 00252 00253 void InteractiveMarkerControl::interactiveMarkerPoseChanged( 00254 Ogre::Vector3 int_marker_position, Ogre::Quaternion int_marker_orientation ) 00255 { 00256 control_frame_node_->setPosition(int_marker_position); 00257 markers_node_->setPosition(int_marker_position); 00258 00259 switch (orientation_mode_) 00260 { 00261 case visualization_msgs::InteractiveMarkerControl::INHERIT: 00262 control_frame_node_->setOrientation(int_marker_orientation); 00263 markers_node_->setOrientation(control_frame_node_->getOrientation()); 00264 break; 00265 00266 case visualization_msgs::InteractiveMarkerControl::FIXED: 00267 { 00268 control_frame_node_->setOrientation(intitial_orientation_ * Ogre::Quaternion( 00269 rotation_, control_orientation_.xAxis())); 00270 markers_node_->setOrientation(control_frame_node_->getOrientation()); 00271 break; 00272 } 00273 00274 case visualization_msgs::InteractiveMarkerControl::VIEW_FACING: 00275 if ( independent_marker_orientation_ ) 00276 { 00277 markers_node_->setOrientation(int_marker_orientation); 00278 } 00279 break; 00280 00281 default: 00282 break; 00283 } 00284 } 00285 00286 Ogre::Vector3 InteractiveMarkerControl::closestPointOnLineToPoint( const Ogre::Vector3& line_start, 00287 const Ogre::Vector3& line_dir, 00288 const Ogre::Vector3& test_point ) 00289 { 00290 // Find closest point on projected ray to mouse point 00291 // Math: if P is the start of the ray, v is the direction vector of 00292 // the ray (not normalized), and X is the test point, then the 00293 // closest point on the line to X is given by: 00294 // 00295 // (X-P).v 00296 // P + v * ------- 00297 // v.v 00298 // where "." is the dot product. 00299 double factor = ( test_point - line_start ).dotProduct( line_dir ) / line_dir.dotProduct( line_dir ); 00300 Ogre::Vector3 closest_point = line_start + line_dir * factor; 00301 return closest_point; 00302 } 00303 00304 void InteractiveMarkerControl::rotate( Ogre::Ray &mouse_ray ) 00305 { 00306 Ogre::Vector3 intersection_3d; 00307 Ogre::Vector2 intersection_2d; 00308 float ray_t; 00309 00310 Ogre::Vector3 rotation_axis = control_frame_orientation_at_mouse_down_ * control_orientation_.xAxis(); 00311 00312 // Find rotation_center = 3D point closest to grab_point_ which is 00313 // on the rotation axis, relative to the reference frame. 00314 Ogre::Vector3 rotation_center = closestPointOnLineToPoint( control_frame_node_->getPosition(), 00315 rotation_axis, 00316 grab_point_ ); 00317 00318 // Find intersection of mouse_ray with plane centered at rotation_center. 00319 if( intersectSomeYzPlane( mouse_ray, rotation_center, control_frame_orientation_at_mouse_down_, 00320 intersection_3d, intersection_2d, ray_t )) 00321 { 00322 // Find rotation 00323 Ogre::Vector3 grab_rel_center = grab_point_ - rotation_center; 00324 Ogre::Vector3 mouse_rel_center = intersection_3d - rotation_center; 00325 00326 Ogre::Quaternion orientation_change_since_mouse_down = 00327 grab_rel_center.getRotationTo( mouse_rel_center, rotation_axis ); 00328 00329 Ogre::Radian rot; 00330 Ogre::Vector3 axis; 00331 orientation_change_since_mouse_down.ToAngleAxis( rot, axis ); 00332 // Quaternion::ToAngleAxis() always gives a positive angle. The 00333 // axis it emits (in this case) will either be equal to 00334 // rotation_axis or will be the negative of it. Doing the 00335 // dot-product then gives either 1.0 or -1.0, which is just what 00336 // we need to get the sign for our angle. 00337 Ogre::Radian rotation_since_mouse_down = rot * axis.dotProduct( rotation_axis ); 00338 00339 rotation_ = rotation_at_mouse_down_ + rotation_since_mouse_down; 00340 parent_->setPose( parent_->getPosition(), 00341 orientation_change_since_mouse_down * parent_orientation_at_mouse_down_, 00342 name_ ); 00343 } 00344 } 00345 00346 void InteractiveMarkerControl::movePlane( Ogre::Ray &mouse_ray ) 00347 { 00348 Ogre::Vector3 intersection_3d; 00349 Ogre::Vector2 intersection_2d; 00350 float ray_t; 00351 00352 if( intersectSomeYzPlane( mouse_ray, grab_point_, control_frame_node_->getOrientation(), 00353 intersection_3d, intersection_2d, ray_t )) 00354 { 00355 parent_->setPose( intersection_3d - grab_point_ + parent_position_at_mouse_down_, parent_->getOrientation(), name_ ); 00356 } 00357 } 00358 00361 void InteractiveMarkerControl::worldToScreen( const Ogre::Vector3& pos_rel_reference, 00362 const Ogre::Viewport* viewport, 00363 Ogre::Vector2& screen_pos ) 00364 { 00365 Ogre::Vector3 world_pos = reference_node_->convertLocalToWorldPosition( pos_rel_reference ); 00366 00367 const Ogre::Camera* cam = viewport->getCamera(); 00368 Ogre::Vector3 homogeneous_screen_position = cam->getProjectionMatrix() * (cam->getViewMatrix() * world_pos); 00369 00370 double half_width = viewport->getActualWidth() / 2.0; 00371 double half_height = viewport->getActualHeight() / 2.0; 00372 00373 screen_pos.x = half_width + (half_width * homogeneous_screen_position.x) - .5; 00374 screen_pos.y = half_height + (half_height * -homogeneous_screen_position.y) - .5; 00375 } 00376 00380 bool InteractiveMarkerControl::findClosestPoint( const Ogre::Ray& target_ray, 00381 const Ogre::Ray& mouse_ray, 00382 Ogre::Vector3& closest_point ) 00383 { 00384 // Find the closest point on target_ray to any point on mouse_ray. 00385 // 00386 // Math taken from http://paulbourke.net/geometry/lineline3d/ 00387 // line P1->P2 is target_ray 00388 // line P3->P4 is mouse_ray 00389 00390 Ogre::Vector3 v13 = target_ray.getOrigin() - mouse_ray.getOrigin(); 00391 Ogre::Vector3 v43 = mouse_ray.getDirection(); 00392 Ogre::Vector3 v21 = target_ray.getDirection(); 00393 double d1343 = v13.dotProduct( v43 ); 00394 double d4321 = v43.dotProduct( v21 ); 00395 double d1321 = v13.dotProduct( v21 ); 00396 double d4343 = v43.dotProduct( v43 ); 00397 double d2121 = v21.dotProduct( v21 ); 00398 00399 double denom = d2121 * d4343 - d4321 * d4321; 00400 if( fabs( denom ) <= Ogre::Matrix3::EPSILON ) 00401 { 00402 return false; 00403 } 00404 double numer = d1343 * d4321 - d1321 * d4343; 00405 00406 double mua = numer / denom; 00407 closest_point = target_ray.getPoint( mua ); 00408 return true; 00409 } 00410 00411 void InteractiveMarkerControl::moveAxis( const Ogre::Ray& mouse_ray, const ViewportMouseEvent& event ) 00412 { 00413 // compute control-axis ray based on grab_point_, etc. 00414 Ogre::Ray control_ray; 00415 control_ray.setOrigin( grab_point_ ); 00416 control_ray.setDirection( control_frame_node_->getOrientation() * control_orientation_.xAxis() ); 00417 00418 // project control-axis ray onto screen. 00419 Ogre::Vector2 control_ray_screen_start, control_ray_screen_end; 00420 worldToScreen( control_ray.getOrigin(), event.viewport, control_ray_screen_start ); 00421 worldToScreen( control_ray.getPoint( 1 ), event.viewport, control_ray_screen_end ); 00422 00423 Ogre::Vector2 mouse_point( event.x, event.y ); 00424 00425 // Find closest point on projected ray to mouse point 00426 // Math: if P is the start of the ray, v is the direction vector of 00427 // the ray (not normalized), and X is the test point, then the 00428 // closest point on the line to X is given by: 00429 // 00430 // (X-P).v 00431 // P + v * ------- 00432 // v.v 00433 // where "." is the dot product. 00434 Ogre::Vector2 control_ray_screen_dir = control_ray_screen_end - control_ray_screen_start; 00435 double denominator = control_ray_screen_dir.dotProduct( control_ray_screen_dir ); 00436 if( fabs( denominator ) > Ogre::Matrix3::EPSILON ) // If the control ray is not straight in line with the view. 00437 { 00438 double factor = 00439 ( mouse_point - control_ray_screen_start ).dotProduct( control_ray_screen_dir ) / denominator; 00440 00441 Ogre::Vector2 closest_screen_point = control_ray_screen_start + control_ray_screen_dir * factor; 00442 00443 // make a new "mouse ray" for the point on the projected ray 00444 int width = event.viewport->getActualWidth() - 1; 00445 int height = event.viewport->getActualHeight() - 1; 00446 Ogre::Ray new_mouse_ray = event.viewport->getCamera()->getCameraToViewportRay( (closest_screen_point.x+.5) / width, 00447 (closest_screen_point.y+.5) / height ); 00448 new_mouse_ray.setOrigin( reference_node_->convertWorldToLocalPosition( new_mouse_ray.getOrigin() ) ); 00449 new_mouse_ray.setDirection( reference_node_->convertWorldToLocalOrientation( Ogre::Quaternion::IDENTITY ) * new_mouse_ray.getDirection() ); 00450 00451 // find closest point on control-axis ray to new mouse ray (should intersect actually) 00452 Ogre::Vector3 closest_point; 00453 if( findClosestPoint( control_ray, new_mouse_ray, closest_point )) 00454 { 00455 // set position of parent to closest_point - grab_point_ + parent_position_at_mouse_down_. 00456 parent_->setPose( closest_point - grab_point_ + parent_position_at_mouse_down_, 00457 parent_->getOrientation(), name_ ); 00458 } 00459 } 00460 } 00461 00462 void InteractiveMarkerControl::moveRotate( Ogre::Ray &mouse_ray ) 00463 { 00464 Ogre::Vector3 new_drag_rel_ref; 00465 Ogre::Vector2 intersection_2d; 00466 float ray_t; 00467 00468 // get rotation axis rel ref (constant for entire drag) 00469 // - rotation_axis_ 00470 00471 // get current rotation center rel ref 00472 // - compute rotation center rel control frame at mouse-down (constant for entire drag) 00473 // - current rotation center rel ref = current control frame * above 00474 Ogre::Matrix4 control_rel_ref; 00475 control_rel_ref.makeTransform( control_frame_node_->getPosition(), 00476 Ogre::Vector3::UNIT_SCALE, 00477 control_frame_node_->getOrientation() ); 00478 Ogre::Vector3 rotation_center = control_rel_ref * rotation_center_rel_control_; 00479 00480 // get previous 3D drag point rel ref 00481 // - compute grab point rel control frame at mouse-down (constant for entire drag) 00482 // - prev_drag_rel_ref = current control frame + above 00483 Ogre::Vector3 prev_drag_rel_ref = control_rel_ref * grab_point_rel_control_; 00484 00485 // get new 3D drag point rel ref (this is "intersection_3d" in rotate().) 00486 // - intersectSomeYzPlane( mouse_ray, rotation_center, control_frame_orientation ) 00487 if( intersectSomeYzPlane( mouse_ray, rotation_center, control_frame_node_->getOrientation(), 00488 new_drag_rel_ref, intersection_2d, ray_t )) 00489 { 00490 // compute rotation angle from old drag point to new. 00491 // - prev_rel_center = prev_drag_rel_ref - rotation_center 00492 // - new_rel_center = new_drag_rel_ref - rotation_center 00493 // - rotation_change = prev_rel_center.getRotationTo( new_rel_center, rotation_axis ) 00494 // - get Radians of angle change 00495 // - rotation_ += angle_change 00496 // - parent_->rotate(rotation_change) 00497 Ogre::Vector3 prev_rel_center = prev_drag_rel_ref - rotation_center; 00498 Ogre::Vector3 new_rel_center = new_drag_rel_ref - rotation_center; 00499 if( new_rel_center.length() > Ogre::Matrix3::EPSILON ) 00500 { 00501 Ogre::Quaternion rotation_change = prev_rel_center.getRotationTo( new_rel_center, rotation_axis_ ); 00502 Ogre::Radian rot; 00503 Ogre::Vector3 axis; 00504 rotation_change.ToAngleAxis( rot, axis ); 00505 // Quaternion::ToAngleAxis() always gives a positive angle. The 00506 // axis it emits (in this case) will either be equal to 00507 // rotation_axis or will be the negative of it. Doing the 00508 // dot-product then gives either 1.0 or -1.0, which is just what 00509 // we need to get the sign for our angle. 00510 Ogre::Radian angle_change = rot * axis.dotProduct( rotation_axis_ ); 00511 rotation_ += angle_change; 00512 parent_->rotate( rotation_change, name_ ); 00513 00514 // compute translation from rotated old drag point to new drag point. 00515 // - pos_change = new_rel_center * (1.0 - prev_rel_center.length() / new_rel_center.length()) 00516 // - parent_->translate(pos_change) 00517 parent_->translate( new_rel_center * (1.0 - prev_rel_center.length() / new_rel_center.length()), name_ ); 00518 } 00519 } 00520 } 00521 00522 void InteractiveMarkerControl::setHighlight( float a ) 00523 { 00524 std::set<Ogre::Pass*>::iterator it; 00525 for (it = highlight_passes_.begin(); it != highlight_passes_.end(); it++) 00526 { 00527 (*it)->setAmbient(a,a,a); 00528 } 00529 00530 std::vector<PointsMarkerPtr>::iterator pm_it; 00531 for( pm_it = points_markers_.begin(); pm_it != points_markers_.end(); pm_it++ ) 00532 { 00533 (*pm_it)->setHighlightColor( a, a, a ); 00534 } 00535 } 00536 00537 void InteractiveMarkerControl::recordDraggingInPlaceEvent( ViewportMouseEvent& event ) 00538 { 00539 dragging_in_place_event_ = event; 00540 dragging_in_place_event_.type = QEvent::MouseMove; 00541 } 00542 00543 void InteractiveMarkerControl::handleMouseEvent( ViewportMouseEvent& event ) 00544 { 00545 // * check if this is just a receive/lost focus event 00546 // * try to hand over the mouse event to the parent interactive marker 00547 // * otherwise, execute mouse move handling 00548 00549 // handle receive/lose focus 00550 if( event.type == QEvent::FocusIn ) 00551 { 00552 has_focus_ = true; 00553 std::set<Ogre::Pass*>::iterator it; 00554 setHighlight(0.4); 00555 } 00556 else if( event.type == QEvent::FocusOut ) 00557 { 00558 has_focus_ = false; 00559 setHighlight(0.0); 00560 return; 00561 } 00562 00563 // change dragging state 00564 switch( interaction_mode_ ) 00565 { 00566 case visualization_msgs::InteractiveMarkerControl::BUTTON: 00567 if( event.leftUp() ) 00568 { 00569 Ogre::Vector3 point_rel_world; 00570 bool got_3D_point = vis_manager_->getSelectionManager()->get3DPoint( event.viewport, event.x, event.y, point_rel_world ); 00571 00572 visualization_msgs::InteractiveMarkerFeedback feedback; 00573 feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK; 00574 feedback.control_name = name_; 00575 feedback.marker_name = parent_->getName(); 00576 parent_->publishFeedback( feedback, got_3D_point, point_rel_world ); 00577 } 00578 break; 00579 00580 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS: 00581 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE: 00582 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE: 00583 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS: 00584 if( event.leftDown() ) 00585 { 00586 parent_->startDragging(); 00587 dragging_ = true; 00588 recordDraggingInPlaceEvent( event ); 00589 if( ! vis_manager_->getSelectionManager()->get3DPoint( event.viewport, event.x, event.y, grab_point_ )) 00590 { 00591 // If we couldn't get a 3D point for the grab, just use the 00592 // current relative position of the control frame. 00593 grab_point_ = control_frame_node_->getPosition(); 00594 } 00595 else 00596 { 00597 // If we could get a 3D point for the grab, convert it from 00598 // the world frame to the reference frame (in case those are different). 00599 grab_point_ = reference_node_->convertWorldToLocalPosition(grab_point_); 00600 } 00601 grab_pixel_.x = event.x; 00602 grab_pixel_.y = event.y; 00603 parent_position_at_mouse_down_ = parent_->getPosition(); 00604 parent_orientation_at_mouse_down_ = parent_->getOrientation(); 00605 control_frame_orientation_at_mouse_down_ = control_frame_node_->getOrientation(); 00606 rotation_at_mouse_down_ = rotation_; 00607 00608 rotation_axis_ = control_frame_node_->getOrientation() * control_orientation_.xAxis(); 00609 00610 // Find rotation_center = 3D point closest to grab_point_ which is 00611 // on the rotation axis, relative to the reference frame. 00612 Ogre::Vector3 rotation_center_rel_ref = closestPointOnLineToPoint( parent_->getPosition(), 00613 rotation_axis_, 00614 grab_point_ ); 00615 Ogre::Matrix4 reference_rel_control_frame; 00616 reference_rel_control_frame.makeInverseTransform( control_frame_node_->getPosition(), 00617 Ogre::Vector3::UNIT_SCALE, 00618 control_frame_node_->getOrientation() ); 00619 rotation_center_rel_control_ = reference_rel_control_frame * rotation_center_rel_ref; 00620 grab_point_rel_control_ = reference_rel_control_frame * grab_point_; 00621 } 00622 if( event.leftUp() ) 00623 { 00624 dragging_ = false; 00625 parent_->stopDragging(); 00626 } 00627 break; 00628 00629 default: 00630 break; 00631 } 00632 00633 if( event.leftDown() ) 00634 { 00635 setHighlight(0.6); 00636 } 00637 else if( event.leftUp() ) 00638 { 00639 setHighlight(0.4); 00640 } 00641 00642 if (!parent_->handleMouseEvent(event, name_)) 00643 { 00644 if( event.type == QEvent::MouseMove && event.left() ) 00645 { 00646 recordDraggingInPlaceEvent( event ); 00647 handleMouseMovement( event ); 00648 } 00649 } 00650 } 00651 00652 void InteractiveMarkerControl::handleMouseMovement( ViewportMouseEvent& event ) 00653 { 00654 // handle mouse movement 00655 float width = event.viewport->getActualWidth() - 1; 00656 float height = event.viewport->getActualHeight() - 1; 00657 00658 Ogre::Ray mouse_ray = event.viewport->getCamera()->getCameraToViewportRay( (event.x + .5) / width, 00659 (event.y + .5) / height ); 00660 00661 Ogre::Ray last_mouse_ray = 00662 event.viewport->getCamera()->getCameraToViewportRay( 00663 (event.last_x + .5) / width, (event.last_y + .5) / height); 00664 00665 //convert rays into reference frame 00666 mouse_ray.setOrigin( reference_node_->convertWorldToLocalPosition( mouse_ray.getOrigin() ) ); 00667 mouse_ray.setDirection( reference_node_->convertWorldToLocalOrientation( Ogre::Quaternion::IDENTITY ) * mouse_ray.getDirection() ); 00668 00669 last_mouse_ray.setOrigin( reference_node_->convertWorldToLocalPosition( last_mouse_ray.getOrigin() ) ); 00670 last_mouse_ray.setDirection( reference_node_->convertWorldToLocalOrientation( Ogre::Quaternion::IDENTITY ) * last_mouse_ray.getDirection() ); 00671 00672 switch (interaction_mode_) 00673 { 00674 case visualization_msgs::InteractiveMarkerControl::MOVE_AXIS: 00675 moveAxis( mouse_ray, event ); 00676 break; 00677 00678 case visualization_msgs::InteractiveMarkerControl::MOVE_PLANE: 00679 movePlane( mouse_ray ); 00680 break; 00681 00682 case visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE: 00683 moveRotate( mouse_ray ); 00684 break; 00685 00686 case visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS: 00687 rotate(mouse_ray); 00688 break; 00689 00690 default: 00691 break; 00692 } 00693 } 00694 00695 bool InteractiveMarkerControl::intersectYzPlane( const Ogre::Ray& mouse_ray, 00696 Ogre::Vector3& intersection_3d, 00697 Ogre::Vector2& intersection_2d, 00698 float &ray_t ) 00699 { 00700 return intersectSomeYzPlane( mouse_ray, 00701 control_frame_node_->getPosition(), 00702 control_frame_node_->getOrientation(), 00703 intersection_3d, intersection_2d, ray_t ); 00704 } 00705 00706 bool InteractiveMarkerControl::intersectSomeYzPlane( const Ogre::Ray& mouse_ray, 00707 const Ogre::Vector3& point_on_plane, 00708 const Ogre::Quaternion& plane_orientation, 00709 Ogre::Vector3& intersection_3d, 00710 Ogre::Vector2& intersection_2d, 00711 float& ray_t ) 00712 { 00713 Ogre::Vector3 normal = plane_orientation * control_orientation_.xAxis(); 00714 Ogre::Vector3 axis_1 = plane_orientation * control_orientation_.yAxis(); 00715 Ogre::Vector3 axis_2 = plane_orientation * control_orientation_.zAxis(); 00716 00717 Ogre::Plane plane(normal, point_on_plane); 00718 00719 Ogre::Vector2 origin_2d(point_on_plane.dotProduct(axis_1), point_on_plane.dotProduct(axis_2)); 00720 00721 std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(plane); 00722 if (intersection.first) 00723 { 00724 intersection_3d = mouse_ray.getPoint(intersection.second); 00725 intersection_2d = Ogre::Vector2(intersection_3d.dotProduct(axis_1), intersection_3d.dotProduct(axis_2)); 00726 intersection_2d -= origin_2d; 00727 00728 ray_t = intersection.second; 00729 return true; 00730 } 00731 00732 ray_t = 0; 00733 return false; 00734 } 00735 00736 void InteractiveMarkerControl::addHighlightPass( S_MaterialPtr materials ) 00737 { 00738 S_MaterialPtr::iterator it; 00739 00740 for (it = materials.begin(); it != materials.end(); it++) 00741 { 00742 Ogre::MaterialPtr material = *it; 00743 Ogre::Pass *original_pass = material->getTechnique(0)->getPass(0); 00744 Ogre::Pass *pass = material->getTechnique(0)->createPass(); 00745 00746 pass->setSceneBlending(Ogre::SBT_ADD); 00747 pass->setDepthWriteEnabled(true); 00748 pass->setDepthCheckEnabled(true); 00749 pass->setLightingEnabled(true); 00750 pass->setAmbient(0, 0, 0); 00751 pass->setDiffuse(0, 0, 0, 0); 00752 pass->setSpecular(0, 0, 0, 0); 00753 pass->setCullingMode(original_pass->getCullingMode()); 00754 00755 highlight_passes_.insert(pass); 00756 } 00757 } 00758 00759 }