motion_planning_frame_objects.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Mario Prats */
36 
38 
43 
45 
46 #include <rviz/display_context.h>
47 #include <rviz/frame_manager.h>
49 
50 #include <tf2_eigen/tf2_eigen.h>
52 
53 #include <QMessageBox>
54 #include <QInputDialog>
55 #include <QFileDialog>
56 
57 #include "ui_motion_planning_rviz_plugin_frame.h"
58 
59 namespace
60 {
61 QString subframe_poses_to_qstring(const moveit::core::FixedTransformsMap& subframes)
62 {
63  QString status_text = "\nIt has the subframes '";
64  for (const auto& subframe : subframes)
65  {
66  status_text += QString::fromStdString(subframe.first) + "', '";
67  }
68  status_text.chop(3);
69  status_text += ".";
70  return status_text;
71 }
72 } // namespace
73 
74 namespace moveit_rviz_plugin
75 {
76 void MotionPlanningFrame::shapesComboBoxChanged(const QString& /*text*/)
77 {
78  switch (ui_->shapes_combo_box->currentData().toInt()) // fetch shape ID from current combobox item
79  {
80  case shapes::BOX:
81  ui_->shape_size_x_spin_box->setEnabled(true);
82  ui_->shape_size_y_spin_box->setEnabled(true);
83  ui_->shape_size_z_spin_box->setEnabled(true);
84  break;
85  case shapes::SPHERE:
86  ui_->shape_size_x_spin_box->setEnabled(true);
87  ui_->shape_size_y_spin_box->setEnabled(false);
88  ui_->shape_size_z_spin_box->setEnabled(false);
89  break;
90  case shapes::CYLINDER:
91  case shapes::CONE:
92  ui_->shape_size_x_spin_box->setEnabled(true);
93  ui_->shape_size_y_spin_box->setEnabled(false);
94  ui_->shape_size_z_spin_box->setEnabled(true);
95  break;
96  case shapes::MESH:
97  ui_->shape_size_x_spin_box->setEnabled(false);
98  ui_->shape_size_y_spin_box->setEnabled(false);
99  ui_->shape_size_z_spin_box->setEnabled(false);
100  break;
101  default:
102  break;
103  }
104 }
105 
107 {
108  ui_->publish_current_scene_button->setEnabled(dirty);
109 }
110 
112 {
113  return ui_->publish_current_scene_button->isEnabled();
114 }
115 
117 {
119  if (ps)
120  {
121  moveit_msgs::PlanningScene msg;
122  ps->getPlanningSceneMsg(msg);
124  setLocalSceneEdited(false);
125  }
126 }
127 
129 {
130  if (isLocalSceneDirty() &&
131  QMessageBox::question(this, "Update PlanningScene",
132  "You have local changes to your planning scene.\n"
133  "Publish them to the move_group node?",
134  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
135  publishScene();
136 }
137 
139 {
140  if (auto ps = planning_display_->getPlanningSceneRW())
141  {
142  ps->getWorldNonConst()->clearObjects();
143  ps->getCurrentStateNonConst().clearAttachedBodies();
144  setLocalSceneEdited(true);
145  planning_display_->updateQueryStates(ps->getCurrentState());
146  populateCollisionObjectsList(&ps); // update list + internal vars
148  }
149 }
150 
152 {
153  const double scaling_factor = (double)value / 100.0; // The GUI slider gives percent values
154  if (scaled_object_)
155  {
157  if (ps)
158  {
159  if (ps->getWorld()->hasObject(scaled_object_->id_))
160  {
161  ps->getWorldNonConst()->removeObject(scaled_object_->id_);
162  for (std::size_t i = 0; i < scaled_object_->shapes_.size(); ++i)
163  {
164  shapes::Shape* s = scaled_object_->shapes_[i]->clone();
165  s->scale(scaling_factor);
166 
167  Eigen::Isometry3d scaled_shape_pose = scaled_object_->shape_poses_[i];
168  scaled_shape_pose.translation() *= scaling_factor;
169 
170  ps->getWorldNonConst()->addToObject(scaled_object_->id_, scaled_object_->pose_, shapes::ShapeConstPtr(s),
171  scaled_shape_pose);
172  }
173  moveit::core::FixedTransformsMap scaled_subframes = scaled_object_->subframe_poses_;
174  for (auto& subframe_pair : scaled_subframes)
175  subframe_pair.second.translation() *= scaling_factor;
176 
177  ps->getWorldNonConst()->setSubframesOfObject(scaled_object_->id_, scaled_subframes);
179  if (scene_marker_)
180  scene_marker_->processMessage(createObjectMarkerMsg(ps->getWorld()->getObject(scaled_object_->id_)));
182  }
183  else
184  scaled_object_.reset();
185  }
186  else
187  scaled_object_.reset();
188  }
189 }
190 
192 {
193  auto current = ui_->collision_objects_list->currentItem();
194  if (!current)
195  return;
196  if (planning_display_->getPlanningSceneMonitor() && current->checkState() == Qt::Unchecked)
197  {
199  if (ps)
200  {
201  scaled_object_ = ps->getWorld()->getObject(current->text().toStdString());
202  scaled_object_subframes_ = scaled_object_->subframe_poses_;
204  }
205  }
206 }
207 
209 {
210  scaled_object_.reset();
211  ui_->scene_scale->setSliderPosition(100);
212 }
213 
215 {
216  QList<QListWidgetItem*> selection = ui_->collision_objects_list->selectedItems();
217  if (selection.empty())
218  return;
219 
220  if (auto ps = planning_display_->getPlanningSceneRW())
221  {
222  bool removed_attached = false;
223  for (QListWidgetItem* item : selection)
224  if (item->checkState() == Qt::Unchecked)
225  ps->getWorldNonConst()->removeObject(item->text().toStdString());
226  else
227  {
228  ps->getCurrentStateNonConst().clearAttachedBody(item->text().toStdString());
229  removed_attached = true;
230  }
231 
232  if (removed_attached)
233  planning_display_->updateQueryStates(ps->getCurrentState());
234 
236  }
237  scene_marker_.reset();
240 }
241 
243 {
244  QString status_text = "'" + QString::fromStdString(obj->id_) + "' is a collision object with ";
245  if (obj->shapes_.empty())
246  status_text += "no geometry";
247  else
248  {
249  std::vector<QString> shape_names;
250  for (const shapes::ShapeConstPtr& shape : obj->shapes_)
251  shape_names.push_back(QString::fromStdString(shapes::shapeStringName(shape.get())));
252  if (shape_names.size() == 1)
253  status_text += "one " + shape_names[0];
254  else
255  {
256  status_text += QString::fromStdString(boost::lexical_cast<std::string>(shape_names.size())) + " shapes:";
257  for (const QString& shape_name : shape_names)
258  status_text += " " + shape_name;
259  }
260  status_text += ".";
261  }
262  if (!obj->subframe_poses_.empty())
263  {
264  status_text += subframe_poses_to_qstring(obj->subframe_poses_);
265  }
266  return status_text;
267 }
268 
269 static QString decideStatusText(const moveit::core::AttachedBody* attached_body)
270 {
271  QString status_text = "'" + QString::fromStdString(attached_body->getName()) + "' is attached to '" +
272  QString::fromStdString(attached_body->getAttachedLinkName()) + "'.";
273  if (!attached_body->getSubframes().empty())
274  {
275  status_text += subframe_poses_to_qstring(attached_body->getSubframes());
276  }
277  return status_text;
278 }
279 
281 {
282  auto setValue = [](QDoubleSpinBox* w, float value) { // NOLINT(readability-identifier-naming)
283  QSignalBlocker block(w);
284  w->setValue(value);
285  };
286 
287  auto current = ui_->collision_objects_list->currentItem();
288  if (!current)
289  {
290  setValue(ui_->object_x, 0.0);
291  setValue(ui_->object_y, 0.0);
292  setValue(ui_->object_z, 0.0);
293  setValue(ui_->object_rx, 0.0);
294  setValue(ui_->object_ry, 0.0);
295  setValue(ui_->object_rz, 0.0);
296  ui_->object_status->setText("");
297  scene_marker_.reset();
298  ui_->pose_scale_group_box->setEnabled(false);
299  }
301  {
302  // if this is a CollisionWorld element
303  if (current->checkState() == Qt::Unchecked)
304  {
305  ui_->pose_scale_group_box->setEnabled(true);
306  bool update_scene_marker = false;
307  Eigen::Isometry3d obj_pose;
308  {
309  const auto& ps = planning_display_->getPlanningSceneRO();
310  if (const auto& obj = ps->getWorld()->getObject(current->text().toStdString()))
311  {
312  ui_->object_status->setText(decideStatusText(obj));
313  obj_pose = obj->pose_; // valid isometry by contract
314  Eigen::Vector3d xyz = obj_pose.linear().eulerAngles(0, 1, 2);
315  update_scene_marker = true; // do the marker update outside locked scope to avoid deadlock
316  setValue(ui_->object_x, obj_pose.translation()[0]);
317  setValue(ui_->object_y, obj_pose.translation()[1]);
318  setValue(ui_->object_z, obj_pose.translation()[2]);
319  setValue(ui_->object_rx, xyz[0]);
320  setValue(ui_->object_ry, xyz[1]);
321  setValue(ui_->object_rz, xyz[2]);
322  }
323  else
324  ui_->object_status->setText("ERROR: '" + current->text() + "' should be a collision object but it is not");
325  }
326  if (update_scene_marker && ui_->tabWidget->tabText(ui_->tabWidget->currentIndex()).toStdString() == TAB_OBJECTS)
327  {
329  }
330  }
331  else
332  {
333  ui_->pose_scale_group_box->setEnabled(false);
334  // if it is an attached object
335  scene_marker_.reset();
337  const moveit::core::AttachedBody* attached_body =
338  ps->getCurrentState().getAttachedBody(current->text().toStdString());
339  if (attached_body)
340  ui_->object_status->setText(decideStatusText(attached_body));
341  else
342  ui_->object_status->setText("ERROR: '" + current->text() + "' should be an attached object but it is not");
343  }
344  }
345 }
346 
348 {
350 }
351 
352 void MotionPlanningFrame::updateCollisionObjectPose(bool update_marker_position)
353 {
354  auto current = ui_->collision_objects_list->currentItem();
355  if (!current)
356  return;
357  if (auto ps = planning_display_->getPlanningSceneRW())
358  {
359  const std::string object_id = current->text().toStdString();
360  if (ps->getWorld()->hasObject(object_id))
361  {
362  Eigen::Isometry3d p;
363  p.translation()[0] = ui_->object_x->value();
364  p.translation()[1] = ui_->object_y->value();
365  p.translation()[2] = ui_->object_z->value();
366 
367  p = Eigen::Translation3d(p.translation()) *
368  (Eigen::AngleAxisd(ui_->object_rx->value(), Eigen::Vector3d::UnitX()) *
369  Eigen::AngleAxisd(ui_->object_ry->value(), Eigen::Vector3d::UnitY()) *
370  Eigen::AngleAxisd(ui_->object_rz->value(), Eigen::Vector3d::UnitZ()));
371 
372  ps->getWorldNonConst()->setObjectPose(object_id, p);
375 
376  // Update the interactive marker pose to match the manually introduced one
377  if (update_marker_position && scene_marker_)
378  {
379  // p is isometry by construction
380  Eigen::Quaterniond eq(p.linear());
381  scene_marker_->setPose(Ogre::Vector3(ui_->object_x->value(), ui_->object_y->value(), ui_->object_z->value()),
382  Ogre::Quaternion(eq.w(), eq.x(), eq.y(), eq.z()), "");
383  }
384  }
385  }
386 }
387 
389 {
390  if (item->type() < (int)known_collision_objects_.size() && planning_display_->getPlanningSceneMonitor())
391  {
392  // if we have a name change
393  if (known_collision_objects_[item->type()].first != item->text().toStdString())
394  renameCollisionObject(item);
395  else
396  {
397  bool checked = item->checkState() == Qt::Checked;
398  if (known_collision_objects_[item->type()].second != checked)
400  }
401  }
402 }
403 
404 /* Receives feedback from the interactive marker and updates the shape pose in the world accordingly */
405 void MotionPlanningFrame::imProcessFeedback(visualization_msgs::InteractiveMarkerFeedback& feedback)
406 {
407  bool old_state = ui_->object_x->blockSignals(true);
408  ui_->object_x->setValue(feedback.pose.position.x);
409  ui_->object_x->blockSignals(old_state);
410 
411  old_state = ui_->object_y->blockSignals(true);
412  ui_->object_y->setValue(feedback.pose.position.y);
413  ui_->object_y->blockSignals(old_state);
414 
415  old_state = ui_->object_z->blockSignals(true);
416  ui_->object_z->setValue(feedback.pose.position.z);
417  ui_->object_z->blockSignals(old_state);
418 
419  Eigen::Quaterniond q;
420  tf2::fromMsg(feedback.pose.orientation, q);
421  Eigen::Vector3d xyz = q.matrix().eulerAngles(0, 1, 2);
422 
423  old_state = ui_->object_rx->blockSignals(true);
424  ui_->object_rx->setValue(xyz[0]);
425  ui_->object_rx->blockSignals(old_state);
426 
427  old_state = ui_->object_ry->blockSignals(true);
428  ui_->object_ry->setValue(xyz[1]);
429  ui_->object_ry->blockSignals(old_state);
430 
431  old_state = ui_->object_rz->blockSignals(true);
432  ui_->object_rz->setValue(xyz[2]);
433  ui_->object_rz->blockSignals(old_state);
434 
436 }
437 
439 {
440  QList<QListWidgetItem*> sel = ui_->collision_objects_list->selectedItems();
441  if (sel.empty())
442  return;
443 
445  if (!ps)
446  return;
447 
448  for (const QListWidgetItem* item : sel)
449  {
450  std::string name = item->text().toStdString();
451  collision_detection::CollisionEnv::ObjectConstPtr obj = ps->getWorld()->getObject(name);
452  if (!obj)
453  continue;
454 
455  // find a name for the copy
456  name.insert(0, "Copy of ");
457  if (ps->getWorld()->hasObject(name))
458  {
459  name += " ";
460  unsigned int n = 1;
461  while (ps->getWorld()->hasObject(name + boost::lexical_cast<std::string>(n)))
462  n++;
463  name += boost::lexical_cast<std::string>(n);
464  }
465  ps->getWorldNonConst()->addToObject(name, obj->shapes_, obj->shape_poses_);
466  ROS_DEBUG("Copied collision object to '%s'", name.c_str());
467  }
470 }
471 
473 {
475  {
476  moveit_msgs::PlanningScene msg;
477  planning_display_->getPlanningSceneRO()->getPlanningSceneMsg(msg);
478  try
479  {
480  planning_scene_storage_->removePlanningScene(msg.name);
481  planning_scene_storage_->addPlanningScene(msg);
482  }
483  catch (std::exception& ex)
484  {
485  ROS_ERROR("%s", ex.what());
486  }
487 
489  }
490 }
491 
492 void MotionPlanningFrame::computeSaveQueryButtonClicked(const std::string& scene, const std::string& query_name)
493 {
494  moveit_msgs::MotionPlanRequest mreq;
497  {
498  try
499  {
500  if (!query_name.empty())
501  planning_scene_storage_->removePlanningQuery(scene, query_name);
502  planning_scene_storage_->addPlanningQuery(mreq, scene, query_name);
503  }
504  catch (std::exception& ex)
505  {
506  ROS_ERROR("%s", ex.what());
507  }
508 
510  }
511 }
512 
514 {
516  {
517  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
518  if (!sel.empty())
519  {
520  QTreeWidgetItem* s = sel.front();
521  if (s->type() == ITEM_TYPE_SCENE)
522  {
523  std::string scene = s->text(0).toStdString();
524  try
525  {
526  planning_scene_storage_->removePlanningScene(scene);
527  }
528  catch (std::exception& ex)
529  {
530  ROS_ERROR("%s", ex.what());
531  }
532  }
533  else
534  {
535  // if we selected a query name, then we overwrite that query
536  std::string scene = s->parent()->text(0).toStdString();
537  try
538  {
539  planning_scene_storage_->removePlanningScene(scene);
540  }
541  catch (std::exception& ex)
542  {
543  ROS_ERROR("%s", ex.what());
544  }
545  }
547  }
548  }
549 }
550 
552 {
554  {
555  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
556  if (!sel.empty())
557  {
558  QTreeWidgetItem* s = sel.front();
559  if (s->type() == ITEM_TYPE_QUERY)
560  {
561  std::string scene = s->parent()->text(0).toStdString();
562  std::string query_name = s->text(0).toStdString();
563  try
564  {
565  planning_scene_storage_->removePlanningQuery(scene, query_name);
566  }
567  catch (std::exception& ex)
568  {
569  ROS_ERROR("%s", ex.what());
570  }
572  }
573  }
574  }
575 }
576 
578 {
579  ui_->planning_scene_tree->setUpdatesEnabled(false);
580  s->parent()->removeChild(s);
581  ui_->planning_scene_tree->setUpdatesEnabled(true);
582 }
583 
585 {
586  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
587  if (sel.empty())
588  {
589  ui_->load_scene_button->setEnabled(false);
590  ui_->load_query_button->setEnabled(false);
591  ui_->save_query_button->setEnabled(false);
592  ui_->delete_scene_button->setEnabled(false);
593  }
594  else
595  {
596  ui_->save_query_button->setEnabled(true);
597 
598  QTreeWidgetItem* s = sel.front();
599 
600  // if the item is a PlanningScene
601  if (s->type() == ITEM_TYPE_SCENE)
602  {
603  ui_->load_scene_button->setEnabled(true);
604  ui_->load_query_button->setEnabled(false);
605  ui_->delete_scene_button->setEnabled(true);
606  ui_->delete_query_button->setEnabled(false);
607  ui_->save_query_button->setEnabled(true);
608  }
609  else
610  {
611  // if the item is a query
612  ui_->load_scene_button->setEnabled(false);
613  ui_->load_query_button->setEnabled(true);
614  ui_->delete_scene_button->setEnabled(false);
615  ui_->delete_query_button->setEnabled(true);
616  }
617  }
618 }
619 
621 {
623  {
624  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
625  if (!sel.empty())
626  {
627  QTreeWidgetItem* s = sel.front();
628  if (s->type() == ITEM_TYPE_SCENE)
629  {
630  std::string scene = s->text(0).toStdString();
631  ROS_DEBUG("Attempting to load scene '%s'", scene.c_str());
633  bool got_ps = false;
634  try
635  {
636  got_ps = planning_scene_storage_->getPlanningScene(scene_m, scene);
637  }
638  catch (std::exception& ex)
639  {
640  ROS_ERROR("%s", ex.what());
641  }
642 
643  if (got_ps)
644  {
645  ROS_INFO("Loaded scene '%s'", scene.c_str());
647  {
648  if (scene_m->robot_model_name != planning_display_->getRobotModel()->getName())
649  {
650  ROS_INFO("Scene '%s' was saved for robot '%s' but we are using robot '%s'. Using scene geometry only",
651  scene.c_str(), scene_m->robot_model_name.c_str(),
652  planning_display_->getRobotModel()->getName().c_str());
654  // publish the parts that are not in the world
655  moveit_msgs::PlanningScene diff;
656  diff.is_diff = true;
657  diff.name = scene_m->name;
659  }
660  else
661  planning_scene_publisher_.publish(static_cast<const moveit_msgs::PlanningScene&>(*scene_m));
662  }
663  else
664  planning_scene_publisher_.publish(static_cast<const moveit_msgs::PlanningScene&>(*scene_m));
665  }
666  else
667  ROS_WARN("Failed to load scene '%s'. Has the message format changed since the scene was saved?",
668  scene.c_str());
669  }
670  }
671  }
672 }
673 
675 {
677  {
678  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
679  if (!sel.empty())
680  {
681  QTreeWidgetItem* s = sel.front();
682  if (s->type() == ITEM_TYPE_QUERY)
683  {
684  std::string scene = s->parent()->text(0).toStdString();
685  std::string query_name = s->text(0).toStdString();
687  bool got_q = false;
688  try
689  {
690  got_q = planning_scene_storage_->getPlanningQuery(mp, scene, query_name);
691  }
692  catch (std::exception& ex)
693  {
694  ROS_ERROR("%s", ex.what());
695  }
696 
697  if (got_q)
698  {
699  moveit::core::RobotStatePtr start_state(
702  mp->start_state, *start_state);
703  planning_display_->setQueryStartState(*start_state);
704 
705  moveit::core::RobotStatePtr goal_state(new moveit::core::RobotState(*planning_display_->getQueryGoalState()));
706  for (const moveit_msgs::Constraints& goal_constraint : mp->goal_constraints)
707  if (!goal_constraint.joint_constraints.empty())
708  {
709  std::map<std::string, double> vals;
710  for (const moveit_msgs::JointConstraint& joint_constraint : goal_constraint.joint_constraints)
711  vals[joint_constraint.joint_name] = joint_constraint.position;
712  goal_state->setVariablePositions(vals);
713  break;
714  }
715  planning_display_->setQueryGoalState(*goal_state);
716  }
717  else
718  ROS_ERROR("Failed to load planning query '%s'. Has the message format changed since the query was saved?",
719  query_name.c_str());
720  }
721  }
722  }
723 }
724 
725 visualization_msgs::InteractiveMarker
727 {
728  Eigen::Vector3d center = Eigen::Vector3d::Zero();
729  double scale = 0.2;
730 
731  if (!obj->shapes_.empty())
732  shapes::computeShapeBoundingSphere(obj->shapes_[0].get(), center, scale);
733  geometry_msgs::PoseStamped shape_pose = tf2::toMsg(
735  scale = (scale + center.cwiseAbs().maxCoeff()) * 2.0 * 1.2; // add padding of 20% size
736 
737  // create an interactive marker msg for the given shape
738  visualization_msgs::InteractiveMarker imarker =
739  robot_interaction::make6DOFMarker("marker_scene_object", shape_pose, scale);
740  imarker.description = obj->id_;
742  return imarker;
743 }
744 
746 {
747  auto current = ui_->collision_objects_list->currentItem();
748  if (!current)
749  return;
750 
752  if (!ps)
753  return;
754 
755  if (const auto& obj = ps->getWorld()->getObject(current->text().toStdString()))
756  {
757  scene_marker_ = std::make_shared<rviz::InteractiveMarker>(planning_display_->getSceneNode(), context_);
758  scene_marker_->processMessage(createObjectMarkerMsg(obj));
759  scene_marker_->setShowAxes(false);
760 
761  // Connect signals
762  connect(scene_marker_.get(), SIGNAL(userFeedback(visualization_msgs::InteractiveMarkerFeedback&)), this,
763  SLOT(imProcessFeedback(visualization_msgs::InteractiveMarkerFeedback&)));
764  }
765  else
766  {
767  scene_marker_.reset();
768  }
769 }
770 
772 {
773  long unsigned int version = known_collision_objects_version_;
774  if (item->text().isEmpty())
775  {
776  QMessageBox::warning(this, "Invalid object name", "Cannot set an empty object name.");
778  item->setText(QString::fromStdString(known_collision_objects_[item->type()].first));
779  return;
780  }
781 
782  std::string item_text = item->text().toStdString();
783  bool already_exists = planning_display_->getPlanningSceneRO()->getWorld()->hasObject(item_text);
784  if (!already_exists)
785  already_exists = planning_display_->getPlanningSceneRO()->getCurrentState().hasAttachedBody(item_text);
786  if (already_exists)
787  {
788  QMessageBox::warning(this, "Duplicate object name",
789  QString("The name '")
790  .append(item->text())
791  .append("' already exists. Not renaming object ")
792  .append((known_collision_objects_[item->type()].first.c_str())));
794  item->setText(QString::fromStdString(known_collision_objects_[item->type()].first));
795  return;
796  }
797 
798  if (item->checkState() == Qt::Unchecked)
799  {
802  ps->getWorld()->getObject(known_collision_objects_[item->type()].first);
803  if (obj)
804  {
805  known_collision_objects_[item->type()].first = item_text;
806  ps->getWorldNonConst()->removeObject(obj->id_);
807  ps->getWorldNonConst()->addToObject(known_collision_objects_[item->type()].first, obj->pose_, obj->shapes_,
808  obj->shape_poses_);
809  ps->getWorldNonConst()->setSubframesOfObject(obj->id_, obj->subframe_poses_);
810  if (scene_marker_)
811  {
812  scene_marker_.reset();
814  }
815  }
816  }
817  else
818  {
819  // rename attached body
821  moveit::core::RobotState& cs = ps->getCurrentStateNonConst();
822  const moveit::core::AttachedBody* ab = cs.getAttachedBody(known_collision_objects_[item->type()].first);
823  if (ab)
824  {
825  known_collision_objects_[item->type()].first = item_text;
826  auto new_ab = std::make_unique<moveit::core::AttachedBody>(
827  ab->getAttachedLink(), known_collision_objects_[item->type()].first, ab->getPose(), ab->getShapes(),
828  ab->getShapePoses(), ab->getTouchLinks(), ab->getDetachPosture(), ab->getSubframes());
829  cs.clearAttachedBody(ab->getName());
830  cs.attachBody(std::move(new_ab));
831  }
832  }
834 }
835 
837 {
838  long unsigned int version = known_collision_objects_version_;
839  bool checked = item->checkState() == Qt::Checked;
840  std::pair<std::string, bool> data = known_collision_objects_[item->type()];
841  moveit_msgs::AttachedCollisionObject aco;
842 
843  if (checked) // we need to attach a known collision object
844  {
845  QStringList links;
846  const std::vector<std::string>& links_std = planning_display_->getRobotModel()->getLinkModelNames();
847  for (const std::string& link : links_std)
848  links.append(QString::fromStdString(link));
849  bool ok = false;
850  QString response =
851  QInputDialog::getItem(this, tr("Select Link Name"), tr("Choose the link to attach to:"), links, 0, false, &ok);
852  if (!ok)
853  {
855  item->setCheckState(Qt::Unchecked);
856  return;
857  }
858  aco.link_name = response.toStdString();
859  aco.object.id = data.first;
860  aco.object.operation = moveit_msgs::CollisionObject::ADD;
861  }
862  else // we need to detach an attached object
863  {
865  const moveit::core::AttachedBody* attached_body = ps->getCurrentState().getAttachedBody(data.first);
866  if (attached_body)
867  {
868  aco.link_name = attached_body->getAttachedLinkName();
869  aco.object.id = attached_body->getName();
870  aco.object.operation = moveit_msgs::CollisionObject::REMOVE;
871  }
872  }
873 
875  {
877  // we loop through the list in case updates were received since the start of the function
878  for (std::pair<std::string, bool>& known_collision_object : known_collision_objects_)
879  if (known_collision_object.first == data.first)
880  {
881  known_collision_object.second = checked;
882  break;
883  }
884  ps->processAttachedCollisionObjectMsg(aco);
885  rs = ps->getCurrentState();
886  }
887 
892 }
893 
894 QListWidgetItem* MotionPlanningFrame::addCollisionObjectToList(const std::string& name, int row, bool attached)
895 {
896  QListWidgetItem* item = new QListWidgetItem(QString::fromStdString(name), ui_->collision_objects_list, row);
897  item->setFlags(item->flags() | Qt::ItemIsEditable);
898  item->setToolTip(item->text());
899  item->setCheckState(attached ? Qt::Checked : Qt::Unchecked);
900  known_collision_objects_.push_back(std::make_pair(name, attached));
901  return item;
902 }
903 
905 {
906  ui_->collision_objects_list->setUpdatesEnabled(false);
907  bool octomap_in_scene = false;
908 
909  {
910  QSignalBlocker block(ui_->collision_objects_list);
911 
912  QString current_item_text; // remember current item to restore it later
913  if (auto* item = ui_->collision_objects_list->currentItem())
914  current_item_text = item->text();
915  QListWidgetItem* current_item = nullptr;
916 
917  std::set<std::string> to_select; // remember current selections to restore it later
918  QList<QListWidgetItem*> sel = ui_->collision_objects_list->selectedItems();
919  for (QListWidgetItem* item : sel)
920  to_select.insert(item->text().toStdString());
921  ui_->collision_objects_list->clear();
922  known_collision_objects_.clear();
924 
925  auto ps = pps ? *pps : planning_display_->getPlanningSceneRO();
926  if (ps)
927  {
928  for (const std::string& name : ps->getWorld()->getObjectIds())
929  {
931  {
932  octomap_in_scene = true;
933  continue;
934  }
935  QListWidgetItem* item = addCollisionObjectToList(name, ui_->collision_objects_list->count(), false);
936  if (to_select.find(name) != to_select.end())
937  item->setSelected(true);
938  if (!current_item && !current_item_text.isEmpty() && item->text() == current_item_text)
939  current_item = item;
940  }
941 
942  std::vector<const moveit::core::AttachedBody*> attached_bodies;
943  ps->getCurrentState().getAttachedBodies(attached_bodies);
944  for (const auto& body : attached_bodies)
945  {
946  QListWidgetItem* item = addCollisionObjectToList(body->getName(), ui_->collision_objects_list->count(), true);
947  if (to_select.find(body->getName()) != to_select.end())
948  item->setSelected(true);
949  }
950  }
951  ui_->collision_objects_list->setCurrentItem(current_item);
952  }
953 
954  ui_->clear_octomap_button->setEnabled(octomap_in_scene);
955  ui_->collision_objects_list->setUpdatesEnabled(true);
957 }
958 
960 {
961  QString path =
962  QFileDialog::getSaveFileName(this, tr("Export Scene Geometry"), tr(""), tr("Scene Geometry (*.scene)"));
963  if (!path.isEmpty())
964  planning_display_->addBackgroundJob([this, path = path.toStdString()] { computeExportGeometryAsText(path); },
965  "export as text");
966 }
967 
969 {
971  if (ps)
972  {
973  std::string p = (path.length() < 7 || path.substr(path.length() - 6) != ".scene") ? path + ".scene" : path;
974  std::ofstream fout(p.c_str());
975  if (fout.good())
976  {
977  ps->saveGeometryToStream(fout);
978  fout.close();
979  ROS_INFO("Saved current scene geometry to '%s'", p.c_str());
980  }
981  else
982  ROS_WARN("Unable to save current scene geometry to '%s'", p.c_str());
983  }
984 }
985 
987 {
988  bool success = false;
989  if (auto ps = planning_display_->getPlanningSceneRW())
990  {
991  std::ifstream fin(path.c_str());
992  if (ps->loadGeometryFromStream(fin))
993  {
994  ROS_INFO("Loaded scene geometry from '%s'", path.c_str());
998  success = true;
999  }
1000  }
1001  if (!success)
1003  QMessageBox::warning(nullptr, "Loading scene geometry",
1004  "Failed to load scene geometry.\n"
1005  "See console output for more details.");
1006  });
1007 }
1008 
1010 {
1011  QString path =
1012  QFileDialog::getOpenFileName(this, tr("Import Scene Geometry"), tr(""), tr("Scene Geometry (*.scene)"));
1013  if (!path.isEmpty())
1014  planning_display_->addBackgroundJob([this, path = path.toStdString()] { computeImportGeometryFromText(path); },
1015  "import from text");
1016 }
1017 } // namespace moveit_rviz_plugin
response
const std::string response
moveit_rviz_plugin::MotionPlanningFrame::sceneScaleChanged
void sceneScaleChanged(int value)
Definition: motion_planning_frame_objects.cpp:151
moveit_rviz_plugin::MotionPlanningFrame::computeSaveQueryButtonClicked
void computeSaveQueryButtonClicked(const std::string &scene, const std::string &query_name)
Definition: motion_planning_frame_objects.cpp:492
moveit::core::AttachedBody::getDetachPosture
const trajectory_msgs::JointTrajectory & getDetachPosture() const
moveit_rviz_plugin::MotionPlanningFrame::sceneScaleEndChange
void sceneScaleEndChange()
Definition: motion_planning_frame_objects.cpp:208
moveit_rviz_plugin::MotionPlanningFrame::computeLoadSceneButtonClicked
void computeLoadSceneButtonClicked()
Definition: motion_planning_frame_objects.cpp:620
moveit_rviz_plugin::MotionPlanningFrame::attachDetachCollisionObject
void attachDetachCollisionObject(QListWidgetItem *item)
Definition: motion_planning_frame_objects.cpp:836
boost::shared_ptr
moveit_rviz_plugin::MotionPlanningFrame::isLocalSceneDirty
bool isLocalSceneDirty() const
Definition: motion_planning_frame_objects.cpp:111
moveit_rviz_plugin::MotionPlanningFrame::createObjectMarkerMsg
visualization_msgs::InteractiveMarker createObjectMarkerMsg(const collision_detection::CollisionEnv::ObjectConstPtr &obj)
Definition: motion_planning_frame_objects.cpp:726
motion_planning_display.h
planning_scene_storage.h
tf2_eigen.h
tf2::fromMsg
void fromMsg(const A &, B &b)
moveit_rviz_plugin::MotionPlanningFrame::scaled_object_subframes_
moveit::core::FixedTransformsMap scaled_object_subframes_
Definition: motion_planning_frame.h:328
s
XmlRpcServer s
moveit_rviz_plugin::MotionPlanningFrame::shapesComboBoxChanged
void shapesComboBoxChanged(const QString &text)
Definition: motion_planning_frame_objects.cpp:76
frame_manager.h
moveit_rviz_plugin::MotionPlanningFrame::exportGeometryAsTextButtonClicked
void exportGeometryAsTextButtonClicked()
Definition: motion_planning_frame_objects.cpp:959
data
data
ROS_DEBUG
#define ROS_DEBUG(...)
moveit::core::AttachedBody::getTouchLinks
const std::set< std::string > & getTouchLinks() const
moveit_rviz_plugin::MotionPlanningFrame::collisionObjectChanged
void collisionObjectChanged(QListWidgetItem *item)
Definition: motion_planning_frame_objects.cpp:388
shape_operations.h
moveit::core::RobotState::getAttachedBody
const AttachedBody * getAttachedBody(const std::string &name) const
tf2::Stamped
moveit_rviz_plugin::MotionPlanningFrame::updateCollisionObjectPose
void updateCollisionObjectPose(bool update_marker_position)
Definition: motion_planning_frame_objects.cpp:352
shapes::SPHERE
SPHERE
moveit_rviz_plugin::PlanningSceneDisplay::getPlanningSceneMonitor
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor()
Definition: planning_scene_display.cpp:300
moveit::core::RobotState
shapes::Shape
tools.h
moveit_rviz_plugin::PlanningSceneDisplay::addMainLoopJob
void addMainLoopJob(const boost::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
Definition: planning_scene_display.cpp:265
robot_interaction::make6DOFMarker
visualization_msgs::InteractiveMarker make6DOFMarker(const std::string &name, const geometry_msgs::PoseStamped &stamped, double scale, bool orientation_fixed=false)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
moveit_rviz_plugin::MotionPlanningFrame::populateCollisionObjectsList
void populateCollisionObjectsList(planning_scene_monitor::LockedPlanningSceneRO *pps=nullptr)
Definition: motion_planning_frame_objects.cpp:904
obj
CollisionObject< S > * obj
ok
ROSCPP_DECL bool ok()
moveit_rviz_plugin::MotionPlanningDisplay::updateQueryStates
void updateQueryStates(const moveit::core::RobotState &current_state)
Definition: motion_planning_display.cpp:1270
shapes::MESH
MESH
moveit_rviz_plugin::MotionPlanningFrame::importGeometryFromTextButtonClicked
void importGeometryFromTextButtonClicked()
Definition: motion_planning_frame_objects.cpp:1009
moveit::core::AttachedBody
planning_scene_monitor::LockedPlanningSceneRW
shapes::CONE
CONE
moveit_rviz_plugin::MotionPlanningFrame::addCollisionObjectToList
QListWidgetItem * addCollisionObjectToList(const std::string &name, int row, bool attached)
Definition: motion_planning_frame_objects.cpp:894
interactive_marker_helpers.h
moveit_rviz_plugin::PlanningSceneDisplay::getPlanningSceneRO
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene
Definition: planning_scene_display.cpp:328
moveit_rviz_plugin::MotionPlanningFrame::planning_scene_world_publisher_
ros::Publisher planning_scene_world_publisher_
Definition: motion_planning_frame.h:325
moveit_rviz_plugin::MotionPlanningFrame::scene_marker_
std::shared_ptr< rviz::InteractiveMarker > scene_marker_
Definition: motion_planning_frame.h:138
moveit_rviz_plugin::MotionPlanningFrame::ui_
Ui::MotionPlanningUI * ui_
Definition: motion_planning_frame.h:127
version
version
moveit_rviz_plugin::MotionPlanningFrame::sceneScaleStartChange
void sceneScaleStartChange()
Definition: motion_planning_frame_objects.cpp:191
moveit_rviz_plugin::MotionPlanningFrame::copySelectedCollisionObjects
void copySelectedCollisionObjects()
Definition: motion_planning_frame_objects.cpp:438
window_manager_interface.h
moveit_rviz_plugin::MotionPlanningFrame::createSceneInteractiveMarker
void createSceneInteractiveMarker()
Definition: motion_planning_frame_objects.cpp:745
moveit_rviz_plugin::MotionPlanningFrame::computeDeleteSceneButtonClicked
void computeDeleteSceneButtonClicked()
Definition: motion_planning_frame_objects.cpp:513
moveit_rviz_plugin::MotionPlanningFrame::planning_scene_storage_
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
Definition: motion_planning_frame.h:134
moveit::core::RobotState::attachBody
void attachBody(std::unique_ptr< AttachedBody > attached_body)
ROS_ERROR
#define ROS_ERROR(...)
moveit_rviz_plugin::MotionPlanningFrame::known_collision_objects_
std::vector< std::pair< std::string, bool > > known_collision_objects_
Definition: motion_planning_frame.h:331
moveit::core::AttachedBody::getSubframes
const moveit::core::FixedTransformsMap & getSubframes() const
moveit_rviz_plugin::decideStatusText
static QString decideStatusText(const collision_detection::CollisionEnv::ObjectConstPtr &obj)
Definition: motion_planning_frame_objects.cpp:242
value
float value
ROS_WARN
#define ROS_WARN(...)
collision_detection::CollisionEnv::ObjectConstPtr
World::ObjectConstPtr ObjectConstPtr
moveit_rviz_plugin::MotionPlanningFrame::known_collision_objects_version_
long unsigned int known_collision_objects_version_
Definition: motion_planning_frame.h:332
moveit::core::FixedTransformsMap
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
moveit_rviz_plugin::MotionPlanningDisplay::getQueryStartState
moveit::core::RobotStateConstPtr getQueryStartState() const
Definition: motion_planning_display.h:99
moveit::core::AttachedBody::getAttachedLink
const LinkModel * getAttachedLink() const
moveit_rviz_plugin::MotionPlanningFrame::planning_scene_publisher_
ros::Publisher planning_scene_publisher_
Definition: motion_planning_frame.h:324
moveit_rviz_plugin::MotionPlanningFrame::computeLoadQueryButtonClicked
void computeLoadQueryButtonClicked()
Definition: motion_planning_frame_objects.cpp:674
name
name
moveit_rviz_plugin::PlanningSceneDisplay::addBackgroundJob
void addBackgroundJob(const boost::function< void()> &job, const std::string &name)
Definition: planning_scene_display.cpp:255
q
q
moveit_rviz_plugin::MotionPlanningFrame::clearScene
void clearScene()
Definition: motion_planning_frame_objects.cpp:138
shapes::shapeStringName
const std::string & shapeStringName(const Shape *shape)
moveit_rviz_plugin::MotionPlanningFrame::scaled_object_
collision_detection::CollisionEnv::ObjectConstPtr scaled_object_
Definition: motion_planning_frame.h:327
moveit_rviz_plugin::MotionPlanningFrame::ITEM_TYPE_SCENE
static const int ITEM_TYPE_SCENE
Definition: motion_planning_frame.h:115
interactive_markers::autoComplete
INTERACTIVE_MARKERS_PUBLIC void autoComplete(const visualization_msgs::InteractiveMarker &msg, visualization_msgs::InteractiveMarkerControl &control, bool enable_autocomplete_transparency=true)
moveit_rviz_plugin::MotionPlanningFrame::imProcessFeedback
void imProcessFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
Definition: motion_planning_frame_objects.cpp:405
moveit_rviz_plugin::MotionPlanningFrame::ITEM_TYPE_QUERY
static const int ITEM_TYPE_QUERY
Definition: motion_planning_frame.h:116
moveit_rviz_plugin::MotionPlanningFrame::computeDeleteQueryButtonClickedHelper
void computeDeleteQueryButtonClickedHelper(QTreeWidgetItem *s)
Definition: motion_planning_frame_objects.cpp:577
moveit_rviz_plugin
Definition: motion_planning_display.h:80
moveit_rviz_plugin::MotionPlanningFrame::currentCollisionObjectChanged
void currentCollisionObjectChanged()
Definition: motion_planning_frame_objects.cpp:280
moveit_rviz_plugin::MotionPlanningDisplay::setQueryStartState
void setQueryStartState(const moveit::core::RobotState &start)
Definition: motion_planning_display.cpp:974
moveit_rviz_plugin::TAB_OBJECTS
static const std::string TAB_OBJECTS
Definition: motion_planning_frame.h:91
append
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
ros::Time
moveit_rviz_plugin::MotionPlanningFrame::scaled_object_shape_poses_
EigenSTL::vector_Isometry3d scaled_object_shape_poses_
Definition: motion_planning_frame.h:329
planning_scene_monitor::LockedPlanningSceneRO
moveit::core::RobotState::clearAttachedBody
bool clearAttachedBody(const std::string &id)
moveit_rviz_plugin::MotionPlanningFrame::computeSaveSceneButtonClicked
void computeSaveSceneButtonClicked()
Definition: motion_planning_frame_objects.cpp:472
rviz::Display::getSceneNode
Ogre::SceneNode * getSceneNode() const
moveit::core::AttachedBody::getAttachedLinkName
const std::string & getAttachedLinkName() const
moveit_rviz_plugin::MotionPlanningFrame::computeImportGeometryFromText
void computeImportGeometryFromText(const std::string &path)
Definition: motion_planning_frame_objects.cpp:986
moveit_rviz_plugin::MotionPlanningFrame::constructPlanningRequest
void constructPlanningRequest(moveit_msgs::MotionPlanRequest &mreq)
Definition: motion_planning_frame_planning.cpp:501
moveit_rviz_plugin::MotionPlanningFrame::populatePlanningSceneTreeView
void populatePlanningSceneTreeView()
Definition: motion_planning_frame_scenes.cpp:285
moveit::core::AttachedBody::getShapes
const std::vector< shapes::ShapeConstPtr > & getShapes() const
planning_scene::PlanningScene::OCTOMAP_NS
static const MOVEIT_PLANNING_SCENE_EXPORT std::string OCTOMAP_NS
shapes::CYLINDER
CYLINDER
moveit_rviz_plugin::PlanningSceneDisplay::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: planning_scene_display.cpp:310
moveit_rviz_plugin::MotionPlanningFrame::publishScene
void publishScene()
Definition: motion_planning_frame_objects.cpp:116
moveit_rviz_plugin::MotionPlanningFrame::context_
rviz::DisplayContext * context_
Definition: motion_planning_frame.h:126
tf2::toMsg
B toMsg(const A &a)
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
moveit_rviz_plugin::MotionPlanningFrame::publishSceneIfNeeded
void publishSceneIfNeeded()
Definition: motion_planning_frame_objects.cpp:128
conversions.h
moveit_rviz_plugin::MotionPlanningFrame::planning_display_
MotionPlanningDisplay * planning_display_
Definition: motion_planning_frame.h:125
shapes::computeShapeBoundingSphere
void computeShapeBoundingSphere(const Shape *shape, Eigen::Vector3d &center, double &radius)
moveit_rviz_plugin::MotionPlanningFrame::checkPlanningSceneTreeEnabledButtons
void checkPlanningSceneTreeEnabledButtons()
Definition: motion_planning_frame_objects.cpp:584
moveit_rviz_plugin::MotionPlanningDisplay::setQueryGoalState
void setQueryGoalState(const moveit::core::RobotState &goal)
Definition: motion_planning_display.cpp:980
ROS_INFO
#define ROS_INFO(...)
moveit_rviz_plugin::MotionPlanningFrame::setLocalSceneEdited
void setLocalSceneEdited(bool dirty=true)
Definition: motion_planning_frame_objects.cpp:106
moveit_rviz_plugin::MotionPlanningFrame::computeDeleteQueryButtonClicked
void computeDeleteQueryButtonClicked()
Definition: motion_planning_frame_objects.cpp:551
motion_planning_frame.h
moveit_rviz_plugin::MotionPlanningFrame::removeSceneObjects
void removeSceneObjects()
Definition: motion_planning_frame_objects.cpp:214
moveit::core::AttachedBody::getPose
const Eigen::Isometry3d & getPose() const
moveit_rviz_plugin::MotionPlanningFrame::objectPoseValueChanged
void objectPoseValueChanged(double value)
Definition: motion_planning_frame_objects.cpp:347
shapes::BOX
BOX
moveit::core::AttachedBody::getShapePoses
const EigenSTL::vector_Isometry3d & getShapePoses() const
moveit::core::AttachedBody::getName
const std::string & getName() const
moveit_rviz_plugin::MotionPlanningFrame::computeExportGeometryAsText
void computeExportGeometryAsText(const std::string &path)
Definition: motion_planning_frame_objects.cpp:968
moveit_rviz_plugin::MotionPlanningFrame::renameCollisionObject
void renameCollisionObject(QListWidgetItem *item)
Definition: motion_planning_frame_objects.cpp:771
moveit::core::robotStateMsgToRobotState
bool robotStateMsgToRobotState(const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
moveit_rviz_plugin::MotionPlanningDisplay::getQueryGoalState
moveit::core::RobotStateConstPtr getQueryGoalState() const
Definition: motion_planning_display.h:104
moveit_rviz_plugin::PlanningSceneDisplay::getPlanningSceneRW
planning_scene_monitor::LockedPlanningSceneRW getPlanningSceneRW()
get write access to planning scene
Definition: planning_scene_display.cpp:333
display_context.h
moveit_rviz_plugin::PlanningSceneDisplay::queueRenderSceneGeometry
void queueRenderSceneGeometry()
Definition: planning_scene_display.cpp:658


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Sat Mar 15 2025 02:27:25