interactive_marker.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <boost/make_shared.hpp>
31 
32 #include <QMenu>
33 
34 #include <OgreSceneNode.h>
35 #include <OgreSceneManager.h>
36 #include <OgreMaterialManager.h>
37 #include <OgreResourceGroupManager.h>
38 #include <OgreSubEntity.h>
39 #include <OgreMath.h>
40 #include <OgreRenderWindow.h>
41 
42 #include <ros/ros.h>
44 #include <tf2_msgs/TF2Error.h>
45 
46 #include <rviz/frame_manager.h>
47 #include <rviz/display_context.h>
49 #include <rviz/frame_manager.h>
50 #include <rviz/render_panel.h>
51 #include <rviz/geometry.h>
53 
56 
57 namespace rviz
58 {
59 InteractiveMarker::InteractiveMarker(Ogre::SceneNode* scene_node, DisplayContext* context)
60  : context_(context)
61  , pose_changed_(false)
62  , time_since_last_feedback_(0)
63  , dragging_(false)
64  , pose_update_requested_(false)
65  , heart_beat_t_(0)
66  , show_visual_aids_(false)
67 {
68  reference_node_ = scene_node->createChildSceneNode();
69  axes_ = new Axes(context->getSceneManager(), reference_node_, 1, 0.05);
70 }
71 
73 {
74  delete axes_;
75  context_->getSceneManager()->destroySceneNode(reference_node_);
76 }
77 
78 void InteractiveMarker::processMessage(const visualization_msgs::InteractiveMarkerPose& message)
79 {
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);
84 
85  if (orientation.w == 0 && orientation.x == 0 && orientation.y == 0 && orientation.z == 0)
86  {
87  orientation.w = 1;
88  }
89 
90  reference_time_ = message.header.stamp;
91  reference_frame_ = message.header.frame_id;
92  frame_locked_ = (message.header.stamp == ros::Time(0));
93 
94  requestPoseUpdate(position, orientation);
96 }
97 
98 bool InteractiveMarker::processMessage(const visualization_msgs::InteractiveMarker& message)
99 {
100  boost::recursive_mutex::scoped_lock lock(mutex_);
101 
102  // copy values
103  name_ = message.name;
104  description_ = message.description;
105 
106  if (message.controls.empty())
107  {
108  Q_EMIT statusUpdate(StatusProperty::Ok, name_, "Marker empty.");
109  return false;
110  }
111 
112  scale_ = message.scale;
113 
114  reference_frame_ = message.header.frame_id;
115  reference_time_ = message.header.stamp;
116  frame_locked_ = (message.header.stamp == ros::Time(0));
117 
118  position_ = Ogre::Vector3(message.pose.position.x, message.pose.position.y, message.pose.position.z);
119 
120  normalizeQuaternion(message.pose.orientation, orientation_);
121 
122  pose_changed_ = false;
124 
125  // setup axes
128  axes_->set(scale_, scale_ * 0.05);
129 
130  has_menu_ = !message.menu_entries.empty();
131 
133 
134  // Instead of just erasing all the old controls and making new ones
135  // here, we want to preserve as much as possible from the old ones,
136  // so that we don't lose the drag action in progress if a control is
137  // being dragged when this update comes in.
138  //
139  // Controls are stored in a map from control name to control
140  // pointer, so we loop over the incoming control messages looking
141  // for names we already know about. When we find them, we just call
142  // the control's processMessage() function to update it. When we
143  // don't find them, we create a new Control. We also keep track of
144  // which control names we used to have but which are not present in
145  // the incoming message, which we use to delete the unwanted
146  // controls.
147 
148  // Make set of old-names called old-names-to-delete.
149  std::set<std::string> old_names_to_delete;
150  M_ControlPtr::const_iterator ci;
151  for (ci = controls_.begin(); ci != controls_.end(); ci++)
152  {
153  old_names_to_delete.insert((*ci).first);
154  }
155 
156  // Loop over new array:
157  for (unsigned i = 0; i < message.controls.size(); i++)
158  {
159  const visualization_msgs::InteractiveMarkerControl& control_message = message.controls[i];
160  M_ControlPtr::iterator search_iter = controls_.find(control_message.name);
162 
163  // If message->name in map,
164  if (search_iter != controls_.end())
165  {
166  // Use existing control
167  control = (*search_iter).second;
168  }
169  else
170  {
171  // Else make new control
172  control = boost::make_shared<InteractiveMarkerControl>(context_, reference_node_, this);
173  controls_[control_message.name] = control;
174  }
175  // Update the control with the message data
176  control->processMessage(control_message);
177  control->setShowVisualAids(show_visual_aids_);
178 
179  // Remove message->name from old-names-to-delete
180  old_names_to_delete.erase(control_message.name);
181  }
182 
183  // Loop over old-names-to-delete
184  std::set<std::string>::iterator si;
185  for (si = old_names_to_delete.begin(); si != old_names_to_delete.end(); si++)
186  {
187  // Remove Control object from map for name-to-delete
188  controls_.erase(*si);
189  }
190 
191  description_control_ = boost::make_shared<InteractiveMarkerControl>(context_, reference_node_, this);
192 
193  if (!message.description.empty())
194  description_control_->processMessage(interactive_markers::makeTitle(message));
195 
196  // create menu
197  menu_entries_.clear();
198  menu_.reset();
199  if (has_menu_)
200  {
201  menu_.reset(new QMenu());
202  top_level_menu_ids_.clear();
203 
204  // Put all menu entries into the menu_entries_ map and create the
205  // tree of menu entry ids.
206  for (unsigned m = 0; m < message.menu_entries.size(); m++)
207  {
208  const visualization_msgs::MenuEntry& entry = message.menu_entries[m];
209  MenuNode node;
210  node.entry = entry;
211  menu_entries_[entry.id] = node;
212  if (entry.parent_id == 0)
213  {
214  top_level_menu_ids_.push_back(entry.id);
215  }
216  else
217  {
218  // Find the parent node and add this entry to the parent's list of children.
219  std::map<uint32_t, MenuNode>::iterator parent_it = menu_entries_.find(entry.parent_id);
220  if (parent_it == menu_entries_.end())
221  {
222  ROS_ERROR("interactive marker menu entry %u found before its parent id %u. Ignoring.",
223  entry.id, entry.parent_id);
224  }
225  else
226  {
227  (*parent_it).second.child_ids.push_back(entry.id);
228  }
229  }
230  }
232  }
233 
234  if (frame_locked_)
235  {
236  std::ostringstream s;
237  s << "Locked to frame " << reference_frame_;
238  Q_EMIT statusUpdate(StatusProperty::Ok, name_, s.str());
239  }
240  else
241  {
242  Q_EMIT statusUpdate(StatusProperty::Ok, name_, "Position is fixed.");
243  }
244  return true;
245 }
246 
247 // Recursively append menu and submenu entries to menu, based on a
248 // vector of menu entry id numbers describing the menu entries at the
249 // current level.
250 void InteractiveMarker::populateMenu(QMenu* menu, std::vector<uint32_t>& ids)
251 {
252  for (size_t id_index = 0; id_index < ids.size(); id_index++)
253  {
254  uint32_t id = ids[id_index];
255  std::map<uint32_t, MenuNode>::iterator node_it = menu_entries_.find(id);
256  ROS_ASSERT_MSG(node_it != menu_entries_.end(),
257  "interactive marker menu entry %u not found during populateMenu().", id);
258  MenuNode node = (*node_it).second;
259 
260  if (node.child_ids.empty())
261  {
262  IntegerAction* action =
263  new IntegerAction(makeMenuString(node.entry.title), menu, (int)node.entry.id);
265  menu->addAction(action);
266  }
267  else
268  {
269  // make sub-menu
270  QMenu* sub_menu = menu->addMenu(makeMenuString(node.entry.title));
271  populateMenu(sub_menu, node.child_ids);
272  }
273  }
274 }
275 
276 QString InteractiveMarker::makeMenuString(const std::string& entry)
277 {
278  QString menu_entry;
279  if (entry.find("[x]") == 0)
280  {
281  menu_entry = QChar(0x2611) + QString::fromStdString(entry.substr(3));
282  }
283  else if (entry.find("[ ]") == 0)
284  {
285  menu_entry = QChar(0x2610) + QString::fromStdString(entry.substr(3));
286  }
287  else
288  {
289  menu_entry = QChar(0x3000) + QString::fromStdString(entry);
290  }
291  return menu_entry;
292 }
293 
294 
296 {
297  boost::recursive_mutex::scoped_lock lock(mutex_);
298  Ogre::Vector3 reference_position;
299  Ogre::Quaternion reference_orientation;
300 
301  // if we're frame-locked, we need to find out what the most recent transformation time
302  // actually is so we send back correct feedback
303  if (frame_locked_)
304  {
305  std::string fixed_frame = context_->getFrameManager()->getFixedFrame();
306  if (reference_frame_ == fixed_frame)
307  {
308  // if the two frames are identical, we don't need to do anything.
309  // This should be ros::Time::now(), but then the computer running
310  // RViz has to be time-synced with the server
312  }
313  else
314  {
316  tf2::CompactFrameID target_id = tf->_lookupFrameNumber(reference_frame_);
317  tf2::CompactFrameID source_id = tf->_lookupFrameNumber(fixed_frame);
318  std::string error;
319  int retval = tf->_getLatestCommonTime(target_id, source_id, reference_time_, &error);
320 
321  if (retval != tf2_msgs::TF2Error::NO_ERROR)
322  {
323  std::ostringstream s;
324  s << "Error getting time of latest transform between " << reference_frame_ << " and "
325  << fixed_frame << ": " << error << " (error code: " << retval << ")";
326  Q_EMIT statusUpdate(StatusProperty::Error, name_, s.str());
327  reference_node_->setVisible(false);
328  return;
329  }
330  }
331  }
332 
333  if (!context_->getFrameManager()->getTransform(reference_frame_, ros::Time(), reference_position,
334  reference_orientation))
335  {
336  std::string error;
338  Q_EMIT statusUpdate(StatusProperty::Error, name_, error);
339  reference_node_->setVisible(false);
340  return;
341  }
342 
343  reference_node_->setPosition(reference_position);
344  reference_node_->setOrientation(reference_orientation);
345  reference_node_->setVisible(true, false);
346 
348 }
349 
350 
351 void InteractiveMarker::update(float wall_dt)
352 {
353  boost::recursive_mutex::scoped_lock lock(mutex_);
354  time_since_last_feedback_ += wall_dt;
355  if (frame_locked_)
356  {
358  }
359 
360  M_ControlPtr::iterator it;
361  for (it = controls_.begin(); it != controls_.end(); it++)
362  {
363  (*it).second->update();
364  }
366  {
367  description_control_->update();
368  }
369 
370  if (dragging_)
371  {
372  if (pose_changed_)
373  {
374  publishPose();
375  }
376  else if (time_since_last_feedback_ > 0.25)
377  {
378  // send keep-alive so we don't use control over the marker
379  visualization_msgs::InteractiveMarkerFeedback feedback;
380  feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::KEEP_ALIVE;
381  publishFeedback(feedback);
382  }
383  }
384 }
385 
387 {
388  boost::recursive_mutex::scoped_lock lock(mutex_);
389  visualization_msgs::InteractiveMarkerFeedback feedback;
390  feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE;
391  feedback.control_name = last_control_name_;
392  publishFeedback(feedback);
393  pose_changed_ = false;
394 }
395 
396 void InteractiveMarker::requestPoseUpdate(Ogre::Vector3 position, Ogre::Quaternion orientation)
397 {
398  boost::recursive_mutex::scoped_lock lock(mutex_);
399  if (dragging_)
400  {
401  pose_update_requested_ = true;
402  requested_position_ = position;
403  requested_orientation_ = orientation;
404  }
405  else
406  {
408  setPose(position, orientation, "");
409  }
410 }
411 
412 void InteractiveMarker::setPose(Ogre::Vector3 position,
413  Ogre::Quaternion orientation,
414  const std::string& control_name)
415 {
416  boost::recursive_mutex::scoped_lock lock(mutex_);
417  position_ = position;
418  orientation_ = orientation;
419  pose_changed_ = true;
420  last_control_name_ = control_name;
421 
424 
425  M_ControlPtr::iterator it;
426  for (it = controls_.begin(); it != controls_.end(); it++)
427  {
428  (*it).second->interactiveMarkerPoseChanged(position_, orientation_);
429  }
431  {
432  description_control_->interactiveMarkerPoseChanged(position_, orientation_);
433  }
434 }
435 
437 {
438  boost::recursive_mutex::scoped_lock lock(mutex_);
439  if (description_control_.get())
440  {
441  description_control_->setVisible(show);
442  }
443 }
444 
446 {
447  boost::recursive_mutex::scoped_lock lock(mutex_);
448  axes_->getSceneNode()->setVisible(show);
449 }
450 
452 {
453  boost::recursive_mutex::scoped_lock lock(mutex_);
454  M_ControlPtr::iterator it;
455  for (it = controls_.begin(); it != controls_.end(); it++)
456  {
457  (*it).second->setShowVisualAids(show);
458  }
459  show_visual_aids_ = show;
460 }
461 
462 void InteractiveMarker::translate(Ogre::Vector3 delta_position, const std::string& control_name)
463 {
464  boost::recursive_mutex::scoped_lock lock(mutex_);
465  setPose(position_ + delta_position, orientation_, control_name);
466 }
467 
468 void InteractiveMarker::rotate(Ogre::Quaternion delta_orientation, const std::string& control_name)
469 {
470  boost::recursive_mutex::scoped_lock lock(mutex_);
471  setPose(position_, delta_orientation * orientation_, control_name);
472 }
473 
475 {
476  boost::recursive_mutex::scoped_lock lock(mutex_);
477  dragging_ = true;
478  pose_changed_ = false;
479 }
480 
482 {
483  boost::recursive_mutex::scoped_lock lock(mutex_);
484  dragging_ = false;
486  {
489  pose_update_requested_ = false;
490  }
491 }
492 
494  const Ogre::Vector3& cursor_pos,
495  const Ogre::Quaternion& /*cursor_rot*/,
496  const std::string& control_name)
497 {
498  boost::recursive_mutex::scoped_lock lock(mutex_);
499 
500  if (event.acting_button == Qt::LeftButton)
501  {
502  Ogre::Vector3 point_rel_world = cursor_pos;
503  bool got_3D_point = true;
504 
505  visualization_msgs::InteractiveMarkerFeedback feedback;
506  feedback.control_name = control_name;
507  feedback.marker_name = name_;
508 
509  // make sure we've published a last pose update
510  feedback.event_type = ((uint8_t)visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE);
511  publishFeedback(feedback, got_3D_point, point_rel_world);
512 
513  feedback.event_type = (event.type == QEvent::MouseButtonPress ?
514  (uint8_t)visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN :
515  (uint8_t)visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP);
516  publishFeedback(feedback, got_3D_point, point_rel_world);
517  }
518 
519  if (!dragging_ && menu_.get())
520  {
521  // Event.right() will be false during a right-button-up event. We
522  // want to swallow (with the "return true") all other
523  // right-button-related mouse events.
524  if (event.right())
525  {
526  return true;
527  }
528  if (event.rightUp() && event.buttons_down == Qt::NoButton)
529  {
530  // Save the 3D mouse point to send with the menu feedback, if any.
531  Ogre::Vector3 three_d_point = cursor_pos;
532  bool valid_point = true;
533  Ogre::Vector2 mouse_pos = project3DPointToViewportXY(event.viewport, cursor_pos);
534  QCursor::setPos(event.panel->mapToGlobal(QPoint(mouse_pos.x, mouse_pos.y)));
535  showMenu(event, control_name, three_d_point, valid_point);
536  return true;
537  }
538  }
539 
540  return false;
541 }
542 
543 bool InteractiveMarker::handleMouseEvent(ViewportMouseEvent& event, const std::string& control_name)
544 {
545  boost::recursive_mutex::scoped_lock lock(mutex_);
546 
547  if (event.acting_button == Qt::LeftButton)
548  {
549  Ogre::Vector3 point_rel_world;
550  bool got_3D_point =
551  context_->getSelectionManager()->get3DPoint(event.viewport, event.x, event.y, point_rel_world);
552 
553  visualization_msgs::InteractiveMarkerFeedback feedback;
554  feedback.control_name = control_name;
555  feedback.marker_name = name_;
556 
557  // make sure we've published a last pose update
558  feedback.event_type = ((uint8_t)visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE);
559  publishFeedback(feedback, got_3D_point, point_rel_world);
560 
561  feedback.event_type = (event.type == QEvent::MouseButtonPress ?
562  (uint8_t)visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN :
563  (uint8_t)visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP);
564  publishFeedback(feedback, got_3D_point, point_rel_world);
565  }
566 
567  if (!dragging_ && menu_.get())
568  {
569  // Event.right() will be false during a right-button-up event. We
570  // want to swallow (with the "return true") all other
571  // right-button-related mouse events.
572  if (event.right())
573  {
574  return true;
575  }
576  if (event.rightUp() && event.buttons_down == Qt::NoButton)
577  {
578  // Save the 3D mouse point to send with the menu feedback, if any.
579  Ogre::Vector3 three_d_point;
580  bool valid_point =
581  context_->getSelectionManager()->get3DPoint(event.viewport, event.x, event.y, three_d_point);
582  showMenu(event, control_name, three_d_point, valid_point);
583  return true;
584  }
585  }
586 
587  return false;
588 }
589 
590 
592  const std::string& control_name,
593  const Ogre::Vector3& three_d_point,
594  bool valid_point)
595 {
596  // Save the 3D mouse point to send with the menu feedback, if any.
597  got_3d_point_for_menu_ = valid_point;
598  three_d_point_for_menu_ = three_d_point;
599 
600  event.panel->showContextMenu(menu_);
601  last_control_name_ = control_name;
602 }
603 
604 
606 {
607  boost::recursive_mutex::scoped_lock lock(mutex_);
608 
609  std::map<uint32_t, MenuNode>::iterator it = menu_entries_.find(menu_item_id);
610 
611  if (it != menu_entries_.end())
612  {
613  visualization_msgs::MenuEntry& entry = it->second.entry;
614 
615  std::string command = entry.command;
616  uint8_t command_type = entry.command_type;
617 
618  if (command_type == visualization_msgs::MenuEntry::FEEDBACK)
619  {
620  visualization_msgs::InteractiveMarkerFeedback feedback;
621  feedback.event_type = visualization_msgs::InteractiveMarkerFeedback::MENU_SELECT;
622  feedback.menu_entry_id = entry.id;
623  feedback.control_name = last_control_name_;
625  }
626  else if (command_type == visualization_msgs::MenuEntry::ROSRUN)
627  {
628  std::string sys_cmd = "rosrun " + command;
629  ROS_INFO_STREAM("Running system command: " << sys_cmd);
630  sys_thread_ =
631  boost::shared_ptr<boost::thread>(new boost::thread(boost::bind(&system, sys_cmd.c_str())));
632  // system( sys_cmd.c_str() );
633  }
634  else if (command_type == visualization_msgs::MenuEntry::ROSLAUNCH)
635  {
636  std::string sys_cmd = "roslaunch " + command;
637  ROS_INFO_STREAM("Running system command: " << sys_cmd);
638  sys_thread_ =
639  boost::shared_ptr<boost::thread>(new boost::thread(boost::bind(&system, sys_cmd.c_str())));
640  // system( sys_cmd.c_str() );
641  }
642  }
643 }
644 
645 
646 void InteractiveMarker::publishFeedback(visualization_msgs::InteractiveMarkerFeedback& feedback,
647  bool mouse_point_valid,
648  const Ogre::Vector3& mouse_point_rel_world)
649 {
650  boost::recursive_mutex::scoped_lock lock(mutex_);
651 
652  feedback.marker_name = name_;
653 
654  if (frame_locked_)
655  {
656  // frame-locked IMs will return their pose in the same coordinate frame
657  // as they were set up with (the "reference frame").
658  // The transformation's timestamp will be the one used for placing
659  // the reference frame into the fixed frame
660  feedback.header.frame_id = reference_frame_;
661  feedback.header.stamp = reference_time_;
662  feedback.pose.position.x = position_.x;
663  feedback.pose.position.y = position_.y;
664  feedback.pose.position.z = position_.z;
665  feedback.pose.orientation.x = orientation_.x;
666  feedback.pose.orientation.y = orientation_.y;
667  feedback.pose.orientation.z = orientation_.z;
668  feedback.pose.orientation.w = orientation_.w;
669 
670  feedback.mouse_point_valid = mouse_point_valid;
671  if (mouse_point_valid)
672  {
673  Ogre::Vector3 mouse_rel_reference =
674  reference_node_->convertWorldToLocalPosition(mouse_point_rel_world);
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;
678  }
679  }
680  else
681  {
682  // Timestamped IMs will return feedback in RViz's fixed frame
683  feedback.header.frame_id = context_->getFixedFrame().toStdString();
684  // This should be ros::Time::now(), but then the computer running
685  // RViz has to be time-synced with the server
686  feedback.header.stamp = ros::Time();
687 
688  Ogre::Vector3 world_position = reference_node_->convertLocalToWorldPosition(position_);
689  Ogre::Quaternion world_orientation = reference_node_->convertLocalToWorldOrientation(orientation_);
690 
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;
698 
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;
703  }
704 
705  Q_EMIT userFeedback(feedback);
706 
708 }
709 
710 } // end namespace rviz
rviz::FrameManager::getTF2BufferPtr
const std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr()
Definition: frame_manager.h:209
rviz::InteractiveMarker::processMessage
bool processMessage(const visualization_msgs::InteractiveMarker &message)
Definition: interactive_marker.cpp:98
rviz::Axes::getSceneNode
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
Definition: axes.h:96
rviz::InteractiveMarker::InteractiveMarker
InteractiveMarker(Ogre::SceneNode *scene_node, DisplayContext *context)
Definition: interactive_marker.cpp:59
rviz::InteractiveMarker::MenuNode::entry
visualization_msgs::MenuEntry entry
Definition: interactive_marker.h:244
rviz::ViewportMouseEvent::rightUp
bool rightUp()
Definition: viewport_mouse_event.h:136
frame_manager.h
rviz::DisplayContext::queueRender
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
rviz::InteractiveMarker::name_
std::string name_
Definition: interactive_marker.h:226
rviz::InteractiveMarker::context_
DisplayContext * context_
Definition: interactive_marker.h:204
boost::shared_ptr< InteractiveMarkerControl >
geometry.h
rviz::StatusProperty::Error
@ Error
Definition: status_property.h:46
rviz::InteractiveMarker::reference_frame_
std::string reference_frame_
Definition: interactive_marker.h:207
rviz::IntegerAction
Definition: integer_action.h:39
rviz::InteractiveMarker::startDragging
void startDragging()
Definition: interactive_marker.cpp:474
rviz::InteractiveMarker::update
void update(float wall_dt)
Definition: interactive_marker.cpp:351
rviz::InteractiveMarker::handleMouseEvent
bool handleMouseEvent(ViewportMouseEvent &event, const std::string &control_name)
Definition: interactive_marker.cpp:543
rviz::InteractiveMarker::publishFeedback
void publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback, bool mouse_point_valid=false, const Ogre::Vector3 &mouse_point_rel_world=Ogre::Vector3(0, 0, 0))
Definition: interactive_marker.cpp:646
s
XmlRpcServer s
rviz::InteractiveMarker::menu_entries_
std::map< uint32_t, MenuNode > menu_entries_
Definition: interactive_marker.h:249
ros.h
rviz::InteractiveMarker::populateMenu
void populateMenu(QMenu *menu, std::vector< uint32_t > &ids)
Definition: interactive_marker.cpp:250
command
ROSLIB_DECL std::string command(const std::string &cmd)
rviz::project3DPointToViewportXY
Ogre::Vector2 project3DPointToViewportXY(const Ogre::Viewport *view, const Ogre::Vector3 &pos)
Given a viewport and a 3D position in world coordinates, project that point into the view plane.
Definition: geometry.cpp:75
rviz::ViewportMouseEvent
Definition: viewport_mouse_event.h:45
rviz::InteractiveMarker::axes_
Axes * axes_
Definition: interactive_marker.h:261
rviz::ViewportMouseEvent::x
int x
Definition: viewport_mouse_event.h:157
rviz::InteractiveMarker::updateReferencePose
void updateReferencePose()
Definition: interactive_marker.cpp:295
rviz::InteractiveMarker::sys_thread_
boost::shared_ptr< boost::thread > sys_thread_
Definition: interactive_marker.h:270
rviz::InteractiveMarker::show_visual_aids_
bool show_visual_aids_
Definition: interactive_marker.h:275
rviz::InteractiveMarker::publishPose
void publishPose()
Definition: interactive_marker.cpp:386
rviz::InteractiveMarker::setPose
void setPose(Ogre::Vector3 position, Ogre::Quaternion orientation, const std::string &control_name)
Definition: interactive_marker.cpp:412
rviz::InteractiveMarker::requested_orientation_
Ogre::Quaternion requested_orientation_
Definition: interactive_marker.h:234
rviz::InteractiveMarker::reference_time_
ros::Time reference_time_
Definition: interactive_marker.h:208
rviz::InteractiveMarker::position_
Ogre::Vector3 position_
Definition: interactive_marker.h:215
rviz::InteractiveMarker::description_control_
InteractiveMarkerControlPtr description_control_
Definition: interactive_marker.h:263
rviz::InteractiveMarker::reference_node_
Ogre::SceneNode * reference_node_
Definition: interactive_marker.h:212
selection_manager.h
rviz::InteractiveMarker::statusUpdate
void statusUpdate(StatusProperty::Level level, const std::string &name, const std::string &text)
validate_quaternions.h
interactive_marker.h
tools.h
rviz::InteractiveMarker::orientation_
Ogre::Quaternion orientation_
Definition: interactive_marker.h:216
rviz::DisplayContext::getSceneManager
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
rviz::InteractiveMarker::got_3d_point_for_menu_
bool got_3d_point_for_menu_
Definition: interactive_marker.h:272
rviz::InteractiveMarker::MenuNode::child_ids
std::vector< uint32_t > child_ids
Definition: interactive_marker.h:245
rviz::ViewportMouseEvent::right
bool right()
Definition: viewport_mouse_event.h:108
rviz::SelectionManager::get3DPoint
bool get3DPoint(Ogre::Viewport *viewport, const int x, const int y, Ogre::Vector3 &result_point)
Definition: selection_manager.cpp:179
tf2::CompactFrameID
uint32_t CompactFrameID
rviz::ViewportMouseEvent::viewport
Ogre::Viewport * viewport
Definition: viewport_mouse_event.h:155
rviz::normalizeQuaternion
float normalizeQuaternion(float &w, float &x, float &y, float &z)
Definition: validate_quaternions.h:66
rviz::InteractiveMarker::description_
std::string description_
Definition: interactive_marker.h:227
rviz::IntegerAction::triggered
void triggered(int id)
rviz::InteractiveMarker::frame_locked_
bool frame_locked_
Definition: interactive_marker.h:209
rviz::FrameManager::getFixedFrame
const std::string & getFixedFrame()
Return the current fixed frame name.
Definition: frame_manager.h:204
rviz::InteractiveMarker::stopDragging
void stopDragging()
Definition: interactive_marker.cpp:481
rviz::InteractiveMarker::setShowDescription
void setShowDescription(bool show)
Definition: interactive_marker.cpp:436
rviz::ViewportMouseEvent::buttons_down
Qt::MouseButtons buttons_down
Definition: viewport_mouse_event.h:162
rviz
Definition: add_display_dialog.cpp:54
rviz::InteractiveMarker::scale_
float scale_
Definition: interactive_marker.h:236
rviz::InteractiveMarker::time_since_last_feedback_
double time_since_last_feedback_
Definition: interactive_marker.h:220
rviz::StatusProperty::Ok
@ Ok
Definition: status_property.h:44
rviz::ViewportMouseEvent::y
int y
Definition: viewport_mouse_event.h:158
rviz::InteractiveMarker::has_menu_
bool has_menu_
Definition: interactive_marker.h:239
rviz::InteractiveMarker::mutex_
boost::recursive_mutex mutex_
Definition: interactive_marker.h:268
rviz::ViewportMouseEvent::panel
RenderPanel * panel
Definition: viewport_mouse_event.h:154
rviz::InteractiveMarker::setShowAxes
void setShowAxes(bool show)
Definition: interactive_marker.cpp:445
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
rviz::DisplayContext::getFixedFrame
virtual QString getFixedFrame() const =0
Return the fixed frame name.
rviz::InteractiveMarker::three_d_point_for_menu_
Ogre::Vector3 three_d_point_for_menu_
Definition: interactive_marker.h:273
integer_action.h
rviz::InteractiveMarker::last_control_name_
std::string last_control_name_
Definition: interactive_marker.h:255
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
rviz::DisplayContext
Pure-virtual base class for objects which give Display subclasses context in which to work.
Definition: display_context.h:81
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
rviz::InteractiveMarker::pose_changed_
bool pose_changed_
Definition: interactive_marker.h:219
rviz::Axes
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Definition: axes.h:57
rviz::InteractiveMarker::handle3DCursorEvent
bool handle3DCursorEvent(ViewportMouseEvent &event, const Ogre::Vector3 &cursor_pos, const Ogre::Quaternion &cursor_rot, const std::string &control_name)
Definition: interactive_marker.cpp:493
rviz::InteractiveMarker::MenuNode
Definition: interactive_marker.h:242
rviz::InteractiveMarker::rotate
void rotate(Ogre::Quaternion delta_orientation, const std::string &control_name)
Definition: interactive_marker.cpp:468
render_panel.h
rviz::InteractiveMarker::controls_
M_ControlPtr controls_
Definition: interactive_marker.h:224
rviz::FrameManager::getTransform
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
Definition: frame_manager.h:125
rviz::InteractiveMarker::menu_
boost::shared_ptr< QMenu > menu_
Definition: interactive_marker.h:238
rviz::InteractiveMarker::showMenu
void showMenu(ViewportMouseEvent &event, const std::string &control_name, const Ogre::Vector3 &three_d_point, bool valid_point)
Definition: interactive_marker.cpp:591
interactive_markers::makeTitle
INTERACTIVE_MARKERS_PUBLIC visualization_msgs::InteractiveMarkerControl makeTitle(const visualization_msgs::InteractiveMarker &msg)
rviz::InteractiveMarker::translate
void translate(Ogre::Vector3 delta_position, const std::string &control_name)
Definition: interactive_marker.cpp:462
ros::Time
rviz::InteractiveMarker::requestPoseUpdate
void requestPoseUpdate(Ogre::Vector3 position, Ogre::Quaternion orientation)
Definition: interactive_marker.cpp:396
rviz::InteractiveMarker::setShowVisualAids
void setShowVisualAids(bool show)
Definition: interactive_marker.cpp:451
rviz::InteractiveMarker::makeMenuString
QString makeMenuString(const std::string &entry)
Definition: interactive_marker.cpp:276
ROS_ERROR
#define ROS_ERROR(...)
rviz::InteractiveMarker::~InteractiveMarker
~InteractiveMarker() override
Definition: interactive_marker.cpp:72
rviz::InteractiveMarker::top_level_menu_ids_
std::vector< uint32_t > top_level_menu_ids_
Definition: interactive_marker.h:252
rviz::Axes::set
void set(float length, float radius, float alpha=1.0f)
Set the parameters on this object.
Definition: axes.cpp:76
tf
rviz::Axes::setPosition
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
Definition: axes.cpp:92
rviz::DisplayContext::getSelectionManager
virtual SelectionManager * getSelectionManager() const =0
Return a pointer to the SelectionManager.
display_context.h
rviz::Axes::setOrientation
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation of the object.
Definition: axes.cpp:97
rviz::InteractiveMarker::requested_position_
Ogre::Vector3 requested_position_
Definition: interactive_marker.h:233
rviz::ViewportMouseEvent::acting_button
Qt::MouseButton acting_button
Definition: viewport_mouse_event.h:161
rviz::InteractiveMarker::dragging_
bool dragging_
Definition: interactive_marker.h:229
rviz::FrameManager::transformHasProblems
bool transformHasProblems(const std::string &frame, ros::Time time, std::string &error)
Check to see if a transform is known between a given frame and the fixed frame.
Definition: frame_manager.cpp:272
rviz::InteractiveMarker::handleMenuSelect
void handleMenuSelect(int menu_item_id)
Definition: interactive_marker.cpp:605
rviz::InteractiveMarker::pose_update_requested_
bool pose_update_requested_
Definition: interactive_marker.h:232
rviz::InteractiveMarker::userFeedback
void userFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53