$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.h" 00031 00032 #include "interactive_markers/tools.h" 00033 00034 #include "rviz/frame_manager.h" 00035 #include "rviz/visualization_manager.h" 00036 #include "rviz/selection/selection_manager.h" 00037 #include "rviz/frame_manager.h" 00038 #include "rviz/default_plugin/interactive_marker_display.h" 00039 #include "rviz/render_panel.h" 00040 00041 #include <OGRE/OgreSceneNode.h> 00042 #include <OGRE/OgreSceneManager.h> 00043 #include <OGRE/OgreMaterialManager.h> 00044 #include <OGRE/OgreResourceGroupManager.h> 00045 #include <OGRE/OgreSubEntity.h> 00046 #include <OGRE/OgreMath.h> 00047 00048 #include <boost/make_shared.hpp> 00049 #include <wx/menu.h> 00050 00051 #include <ros/ros.h> 00052 00053 namespace rviz 00054 { 00055 00056 InteractiveMarker::InteractiveMarker( InteractiveMarkerDisplay *owner, VisualizationManager *vis_manager, std::string topic_ns, std::string client_id ) : 00057 owner_(owner) 00058 , vis_manager_(vis_manager) 00059 , pose_changed_(false) 00060 , time_since_last_feedback_(0) 00061 , dragging_(false) 00062 , pose_update_requested_(false) 00063 , heart_beat_t_(0) 00064 , topic_ns_(topic_ns) 00065 , client_id_(client_id) 00066 { 00067 ros::NodeHandle nh; 00068 std::string feedback_topic = topic_ns+"/feedback"; 00069 feedback_pub_ = nh.advertise<visualization_msgs::InteractiveMarkerFeedback>( feedback_topic, 100, false ); 00070 00071 reference_node_ = vis_manager->getSceneManager()->getRootSceneNode()->createChildSceneNode(); 00072 00073 axes_node_ = reference_node_->createChildSceneNode(); 00074 axes_ = new ogre_tools::Axes( vis_manager->getSceneManager(), axes_node_, 1, 0.05 ); 00075 } 00076 00077 InteractiveMarker::~InteractiveMarker() 00078 { 00079 delete axes_; 00080 vis_manager_->getSceneManager()->destroySceneNode( axes_node_ ); 00081 vis_manager_->getSceneManager()->destroySceneNode( reference_node_ ); 00082 } 00083 00084 void InteractiveMarker::reset() 00085 { 00086 boost::recursive_mutex::scoped_lock lock(mutex_); 00087 controls_.clear(); 00088 menu_entries_.clear(); 00089 } 00090 00091 void InteractiveMarker::processMessage( visualization_msgs::InteractiveMarkerPoseConstPtr message ) 00092 { 00093 boost::recursive_mutex::scoped_lock lock(mutex_); 00094 Ogre::Vector3 position( message->pose.position.x, message->pose.position.y, message->pose.position.z ); 00095 Ogre::Quaternion orientation( message->pose.orientation.w, message->pose.orientation.x, 00096 message->pose.orientation.y, message->pose.orientation.z ); 00097 00098 if ( orientation.w == 0 && orientation.x == 0 && orientation.y == 0 && orientation.z == 0 ) 00099 { 00100 orientation.w = 1; 00101 } 00102 00103 reference_time_ = message->header.stamp; 00104 reference_frame_ = message->header.frame_id; 00105 frame_locked_ = (message->header.stamp == ros::Time(0)); 00106 00107 requestPoseUpdate( position, orientation ); 00108 vis_manager_->queueRender(); 00109 } 00110 00111 bool InteractiveMarker::processMessage( visualization_msgs::InteractiveMarkerConstPtr message ) 00112 { 00113 boost::recursive_mutex::scoped_lock lock(mutex_); 00114 reset(); 00115 00116 visualization_msgs::InteractiveMarker auto_message = *message; 00117 interactive_markers::autoComplete( auto_message ); 00118 00119 // copy values 00120 00121 name_ = auto_message.name; 00122 description_ = auto_message.description; 00123 00124 if ( auto_message.controls.size() == 0 ) 00125 { 00126 owner_->setStatus( status_levels::Ok, name_, "Marker empty."); 00127 return false; 00128 } 00129 00130 scale_ = auto_message.scale; 00131 00132 reference_frame_ = auto_message.header.frame_id; 00133 reference_time_ = auto_message.header.stamp; 00134 frame_locked_ = (auto_message.header.stamp == ros::Time(0)); 00135 00136 position_ = Ogre::Vector3( 00137 auto_message.pose.position.x, 00138 auto_message.pose.position.y, 00139 auto_message.pose.position.z ); 00140 00141 orientation_ = Ogre::Quaternion( 00142 auto_message.pose.orientation.w, 00143 auto_message.pose.orientation.x, 00144 auto_message.pose.orientation.y, 00145 auto_message.pose.orientation.z ); 00146 00147 pose_changed_ =false; 00148 time_since_last_feedback_ = 0; 00149 00150 // setup axes 00151 axes_->setPosition(position_); 00152 axes_->setOrientation(orientation_); 00153 axes_->set( scale_, scale_*0.05 ); 00154 00155 updateReferencePose(); 00156 00157 for ( unsigned i=0; i<auto_message.controls.size(); i++ ) 00158 { 00159 controls_.push_back( boost::make_shared<InteractiveMarkerControl>( 00160 vis_manager_, auto_message.controls[i], reference_node_, this ) ); 00161 } 00162 00163 description_control_ = boost::make_shared<InteractiveMarkerControl>( 00164 vis_manager_, interactive_markers::makeTitle( auto_message ), reference_node_, this ); 00165 controls_.push_back( description_control_ ); 00166 00167 00168 //create menu 00169 if ( message->menu_entries.size() > 0 ) 00170 { 00171 menu_.reset( new wxMenu() ); 00172 menu_entries_.clear(); 00173 top_level_menu_ids_.clear(); 00174 00175 // Put all menu entries into the menu_entries_ map and create the 00176 // tree of menu entry ids. 00177 for ( unsigned m=0; m < message->menu_entries.size(); m++ ) 00178 { 00179 const visualization_msgs::MenuEntry& entry = message->menu_entries[ m ]; 00180 MenuNode node; 00181 node.entry = entry; 00182 menu_entries_[ entry.id ] = node; 00183 if( entry.parent_id == 0 ) 00184 { 00185 top_level_menu_ids_.push_back( entry.id ); 00186 } 00187 else 00188 { 00189 // Find the parent node and add this entry to the parent's list of children. 00190 std::map< uint32_t, MenuNode >::iterator parent_it = menu_entries_.find( entry.parent_id ); 00191 if( parent_it == menu_entries_.end() ) { 00192 ROS_ERROR("interactive marker menu entry %u found before its parent id %u. Ignoring.", entry.id, entry.parent_id); 00193 } 00194 else 00195 { 00196 (*parent_it).second.child_ids.push_back( entry.id ); 00197 } 00198 } 00199 } 00200 00201 populateMenu( menu_.get(), top_level_menu_ids_ ); 00202 } 00203 00204 owner_->setStatus( status_levels::Ok, name_, "OK"); 00205 return true; 00206 } 00207 00208 // Recursively append menu and submenu entries to menu, based on a 00209 // vector of menu entry id numbers describing the menu entries at the 00210 // current level. 00211 void InteractiveMarker::populateMenu( wxMenu* menu, std::vector<uint32_t>& ids ) 00212 { 00213 for( size_t id_index = 0; id_index < ids.size(); id_index++ ) 00214 { 00215 uint32_t id = ids[ id_index ]; 00216 std::map< uint32_t, MenuNode >::iterator node_it = menu_entries_.find( id ); 00217 ROS_ASSERT_MSG(node_it != menu_entries_.end(), "interactive marker menu entry %u not found during populateMenu().", id); 00218 MenuNode node = (*node_it).second; 00219 00220 if ( node.child_ids.empty() ) 00221 { 00222 // make regular entry. MenuEntry id numbers are re-used as wx menu command identifiers. 00223 menu->Append( (int) node.entry.id, makeMenuString( node.entry.title )); 00224 } 00225 else 00226 { 00227 // make sub-menu 00228 wxMenu* sub_menu = new wxMenu(); 00229 populateMenu( sub_menu, node.child_ids ); 00230 menu->AppendSubMenu( sub_menu, makeMenuString( node.entry.title )); 00231 } 00232 } 00233 menu->Connect(wxEVT_COMMAND_MENU_SELECTED, 00234 (wxObjectEventFunction)&InteractiveMarker::handleMenuSelect, NULL, this); 00235 } 00236 00237 wxString InteractiveMarker::makeMenuString( const std::string &entry ) 00238 { 00239 wxString menu_entry; 00240 if ( entry.find( "[x]" ) == 0 ) 00241 { 00242 menu_entry = wxString::FromUTF8("\u2611") + wxString::FromAscii( entry.substr( 3 ).c_str() ); 00243 } 00244 else if ( entry.find( "[ ]" ) == 0 ) 00245 { 00246 menu_entry = wxString::FromUTF8("\u2610") + wxString::FromAscii( entry.substr( 3 ).c_str() ); 00247 } 00248 else 00249 { 00250 menu_entry = wxString::FromUTF8("\u3000 ") + wxString::FromAscii( entry.c_str() ); 00251 } 00252 return menu_entry; 00253 } 00254 00255 void InteractiveMarker::updateReferencePose() 00256 { 00257 boost::recursive_mutex::scoped_lock lock(mutex_); 00258 Ogre::Vector3 reference_position; 00259 Ogre::Quaternion reference_orientation; 00260 00261 // if we're frame-locked, we need to find out what the most recent transformation time 00262 // actually is so we send back correct feedback 00263 if ( frame_locked_ ) 00264 { 00265 std::string fixed_frame = FrameManager::instance()->getFixedFrame(); 00266 if ( reference_frame_ == fixed_frame ) 00267 { 00268 // if the two frames are identical, we don't need to do anything. 00269 reference_time_ = ros::Time::now(); 00270 } 00271 else 00272 { 00273 std::string error; 00274 int retval = FrameManager::instance()->getTFClient()->getLatestCommonTime( 00275 reference_frame_, fixed_frame, reference_time_, &error ); 00276 if ( retval != tf::NO_ERROR ) 00277 { 00278 std::ostringstream s; 00279 s <<"Error getting time of latest transform between " << reference_frame_ 00280 << " and " << fixed_frame << ": " << error << " (error code: " << retval << ")"; 00281 owner_->setStatus( status_levels::Error, name_, s.str() ); 00282 reference_node_->setVisible( false ); 00283 return; 00284 } 00285 } 00286 } 00287 00288 if (!FrameManager::instance()->getTransform( reference_frame_, reference_time_, 00289 reference_position, reference_orientation )) 00290 { 00291 std::string error; 00292 FrameManager::instance()->transformHasProblems(reference_frame_, reference_time_, error); 00293 owner_->setStatus( status_levels::Error, name_, error); 00294 reference_node_->setVisible( false ); 00295 return; 00296 } 00297 00298 reference_node_->setPosition( reference_position ); 00299 reference_node_->setOrientation( reference_orientation ); 00300 reference_node_->setVisible( true, false ); 00301 00302 vis_manager_->queueRender(); 00303 } 00304 00305 void InteractiveMarker::update(float wall_dt) 00306 { 00307 boost::recursive_mutex::scoped_lock lock(mutex_); 00308 time_since_last_feedback_ += wall_dt; 00309 if ( frame_locked_ ) 00310 { 00311 updateReferencePose(); 00312 } 00313 00314 std::list<InteractiveMarkerControlPtr>::iterator it; 00315 for ( it = controls_.begin(); it != controls_.end(); it++ ) 00316 { 00317 (*it)->update(); 00318 } 00319 00320 if ( dragging_ ) 00321 { 00322 if ( pose_changed_ ) 00323 { 00324 publishPose(); 00325 } 00326 else if ( time_since_last_feedback_ > 0.25 ) 00327 { 00328 //send keep-alive so we don't use control over the marker 00329 visualization_msgs::InteractiveMarkerFeedback feedback; 00330 feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::KEEP_ALIVE; 00331 publishFeedback( feedback ); 00332 } 00333 } 00334 } 00335 00336 void InteractiveMarker::publishPose() 00337 { 00338 boost::recursive_mutex::scoped_lock lock(mutex_); 00339 visualization_msgs::InteractiveMarkerFeedback feedback; 00340 feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE; 00341 feedback.control_name = last_control_name_; 00342 publishFeedback( feedback ); 00343 pose_changed_ = false; 00344 } 00345 00346 void InteractiveMarker::requestPoseUpdate( Ogre::Vector3 position, Ogre::Quaternion orientation ) 00347 { 00348 boost::recursive_mutex::scoped_lock lock(mutex_); 00349 if ( dragging_ ) 00350 { 00351 pose_update_requested_ = true; 00352 requested_position_ = position; 00353 requested_orientation_ = orientation; 00354 } 00355 else 00356 { 00357 updateReferencePose(); 00358 setPose( position, orientation, "" ); 00359 } 00360 } 00361 00362 void InteractiveMarker::setPose( Ogre::Vector3 position, Ogre::Quaternion orientation, const std::string &control_name ) 00363 { 00364 boost::recursive_mutex::scoped_lock lock(mutex_); 00365 position_ = position; 00366 orientation_ = orientation; 00367 pose_changed_ = true; 00368 last_control_name_ = control_name; 00369 00370 axes_->setPosition(position_); 00371 axes_->setOrientation(orientation_); 00372 00373 std::list<InteractiveMarkerControlPtr>::iterator it; 00374 for ( it = controls_.begin(); it != controls_.end(); it++ ) 00375 { 00376 (*it)->interactiveMarkerPoseChanged( position_, orientation_ ); 00377 } 00378 } 00379 00380 void InteractiveMarker::setShowDescription( bool show ) 00381 { 00382 boost::recursive_mutex::scoped_lock lock(mutex_); 00383 if ( description_control_.get() ) 00384 { 00385 description_control_->setVisible( show ); 00386 } 00387 } 00388 00389 void InteractiveMarker::setShowAxes( bool show ) 00390 { 00391 boost::recursive_mutex::scoped_lock lock(mutex_); 00392 axes_node_->setVisible( show ); 00393 } 00394 00395 void InteractiveMarker::translate( Ogre::Vector3 delta_position, const std::string &control_name ) 00396 { 00397 boost::recursive_mutex::scoped_lock lock(mutex_); 00398 setPose( position_+delta_position, orientation_, control_name ); 00399 } 00400 00401 void InteractiveMarker::rotate( Ogre::Quaternion delta_orientation, const std::string &control_name ) 00402 { 00403 boost::recursive_mutex::scoped_lock lock(mutex_); 00404 setPose( position_, delta_orientation * orientation_, control_name ); 00405 } 00406 00407 void InteractiveMarker::startDragging() 00408 { 00409 boost::recursive_mutex::scoped_lock lock(mutex_); 00410 dragging_ = true; 00411 pose_changed_ = false; 00412 } 00413 00414 void InteractiveMarker::stopDragging() 00415 { 00416 boost::recursive_mutex::scoped_lock lock(mutex_); 00417 if ( pose_changed_ ) 00418 { 00419 publishPose(); 00420 } 00421 dragging_ = false; 00422 if ( pose_update_requested_ ) 00423 { 00424 updateReferencePose(); 00425 setPose( requested_position_, requested_orientation_, "" ); 00426 pose_update_requested_ = false; 00427 } 00428 } 00429 00430 bool InteractiveMarker::handleMouseEvent(ViewportMouseEvent& event, const std::string &control_name) 00431 { 00432 boost::recursive_mutex::scoped_lock lock(mutex_); 00433 00434 if (event.event.LeftDown() || event.event.LeftUp()) 00435 { 00436 Ogre::Vector3 point_rel_world; 00437 bool got_3D_point = 00438 vis_manager_->getSelectionManager()->get3DPoint( event.viewport, 00439 event.event.GetX(), event.event.GetY(), 00440 point_rel_world ); 00441 00442 visualization_msgs::InteractiveMarkerFeedback feedback; 00443 feedback.event_type = (event.event.LeftDown() ? 00444 (uint8_t)visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN : 00445 (uint8_t)visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP); 00446 00447 feedback.control_name = control_name; 00448 feedback.marker_name = name_; 00449 publishFeedback( feedback, got_3D_point, point_rel_world ); 00450 } 00451 00452 if ( menu_.get() ) 00453 { 00454 if ( event.event.RightDown() || event.event.RightIsDown() ) 00455 { 00456 return true; 00457 } 00458 if ( event.event.RightUp() ) 00459 { 00460 // Save the 3D mouse point to send with the menu feedback, if any. 00461 got_3d_point_for_menu_ = 00462 vis_manager_->getSelectionManager()->get3DPoint( event.viewport, 00463 event.event.GetX(), event.event.GetY(), 00464 three_d_point_for_menu_ ); 00465 00466 event.panel->setContextMenu( menu_ ); 00467 wxContextMenuEvent context_event( wxEVT_CONTEXT_MENU, 0, event.event.GetPosition() ); 00468 /* START_WX-2.9_COMPAT_CODE 00469 This code is related to ticket: https://code.ros.org/trac/ros-pkg/ticket/5156 00470 */ 00471 #if wxMAJOR_VERSION == 2 and wxMINOR_VERSION == 8 // If wxWidgets 2.8.x 00472 event.panel->AddPendingEvent( context_event ); 00473 #else 00474 event.panel->addPendingEvent(context_event); 00475 #endif 00476 /* END_WX-2.9_COMPAT_CODE */ 00477 last_control_name_ = control_name; 00478 return true; 00479 } 00480 } 00481 00482 return false; 00483 } 00484 00485 00486 void InteractiveMarker::handleMenuSelect(wxCommandEvent &evt) 00487 { 00488 boost::recursive_mutex::scoped_lock lock(mutex_); 00489 00490 std::map< uint32_t, MenuNode >::iterator it = menu_entries_.find( (uint32_t)evt.GetId() ); 00491 00492 if ( it != menu_entries_.end() ) 00493 { 00494 visualization_msgs::MenuEntry& entry = it->second.entry; 00495 00496 std::string command = entry.command; 00497 uint8_t command_type = entry.command_type; 00498 00499 if ( command_type == visualization_msgs::MenuEntry::FEEDBACK ) 00500 { 00501 visualization_msgs::InteractiveMarkerFeedback feedback; 00502 feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::MENU_SELECT; 00503 feedback.menu_entry_id = entry.id; 00504 feedback.control_name = last_control_name_; 00505 publishFeedback( feedback, got_3d_point_for_menu_, three_d_point_for_menu_ ); 00506 } 00507 else if ( command_type == visualization_msgs::MenuEntry::ROSRUN ) 00508 { 00509 std::string sys_cmd = "rosrun " + command; 00510 ROS_INFO_STREAM( "Running system command: " << sys_cmd ); 00511 sys_thread_ = boost::shared_ptr<boost::thread>( new boost::thread( boost::bind( &system, sys_cmd.c_str() ) ) ); 00512 //system( sys_cmd.c_str() ); 00513 } 00514 else if ( command_type == visualization_msgs::MenuEntry::ROSLAUNCH ) 00515 { 00516 std::string sys_cmd = "roslaunch " + command; 00517 ROS_INFO_STREAM( "Running system command: " << sys_cmd ); 00518 sys_thread_ = boost::shared_ptr<boost::thread>( new boost::thread( boost::bind( &system, sys_cmd.c_str() ) ) ); 00519 //system( sys_cmd.c_str() ); 00520 } 00521 } 00522 } 00523 00524 00525 void InteractiveMarker::publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback, 00526 bool mouse_point_valid, 00527 const Ogre::Vector3& mouse_point_rel_world ) 00528 { 00529 boost::recursive_mutex::scoped_lock lock(mutex_); 00530 00531 feedback.client_id = client_id_; 00532 feedback.marker_name = name_; 00533 00534 if ( frame_locked_ ) 00535 { 00536 feedback.header.frame_id = reference_frame_; 00537 feedback.header.stamp = reference_time_; 00538 feedback.pose.position.x = position_.x; 00539 feedback.pose.position.y = position_.y; 00540 feedback.pose.position.z = position_.z; 00541 feedback.pose.orientation.x = orientation_.x; 00542 feedback.pose.orientation.y = orientation_.y; 00543 feedback.pose.orientation.z = orientation_.z; 00544 feedback.pose.orientation.w = orientation_.w; 00545 00546 feedback.mouse_point_valid = mouse_point_valid; 00547 if( mouse_point_valid ) 00548 { 00549 Ogre::Vector3 mouse_rel_reference = reference_node_->convertWorldToLocalPosition( mouse_point_rel_world ); 00550 feedback.mouse_point.x = mouse_rel_reference.x; 00551 feedback.mouse_point.y = mouse_rel_reference.y; 00552 feedback.mouse_point.z = mouse_rel_reference.z; 00553 } 00554 } 00555 else 00556 { 00557 feedback.header.frame_id = vis_manager_->getFixedFrame(); 00558 feedback.header.stamp = ros::Time::now(); 00559 00560 Ogre::Vector3 world_position = reference_node_->convertLocalToWorldPosition( position_ ); 00561 Ogre::Quaternion world_orientation = reference_node_->convertLocalToWorldOrientation( orientation_ ); 00562 00563 feedback.pose.position.x = world_position.x; 00564 feedback.pose.position.y = world_position.y; 00565 feedback.pose.position.z = world_position.z; 00566 feedback.pose.orientation.x = world_orientation.x; 00567 feedback.pose.orientation.y = world_orientation.y; 00568 feedback.pose.orientation.z = world_orientation.z; 00569 feedback.pose.orientation.w = world_orientation.w; 00570 00571 feedback.mouse_point_valid = mouse_point_valid; 00572 feedback.mouse_point.x = mouse_point_rel_world.x; 00573 feedback.mouse_point.y = mouse_point_rel_world.y; 00574 feedback.mouse_point.z = mouse_point_rel_world.z; 00575 } 00576 00577 feedback_pub_.publish( feedback ); 00578 00579 time_since_last_feedback_ = 0; 00580 } 00581 00582 }