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