30 #include <boost/make_shared.hpp> 
   34 #include <OgreSceneNode.h> 
   35 #include <OgreSceneManager.h> 
   36 #include <OgreMaterialManager.h> 
   37 #include <OgreResourceGroupManager.h> 
   38 #include <OgreSubEntity.h> 
   40 #include <OgreRenderWindow.h> 
   44 #include <tf2_msgs/TF2Error.h> 
   61   , pose_changed_(false)
 
   62   , time_since_last_feedback_(0)
 
   64   , pose_update_requested_(false)
 
   66   , show_visual_aids_(false)
 
   80   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
   81   Ogre::Vector3 position(message.pose.position.x, message.pose.position.y, message.pose.position.z);
 
   82   Ogre::Quaternion orientation(message.pose.orientation.w, message.pose.orientation.x,
 
   83                                message.pose.orientation.y, message.pose.orientation.z);
 
   85   if (orientation.w == 0 && orientation.x == 0 && orientation.y == 0 && orientation.z == 0)
 
  100   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  103   name_ = message.name;
 
  106   if (message.controls.empty())
 
  118   position_ = Ogre::Vector3(message.pose.position.x, message.pose.position.y, message.pose.position.z);
 
  130   has_menu_ = !message.menu_entries.empty();
 
  149   std::set<std::string> old_names_to_delete;
 
  150   M_ControlPtr::const_iterator ci;
 
  153     old_names_to_delete.insert((*ci).first);
 
  157   for (
unsigned i = 0; i < message.controls.size(); i++)
 
  159     const visualization_msgs::InteractiveMarkerControl& control_message = message.controls[i];
 
  160     M_ControlPtr::iterator search_iter = 
controls_.find(control_message.name);
 
  167       control = (*search_iter).second;
 
  173       controls_[control_message.name] = control;
 
  176     control->processMessage(control_message);
 
  180     old_names_to_delete.erase(control_message.name);
 
  184   std::set<std::string>::iterator si;
 
  185   for (si = old_names_to_delete.begin(); si != old_names_to_delete.end(); si++)
 
  193   if (!message.description.empty())
 
  201     menu_.reset(
new QMenu());
 
  206     for (
unsigned m = 0; m < message.menu_entries.size(); m++)
 
  208       const visualization_msgs::MenuEntry& entry = message.menu_entries[m];
 
  212       if (entry.parent_id == 0)
 
  219         std::map<uint32_t, MenuNode>::iterator parent_it = 
menu_entries_.find(entry.parent_id);
 
  222           ROS_ERROR(
"interactive marker menu entry %u found before its parent id %u.  Ignoring.",
 
  223                     entry.id, entry.parent_id);
 
  227           (*parent_it).second.child_ids.push_back(entry.id);
 
  236     std::ostringstream 
s;
 
  252   for (
size_t id_index = 0; id_index < ids.size(); id_index++)
 
  254     uint32_t 
id = ids[id_index];
 
  255     std::map<uint32_t, MenuNode>::iterator node_it = 
menu_entries_.find(
id);
 
  257                    "interactive marker menu entry %u not found during populateMenu().", 
id);
 
  265       menu->addAction(action);
 
  279   if (entry.find(
"[x]") == 0)
 
  281     menu_entry = QChar(0x2611) + QString::fromStdString(entry.substr(3));
 
  283   else if (entry.find(
"[ ]") == 0)
 
  285     menu_entry = QChar(0x2610) + QString::fromStdString(entry.substr(3));
 
  289     menu_entry = QChar(0x3000) + QString::fromStdString(entry);
 
  297   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  298   Ogre::Vector3 reference_position;
 
  299   Ogre::Quaternion reference_orientation;
 
  319       int retval = 
tf->_getLatestCommonTime(target_id, source_id, 
reference_time_, &error);
 
  321       if (retval != tf2_msgs::TF2Error::NO_ERROR)
 
  323         std::ostringstream 
s;
 
  324         s << 
"Error getting time of latest transform between " << 
reference_frame_ << 
" and " 
  325           << fixed_frame << 
