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