": " << error << 
" (error code: " << retval << 
")";
 
  334                                                  reference_orientation))
 
  353   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  360   M_ControlPtr::iterator it;
 
  363     (*it).second->update();
 
  379       visualization_msgs::InteractiveMarkerFeedback feedback;
 
  380       feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::KEEP_ALIVE;
 
  388   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  389   visualization_msgs::InteractiveMarkerFeedback feedback;
 
  390   feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE;
 
  398   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  408     setPose(position, orientation, 
"");
 
  413                                 Ogre::Quaternion orientation,
 
  414                                 const std::string& control_name)
 
  416   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  425   M_ControlPtr::iterator it;
 
  438   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  447   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  453   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  454   M_ControlPtr::iterator it;
 
  457     (*it).second->setShowVisualAids(show);
 
  464   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  470   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  476   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  483   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  494                                             const Ogre::Vector3& cursor_pos,
 
  495                                             const Ogre::Quaternion& ,
 
  496                                             const std::string& control_name)
 
  498   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  502     Ogre::Vector3 point_rel_world = cursor_pos;
 
  503     bool got_3D_point = 
true;
 
  505     visualization_msgs::InteractiveMarkerFeedback feedback;
 
  506     feedback.control_name = control_name;
 
  507     feedback.marker_name = 
name_;
 
  510     feedback.event_type = ((uint8_t)visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE);
 
  513     feedback.event_type = (
event.type == QEvent::MouseButtonPress ?
 
  514                                (uint8_t)visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN :
 
  515                                (uint8_t)visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP);
 
  531       Ogre::Vector3 three_d_point = cursor_pos;
 
  532       bool valid_point = 
true;
 
  534       QCursor::setPos(event.
panel->mapToGlobal(QPoint(mouse_pos.x, mouse_pos.y)));
 
  535       showMenu(event, control_name, three_d_point, valid_point);
 
  545   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  549     Ogre::Vector3 point_rel_world;
 
  553     visualization_msgs::InteractiveMarkerFeedback feedback;
 
  554     feedback.control_name = control_name;
 
  555     feedback.marker_name = 
name_;
 
  558     feedback.event_type = ((uint8_t)visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE);
 
  561     feedback.event_type = (
event.type == QEvent::MouseButtonPress ?
 
  562                                (uint8_t)visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN :
 
  563                                (uint8_t)visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP);
 
  579       Ogre::Vector3 three_d_point;
 
  582       showMenu(event, control_name, three_d_point, valid_point);
 
  592                                  const std::string& control_name,
 
  593                                  const Ogre::Vector3& three_d_point,
 
  600   event.panel->showContextMenu(
menu_);
 
  607   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  609   std::map<uint32_t, MenuNode>::iterator it = 
menu_entries_.find(menu_item_id);
 
  613     visualization_msgs::MenuEntry& entry = it->second.entry;
 
  615     std::string 
command = entry.command;
 
  616     uint8_t command_type = entry.command_type;
 
  618     if (command_type == visualization_msgs::MenuEntry::FEEDBACK)
 
  620       visualization_msgs::InteractiveMarkerFeedback feedback;
 
  621       feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::MENU_SELECT;
 
  622       feedback.menu_entry_id = entry.id;
 
  626     else if (command_type == visualization_msgs::MenuEntry::ROSRUN)
 
  628       std::string sys_cmd = 
"rosrun " + 
command;
 
  634     else if (command_type == visualization_msgs::MenuEntry::ROSLAUNCH)
 
  636       std::string sys_cmd = 
"roslaunch " + 
command;
 
  647                                         bool mouse_point_valid,
 
  648                                         const Ogre::Vector3& mouse_point_rel_world)
 
  650   boost::recursive_mutex::scoped_lock lock(
mutex_);
 
  652   feedback.marker_name = 
name_;
 
  670     feedback.mouse_point_valid = mouse_point_valid;
 
  671     if (mouse_point_valid)
 
  673       Ogre::Vector3 mouse_rel_reference =
 
  675       feedback.mouse_point.x = mouse_rel_reference.x;
 
  676       feedback.mouse_point.y = mouse_rel_reference.y;
 
  677       feedback.mouse_point.z = mouse_rel_reference.z;
 
  691     feedback.pose.position.x = world_position.x;
 
  692     feedback.pose.position.y = world_position.y;
 
  693     feedback.pose.position.z = world_position.z;
 
  694     feedback.pose.orientation.x = world_orientation.x;
 
  695     feedback.pose.orientation.y = world_orientation.y;
 
  696     feedback.pose.orientation.z = world_orientation.z;
 
  697     feedback.pose.orientation.w = world_orientation.w;
 
  699     feedback.mouse_point_valid = mouse_point_valid;
 
  700     feedback.mouse_point.x = mouse_point_rel_world.x;
 
  701     feedback.mouse_point.y = mouse_point_rel_world.y;
 
  702     feedback.mouse_point.z = mouse_point_rel_world.z;