moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 */
37 
42 
43 #include <interactive_markers/tools.hpp>
44 
45 #include <rviz_common/display_context.hpp>
46 #include <rviz_common/frame_manager_iface.hpp>
47 #include <rviz_common/window_manager_interface.hpp>
48 
49 #include <tf2_eigen/tf2_eigen.hpp>
50 #include <geometric_shapes/shape_operations.h>
51 
52 #include <QMessageBox>
53 #include <QInputDialog>
54 #include <QFileDialog>
55 
56 #include "ui_motion_planning_rviz_plugin_frame.h"
57 
58 namespace
59 {
60 QString subframe_poses_to_qstring(const moveit::core::FixedTransformsMap& subframes)
61 {
62  QString status_text = "\nIt has the subframes '";
63  for (const auto& subframe : subframes)
64  {
65  status_text += QString::fromStdString(subframe.first) + "', '";
66  }
67  status_text.chop(3);
68  status_text += ".";
69  return status_text;
70 }
71 } // namespace
72 
73 namespace moveit_rviz_plugin
74 {
75 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros_visualization.motion_planning_frame_objects");
76 
77 void MotionPlanningFrame::shapesComboBoxChanged(const QString& /*text*/)
78 {
79  switch (ui_->shapes_combo_box->currentData().toInt()) // fetch shape ID from current combobox item
80  {
81  case shapes::BOX:
82  ui_->shape_size_x_spin_box->setEnabled(true);
83  ui_->shape_size_y_spin_box->setEnabled(true);
84  ui_->shape_size_z_spin_box->setEnabled(true);
85  break;
86  case shapes::SPHERE:
87  ui_->shape_size_x_spin_box->setEnabled(true);
88  ui_->shape_size_y_spin_box->setEnabled(false);
89  ui_->shape_size_z_spin_box->setEnabled(false);
90  break;
91  case shapes::CYLINDER:
92  case shapes::CONE:
93  ui_->shape_size_x_spin_box->setEnabled(true);
94  ui_->shape_size_y_spin_box->setEnabled(false);
95  ui_->shape_size_z_spin_box->setEnabled(true);
96  break;
97  case shapes::MESH:
98  ui_->shape_size_x_spin_box->setEnabled(false);
99  ui_->shape_size_y_spin_box->setEnabled(false);
100  ui_->shape_size_z_spin_box->setEnabled(false);
101  break;
102  default:
103  break;
104  }
105 }
106 
107 void MotionPlanningFrame::setLocalSceneEdited(bool dirty)
108 {
109  ui_->publish_current_scene_button->setEnabled(dirty);
110 }
111 
112 bool MotionPlanningFrame::isLocalSceneDirty() const
113 {
114  return ui_->publish_current_scene_button->isEnabled();
115 }
116 
117 void MotionPlanningFrame::publishScene()
118 {
120  if (ps)
121  {
122  moveit_msgs::msg::PlanningScene msg;
123  ps->getPlanningSceneMsg(msg);
124  planning_scene_publisher_->publish(msg);
125  setLocalSceneEdited(false);
126  }
127 }
128 
129 void MotionPlanningFrame::publishSceneIfNeeded()
130 {
131  if (isLocalSceneDirty() &&
132  QMessageBox::question(this, "Update PlanningScene",
133  "You have local changes to your planning scene.\n"
134  "Publish them to the move_group node?",
135  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
136  publishScene();
137 }
138 
139 void MotionPlanningFrame::clearScene()
140 {
142  if (ps)
143  {
144  ps->getWorldNonConst()->clearObjects();
145  ps->getCurrentStateNonConst().clearAttachedBodies();
146  moveit_msgs::msg::PlanningScene msg;
147  ps->getPlanningSceneMsg(msg);
148  planning_scene_publisher_->publish(msg);
149  setLocalSceneEdited(false);
150  planning_display_->addMainLoopJob([this] { populateCollisionObjectsList(); });
152  }
153 }
154 
155 void MotionPlanningFrame::sceneScaleChanged(int value)
156 {
157  const double scaling_factor = (double)value / 100.0; // The GUI slider gives percent values
158  if (scaled_object_)
159  {
161  if (ps)
162  {
163  if (ps->getWorld()->hasObject(scaled_object_->id_))
164  {
165  ps->getWorldNonConst()->removeObject(scaled_object_->id_);
166  for (std::size_t i = 0; i < scaled_object_->shapes_.size(); ++i)
167  {
168  shapes::Shape* s = scaled_object_->shapes_[i]->clone();
169  s->scale(scaling_factor);
170 
171  Eigen::Isometry3d scaled_shape_pose = scaled_object_->shape_poses_[i];
172  scaled_shape_pose.translation() *= scaling_factor;
173 
174  ps->getWorldNonConst()->addToObject(scaled_object_->id_, scaled_object_->pose_, shapes::ShapeConstPtr(s),
175  scaled_shape_pose);
176  }
177  moveit::core::FixedTransformsMap scaled_subframes = scaled_object_->subframe_poses_;
178  for (auto& subframe_pair : scaled_subframes)
179  subframe_pair.second.translation() *= scaling_factor;
180 
181  ps->getWorldNonConst()->setSubframesOfObject(scaled_object_->id_, scaled_subframes);
182  setLocalSceneEdited();
183  scene_marker_->processMessage(createObjectMarkerMsg(ps->getWorld()->getObject(scaled_object_->id_)));
185  }
186  else
187  scaled_object_.reset();
188  }
189  else
190  scaled_object_.reset();
191  }
192 }
193 
194 void MotionPlanningFrame::sceneScaleStartChange()
195 {
196  QList<QListWidgetItem*> sel = ui_->collision_objects_list->selectedItems();
197  if (sel.empty())
198  return;
199  if (planning_display_->getPlanningSceneMonitor() && sel[0]->checkState() == Qt::Unchecked)
200  {
202  if (ps)
203  {
204  scaled_object_ = ps->getWorld()->getObject(sel[0]->text().toStdString());
205  scaled_object_subframes_ = scaled_object_->subframe_poses_;
206  scaled_object_shape_poses_ = scaled_object_->shape_poses_;
207  }
208  }
209 }
210 
211 void MotionPlanningFrame::sceneScaleEndChange()
212 {
213  scaled_object_.reset();
214  ui_->scene_scale->setSliderPosition(100);
215 }
216 
217 void MotionPlanningFrame::removeSceneObject()
218 {
219  QList<QListWidgetItem*> sel = ui_->collision_objects_list->selectedItems();
220  if (sel.empty())
221  return;
223  if (ps)
224  {
225  for (int i = 0; i < sel.count(); ++i)
226  if (sel[i]->checkState() == Qt::Unchecked)
227  ps->getWorldNonConst()->removeObject(sel[i]->text().toStdString());
228  else
229  ps->getCurrentStateNonConst().clearAttachedBody(sel[i]->text().toStdString());
230  scene_marker_.reset();
231  setLocalSceneEdited();
232  planning_display_->addMainLoopJob([this] { populateCollisionObjectsList(); });
234  }
235 }
236 
237 static QString decideStatusText(const collision_detection::CollisionEnv::ObjectConstPtr& obj)
238 {
239  QString status_text = "'" + QString::fromStdString(obj->id_) + "' is a collision object with ";
240  if (obj->shapes_.empty())
241  status_text += "no geometry";
242  else
243  {
244  std::vector<QString> shape_names;
245  for (const shapes::ShapeConstPtr& shape : obj->shapes_)
246  shape_names.push_back(QString::fromStdString(shapes::shapeStringName(shape.get())));
247  if (shape_names.size() == 1)
248  status_text += "one " + shape_names[0];
249  else
250  {
251  status_text += QString::fromStdString(std::to_string(shape_names.size())) + " shapes:";
252  for (const QString& shape_name : shape_names)
253  status_text += " " + shape_name;
254  }
255  status_text += ".";
256  }
257  if (!obj->subframe_poses_.empty())
258  {
259  status_text += subframe_poses_to_qstring(obj->subframe_poses_);
260  }
261  return status_text;
262 }
263 
264 static QString decideStatusText(const moveit::core::AttachedBody* attached_body)
265 {
266  QString status_text = "'" + QString::fromStdString(attached_body->getName()) + "' is attached to '" +
267  QString::fromStdString(attached_body->getAttachedLinkName()) + "'.";
268  if (!attached_body->getSubframes().empty())
269  {
270  status_text += subframe_poses_to_qstring(attached_body->getSubframes());
271  }
272  return status_text;
273 }
274 
275 void MotionPlanningFrame::selectedCollisionObjectChanged()
276 {
277  QList<QListWidgetItem*> sel = ui_->collision_objects_list->selectedItems();
278  if (sel.empty())
279  {
280  bool old_state = ui_->object_x->blockSignals(true);
281  ui_->object_x->setValue(0.0);
282  ui_->object_x->blockSignals(old_state);
283 
284  old_state = ui_->object_y->blockSignals(true);
285  ui_->object_y->setValue(0.0);
286  ui_->object_y->blockSignals(old_state);
287 
288  old_state = ui_->object_z->blockSignals(true);
289  ui_->object_z->setValue(0.0);
290  ui_->object_z->blockSignals(old_state);
291 
292  old_state = ui_->object_rx->blockSignals(true);
293  ui_->object_rx->setValue(0.0);
294  ui_->object_rx->blockSignals(old_state);
295 
296  old_state = ui_->object_ry->blockSignals(true);
297  ui_->object_ry->setValue(0.0);
298  ui_->object_ry->blockSignals(old_state);
299 
300  old_state = ui_->object_rz->blockSignals(true);
301  ui_->object_rz->setValue(0.0);
302  ui_->object_rz->blockSignals(old_state);
303 
304  ui_->object_status->setText("");
305  scene_marker_.reset();
306  ui_->pose_scale_group_box->setEnabled(false);
307  }
309  {
310  // if this is a CollisionWorld element
311  if (sel[0]->checkState() == Qt::Unchecked)
312  {
313  ui_->pose_scale_group_box->setEnabled(true);
314  bool update_scene_marker = false;
315  Eigen::Isometry3d obj_pose;
316  {
319  ps->getWorld()->getObject(sel[0]->text().toStdString());
320  if (obj)
321  {
322  ui_->object_status->setText(decideStatusText(obj));
323 
324  if (obj->shapes_.size() == 1)
325  {
326  obj_pose = obj->pose_; // valid isometry by contract
327  Eigen::Vector3d xyz = obj_pose.linear().eulerAngles(0, 1, 2);
328  update_scene_marker = true; // do the marker update outside locked scope to avoid deadlock
329 
330  bool old_state = ui_->object_x->blockSignals(true);
331  ui_->object_x->setValue(obj_pose.translation()[0]);
332  ui_->object_x->blockSignals(old_state);
333 
334  old_state = ui_->object_y->blockSignals(true);
335  ui_->object_y->setValue(obj_pose.translation()[1]);
336  ui_->object_y->blockSignals(old_state);
337 
338  old_state = ui_->object_z->blockSignals(true);
339  ui_->object_z->setValue(obj_pose.translation()[2]);
340  ui_->object_z->blockSignals(old_state);
341 
342  old_state = ui_->object_rx->blockSignals(true);
343  ui_->object_rx->setValue(xyz[0]);
344  ui_->object_rx->blockSignals(old_state);
345 
346  old_state = ui_->object_ry->blockSignals(true);
347  ui_->object_ry->setValue(xyz[1]);
348  ui_->object_ry->blockSignals(old_state);
349 
350  old_state = ui_->object_rz->blockSignals(true);
351  ui_->object_rz->setValue(xyz[2]);
352  ui_->object_rz->blockSignals(old_state);
353  }
354  }
355  else
356  ui_->object_status->setText("ERROR: '" + sel[0]->text() + "' should be a collision object but it is not");
357  }
358  if (update_scene_marker && ui_->tabWidget->tabText(ui_->tabWidget->currentIndex()).toStdString() == TAB_OBJECTS)
359  {
360  createSceneInteractiveMarker();
361  }
362  }
363  else
364  {
365  ui_->pose_scale_group_box->setEnabled(false);
366  // if it is an attached object
367  scene_marker_.reset();
369  const moveit::core::AttachedBody* attached_body =
370  ps->getCurrentState().getAttachedBody(sel[0]->text().toStdString());
371  if (attached_body)
372  ui_->object_status->setText(decideStatusText(attached_body));
373  else
374  ui_->object_status->setText("ERROR: '" + sel[0]->text() + "' should be an attached object but it is not");
375  }
376  }
377 }
378 
379 void MotionPlanningFrame::objectPoseValueChanged(double /* value */)
380 {
381  updateCollisionObjectPose(true);
382 }
383 
384 void MotionPlanningFrame::updateCollisionObjectPose(bool update_marker_position)
385 {
386  QList<QListWidgetItem*> sel = ui_->collision_objects_list->selectedItems();
387  if (sel.empty())
388  return;
390  if (ps)
391  {
392  collision_detection::CollisionEnv::ObjectConstPtr obj = ps->getWorld()->getObject(sel[0]->text().toStdString());
393  if (obj)
394  {
395  Eigen::Isometry3d p;
396  p.translation()[0] = ui_->object_x->value();
397  p.translation()[1] = ui_->object_y->value();
398  p.translation()[2] = ui_->object_z->value();
399 
400  p = Eigen::Translation3d(p.translation()) *
401  (Eigen::AngleAxisd(ui_->object_rx->value(), Eigen::Vector3d::UnitX()) *
402  Eigen::AngleAxisd(ui_->object_ry->value(), Eigen::Vector3d::UnitY()) *
403  Eigen::AngleAxisd(ui_->object_rz->value(), Eigen::Vector3d::UnitZ()));
404 
405  ps->getWorldNonConst()->setObjectPose(obj->id_, p);
407  setLocalSceneEdited();
408 
409  // Update the interactive marker pose to match the manually introduced one
410  if (update_marker_position && scene_marker_)
411  {
412  // p is isometry by construction
413  Eigen::Quaterniond eq(p.linear());
414  scene_marker_->setPose(Ogre::Vector3(ui_->object_x->value(), ui_->object_y->value(), ui_->object_z->value()),
415  Ogre::Quaternion(eq.w(), eq.x(), eq.y(), eq.z()), "");
416  }
417  }
418  }
419 }
420 
421 void MotionPlanningFrame::collisionObjectChanged(QListWidgetItem* item)
422 {
423  if (item->type() < static_cast<int>(known_collision_objects_.size()) && planning_display_->getPlanningSceneMonitor())
424  {
425  // if we have a name change
426  if (known_collision_objects_[item->type()].first != item->text().toStdString())
427  renameCollisionObject(item);
428  else
429  {
430  bool checked = item->checkState() == Qt::Checked;
431  if (known_collision_objects_[item->type()].second != checked)
432  attachDetachCollisionObject(item);
433  }
434  }
435 }
436 
437 /* Receives feedback from the interactive marker and updates the shape pose in the world accordingly */
438 void MotionPlanningFrame::imProcessFeedback(visualization_msgs::msg::InteractiveMarkerFeedback& feedback)
439 {
440  if (!planning_display_->getPlanningSceneRO()->knowsFrameTransform(feedback.header.frame_id))
441  {
442  RCLCPP_ERROR_STREAM(LOGGER,
443  "Frame `" << feedback.header.frame_id << "` unknown doesn't exists in the planning scene");
444  }
445  Eigen::Isometry3d fixed_frame_t_scene_marker;
446  tf2::fromMsg(feedback.pose, fixed_frame_t_scene_marker);
447  Eigen::Isometry3d model_frame_t_scene_marker =
448  planning_display_->getPlanningSceneRO()->getFrameTransform(feedback.header.frame_id) * fixed_frame_t_scene_marker;
449 
450  bool old_state = ui_->object_x->blockSignals(true);
451  ui_->object_x->setValue(model_frame_t_scene_marker.translation().x());
452  ui_->object_x->blockSignals(old_state);
453 
454  old_state = ui_->object_y->blockSignals(true);
455  ui_->object_y->setValue(model_frame_t_scene_marker.translation().y());
456  ui_->object_y->blockSignals(old_state);
457 
458  old_state = ui_->object_z->blockSignals(true);
459  ui_->object_z->setValue(model_frame_t_scene_marker.translation().z());
460  ui_->object_z->blockSignals(old_state);
461 
462  Eigen::Vector3d xyz = model_frame_t_scene_marker.linear().eulerAngles(0, 1, 2);
463 
464  old_state = ui_->object_rx->blockSignals(true);
465  ui_->object_rx->setValue(xyz[0]);
466  ui_->object_rx->blockSignals(old_state);
467 
468  old_state = ui_->object_ry->blockSignals(true);
469  ui_->object_ry->setValue(xyz[1]);
470  ui_->object_ry->blockSignals(old_state);
471 
472  old_state = ui_->object_rz->blockSignals(true);
473  ui_->object_rz->setValue(xyz[2]);
474  ui_->object_rz->blockSignals(old_state);
475 
476  updateCollisionObjectPose(false);
477 }
478 
479 void MotionPlanningFrame::copySelectedCollisionObject()
480 {
481  QList<QListWidgetItem*> sel = ui_->collision_objects_list->selectedItems();
482  if (sel.empty())
483  return;
484 
486  if (!ps)
487  return;
488 
489  for (const QListWidgetItem* item : sel)
490  {
491  std::string name = item->text().toStdString();
492  collision_detection::CollisionEnv::ObjectConstPtr obj = ps->getWorld()->getObject(name);
493  if (!obj)
494  continue;
495 
496  // find a name for the copy
497  name.insert(0, "Copy of ");
498  if (ps->getWorld()->hasObject(name))
499  {
500  name += " ";
501  unsigned int n = 1;
502  while (ps->getWorld()->hasObject(name + std::to_string(n)))
503  n++;
504  name += std::to_string(n);
505  }
506  ps->getWorldNonConst()->addToObject(name, obj->shapes_, obj->shape_poses_);
507  RCLCPP_DEBUG(LOGGER, "Copied collision object to '%s'", name.c_str());
508  }
509  setLocalSceneEdited();
510  planning_display_->addMainLoopJob([this] { populateCollisionObjectsList(); });
511 }
512 
513 void MotionPlanningFrame::computeSaveSceneButtonClicked()
514 {
516  {
517  moveit_msgs::msg::PlanningScene msg;
518  planning_display_->getPlanningSceneRO()->getPlanningSceneMsg(msg);
519  try
520  {
521  planning_scene_storage_->removePlanningScene(msg.name);
522  planning_scene_storage_->addPlanningScene(msg);
523  }
524  catch (std::exception& ex)
525  {
526  RCLCPP_ERROR(LOGGER, "%s", ex.what());
527  }
528 
529  planning_display_->addMainLoopJob([this] { populatePlanningSceneTreeView(); });
530  }
531 }
532 
533 void MotionPlanningFrame::computeSaveQueryButtonClicked(const std::string& scene, const std::string& query_name)
534 {
538  {
539  try
540  {
541  if (!query_name.empty())
542  planning_scene_storage_->removePlanningQuery(scene, query_name);
543  planning_scene_storage_->addPlanningQuery(mreq, scene, query_name);
544  }
545  catch (std::exception& ex)
546  {
547  RCLCPP_ERROR(LOGGER, "%s", ex.what());
548  }
549 
550  planning_display_->addMainLoopJob([this] { populatePlanningSceneTreeView(); });
551  }
552 }
553 
554 void MotionPlanningFrame::computeDeleteSceneButtonClicked()
555 {
557  {
558  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
559  if (!sel.empty())
560  {
561  QTreeWidgetItem* s = sel.front();
562  if (s->type() == ITEM_TYPE_SCENE)
563  {
564  std::string scene = s->text(0).toStdString();
565  try
566  {
567  planning_scene_storage_->removePlanningScene(scene);
568  }
569  catch (std::exception& ex)
570  {
571  RCLCPP_ERROR(LOGGER, "%s", ex.what());
572  }
573  }
574  else
575  {
576  // if we selected a query name, then we overwrite that query
577  std::string scene = s->parent()->text(0).toStdString();
578  try
579  {
580  planning_scene_storage_->removePlanningScene(scene);
581  }
582  catch (std::exception& ex)
583  {
584  RCLCPP_ERROR(LOGGER, "%s", ex.what());
585  }
586  }
587  planning_display_->addMainLoopJob([this] { populatePlanningSceneTreeView(); });
588  }
589  }
590 }
591 
592 void MotionPlanningFrame::computeDeleteQueryButtonClicked()
593 {
595  {
596  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
597  if (!sel.empty())
598  {
599  QTreeWidgetItem* s = sel.front();
600  if (s->type() == ITEM_TYPE_QUERY)
601  {
602  std::string scene = s->parent()->text(0).toStdString();
603  std::string query_name = s->text(0).toStdString();
604  try
605  {
606  planning_scene_storage_->removePlanningQuery(scene, query_name);
607  }
608  catch (std::exception& ex)
609  {
610  RCLCPP_ERROR(LOGGER, "%s", ex.what());
611  }
612  planning_display_->addMainLoopJob([this, s] { computeDeleteQueryButtonClickedHelper(s); });
613  }
614  }
615  }
616 }
617 
618 void MotionPlanningFrame::computeDeleteQueryButtonClickedHelper(QTreeWidgetItem* s)
619 {
620  ui_->planning_scene_tree->setUpdatesEnabled(false);
621  s->parent()->removeChild(s);
622  ui_->planning_scene_tree->setUpdatesEnabled(true);
623 }
624 
625 void MotionPlanningFrame::checkPlanningSceneTreeEnabledButtons()
626 {
627  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
628  if (sel.empty())
629  {
630  ui_->load_scene_button->setEnabled(false);
631  ui_->load_query_button->setEnabled(false);
632  ui_->save_query_button->setEnabled(false);
633  ui_->delete_scene_button->setEnabled(false);
634  }
635  else
636  {
637  ui_->save_query_button->setEnabled(true);
638 
639  QTreeWidgetItem* s = sel.front();
640 
641  // if the item is a PlanningScene
642  if (s->type() == ITEM_TYPE_SCENE)
643  {
644  ui_->load_scene_button->setEnabled(true);
645  ui_->load_query_button->setEnabled(false);
646  ui_->delete_scene_button->setEnabled(true);
647  ui_->delete_query_button->setEnabled(false);
648  ui_->save_query_button->setEnabled(true);
649  }
650  else
651  {
652  // if the item is a query
653  ui_->load_scene_button->setEnabled(false);
654  ui_->load_query_button->setEnabled(true);
655  ui_->delete_scene_button->setEnabled(false);
656  ui_->delete_query_button->setEnabled(true);
657  }
658  }
659 }
660 
661 void MotionPlanningFrame::computeLoadSceneButtonClicked()
662 {
664  {
665  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
666  if (!sel.empty())
667  {
668  QTreeWidgetItem* s = sel.front();
669  if (s->type() == ITEM_TYPE_SCENE)
670  {
671  std::string scene = s->text(0).toStdString();
672  RCLCPP_DEBUG(LOGGER, "Attempting to load scene '%s'", scene.c_str());
673 
675  bool got_ps = false;
676  try
677  {
678  got_ps = planning_scene_storage_->getPlanningScene(scene_m, scene);
679  }
680  catch (std::exception& ex)
681  {
682  RCLCPP_ERROR(LOGGER, "%s", ex.what());
683  }
684 
685  if (got_ps)
686  {
687  RCLCPP_INFO(LOGGER, "Loaded scene '%s'", scene.c_str());
689  {
690  if (scene_m->robot_model_name != planning_display_->getRobotModel()->getName())
691  {
692  RCLCPP_INFO(LOGGER,
693  "Scene '%s' was saved for robot '%s' but we are using robot '%s'. Using scene geometry only",
694  scene.c_str(), scene_m->robot_model_name.c_str(),
695  planning_display_->getRobotModel()->getName().c_str());
696  planning_scene_world_publisher_->publish(scene_m->world);
697  // publish the parts that are not in the world
698  moveit_msgs::msg::PlanningScene diff;
699  diff.is_diff = true;
700  diff.name = scene_m->name;
701  planning_scene_publisher_->publish(diff);
702  }
703  else
704  planning_scene_publisher_->publish(static_cast<const moveit_msgs::msg::PlanningScene&>(*scene_m));
705  }
706  else
707  planning_scene_publisher_->publish(static_cast<const moveit_msgs::msg::PlanningScene&>(*scene_m));
708  }
709  else
710  RCLCPP_WARN(LOGGER, "Failed to load scene '%s'. Has the message format changed since the scene was saved?",
711  scene.c_str());
712  }
713  }
714  }
715 }
716 
717 void MotionPlanningFrame::computeLoadQueryButtonClicked()
718 {
720  {
721  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
722  if (!sel.empty())
723  {
724  QTreeWidgetItem* s = sel.front();
725  if (s->type() == ITEM_TYPE_QUERY)
726  {
727  std::string scene = s->parent()->text(0).toStdString();
728  std::string query_name = s->text(0).toStdString();
729 
731  bool got_q = false;
732  try
733  {
734  got_q = planning_scene_storage_->getPlanningQuery(mp, scene, query_name);
735  }
736  catch (std::exception& ex)
737  {
738  RCLCPP_ERROR(LOGGER, "%s", ex.what());
739  }
740 
741  if (got_q)
742  {
743  moveit::core::RobotStatePtr start_state(
746  mp->start_state, *start_state);
747  planning_display_->setQueryStartState(*start_state);
748 
749  auto goal_state = std::make_shared<moveit::core::RobotState>(*planning_display_->getQueryGoalState());
750  for (const moveit_msgs::msg::Constraints& goal_constraint : mp->goal_constraints)
751  if (!goal_constraint.joint_constraints.empty())
752  {
753  std::map<std::string, double> vals;
754  for (const moveit_msgs::msg::JointConstraint& joint_constraint : goal_constraint.joint_constraints)
755  vals[joint_constraint.joint_name] = joint_constraint.position;
756  goal_state->setVariablePositions(vals);
757  break;
758  }
759  planning_display_->setQueryGoalState(*goal_state);
760  }
761  else
762  RCLCPP_ERROR(LOGGER,
763  "Failed to load planning query '%s'. Has the message format changed since the query was saved?",
764  query_name.c_str());
765  }
766  }
767  }
768 }
769 
770 visualization_msgs::msg::InteractiveMarker
771 MotionPlanningFrame::createObjectMarkerMsg(const collision_detection::CollisionEnv::ObjectConstPtr& obj)
772 {
773  Eigen::Vector3d center;
774  double scale;
775  shapes::computeShapeBoundingSphere(obj->shapes_[0].get(), center, scale);
776  geometry_msgs::msg::PoseStamped shape_pose = tf2::toMsg(tf2::Stamped<Eigen::Isometry3d>(
777  obj->pose_, std::chrono::system_clock::now(), planning_display_->getRobotModel()->getModelFrame()));
778  // TODO(felixvd): Consider where to place the object marker.
779  // obj->pose*obj->shape_poses_[0] is backwards compatible, sits on the visible part of
780  // the object, and is more difficult to implement now.
781  // obj->pose is easier to implement and makes more sense.
782  scale = (scale + center.cwiseAbs().maxCoeff()) * 2.0 * 1.2; // add padding of 20% size
783 
784  // create an interactive marker msg for the given shape
785  visualization_msgs::msg::InteractiveMarker imarker =
786  robot_interaction::make6DOFMarker("marker_scene_object", shape_pose, scale);
787  imarker.description = obj->id_;
788  interactive_markers::autoComplete(imarker);
789  return imarker;
790 }
791 
792 void MotionPlanningFrame::createSceneInteractiveMarker()
793 {
794  QList<QListWidgetItem*> sel = ui_->collision_objects_list->selectedItems();
795  if (sel.empty())
796  return;
797 
799  if (!ps)
800  return;
801 
803  ps->getWorld()->getObject(sel[0]->text().toStdString());
804  if (obj && obj->shapes_.size() == 1)
805  {
806  scene_marker_ = std::make_shared<rviz_default_plugins::displays::InteractiveMarker>(
807  planning_display_->getSceneNode(), context_);
808  scene_marker_->processMessage(createObjectMarkerMsg(obj));
809  scene_marker_->setShowAxes(false);
810 
811  // Connect signals
812  connect(scene_marker_.get(), SIGNAL(userFeedback(visualization_msgs::msg::InteractiveMarkerFeedback&)), this,
813  SLOT(imProcessFeedback(visualization_msgs::msg::InteractiveMarkerFeedback&)));
814  }
815  else
816  {
817  scene_marker_.reset();
818  }
819 }
820 
821 void MotionPlanningFrame::renameCollisionObject(QListWidgetItem* item)
822 {
823  long unsigned int version = known_collision_objects_version_;
824  if (item->text().isEmpty())
825  {
826  QMessageBox::warning(this, "Invalid object name", "Cannot set an empty object name.");
827  if (version == known_collision_objects_version_)
828  item->setText(QString::fromStdString(known_collision_objects_[item->type()].first));
829  return;
830  }
831 
832  std::string item_text = item->text().toStdString();
833  bool already_exists = planning_display_->getPlanningSceneRO()->getWorld()->hasObject(item_text);
834  if (!already_exists)
835  already_exists = planning_display_->getPlanningSceneRO()->getCurrentState().hasAttachedBody(item_text);
836  if (already_exists)
837  {
838  QMessageBox::warning(this, "Duplicate object name",
839  QString("The name '")
840  .append(item->text())
841  .append("' already exists. Not renaming object ")
842  .append((known_collision_objects_[item->type()].first.c_str())));
843  if (version == known_collision_objects_version_)
844  item->setText(QString::fromStdString(known_collision_objects_[item->type()].first));
845  return;
846  }
847 
848  if (item->checkState() == Qt::Unchecked)
849  {
852  ps->getWorld()->getObject(known_collision_objects_[item->type()].first);
853  if (obj)
854  {
855  known_collision_objects_[item->type()].first = item_text;
856  ps->getWorldNonConst()->removeObject(obj->id_);
857  ps->getWorldNonConst()->addToObject(known_collision_objects_[item->type()].first, obj->pose_, obj->shapes_,
858  obj->shape_poses_);
859  ps->getWorldNonConst()->setSubframesOfObject(obj->id_, obj->subframe_poses_);
860  if (scene_marker_)
861  {
862  scene_marker_.reset();
863  planning_display_->addMainLoopJob([this] { createSceneInteractiveMarker(); });
864  }
865  }
866  }
867  else
868  {
869  // rename attached body
871  moveit::core::RobotState& cs = ps->getCurrentStateNonConst();
872  const moveit::core::AttachedBody* ab = cs.getAttachedBody(known_collision_objects_[item->type()].first);
873  if (ab)
874  {
875  known_collision_objects_[item->type()].first = item_text;
876  auto new_ab = std::make_unique<moveit::core::AttachedBody>(
877  ab->getAttachedLink(), known_collision_objects_[item->type()].first, ab->getPose(), ab->getShapes(),
878  ab->getShapePoses(), ab->getTouchLinks(), ab->getDetachPosture(), ab->getSubframes());
879  cs.clearAttachedBody(ab->getName());
880  cs.attachBody(std::move(new_ab));
881  }
882  }
883  setLocalSceneEdited();
884 }
885 
886 void MotionPlanningFrame::attachDetachCollisionObject(QListWidgetItem* item)
887 {
888  long unsigned int version = known_collision_objects_version_;
889  bool checked = item->checkState() == Qt::Checked;
890  std::pair<std::string, bool> data = known_collision_objects_[item->type()];
891  moveit_msgs::msg::AttachedCollisionObject aco;
892 
893  if (checked) // we need to attach a known collision object
894  {
895  QStringList links;
896  const std::vector<std::string>& links_std = planning_display_->getRobotModel()->getLinkModelNames();
897  for (const std::string& link : links_std)
898  links.append(QString::fromStdString(link));
899  bool ok = false;
900  QString response =
901  QInputDialog::getItem(this, tr("Select Link Name"), tr("Choose the link to attach to:"), links, 0, false, &ok);
902  if (!ok)
903  {
904  if (version == known_collision_objects_version_)
905  item->setCheckState(Qt::Unchecked);
906  return;
907  }
908  aco.link_name = response.toStdString();
909  aco.object.id = data.first;
910  aco.object.operation = moveit_msgs::msg::CollisionObject::ADD;
911  }
912  else // we need to detach an attached object
913  {
915  const moveit::core::AttachedBody* attached_body = ps->getCurrentState().getAttachedBody(data.first);
916  if (attached_body)
917  {
918  aco.link_name = attached_body->getAttachedLinkName();
919  aco.object.id = attached_body->getName();
920  aco.object.operation = moveit_msgs::msg::CollisionObject::REMOVE;
921  }
922  }
923 
925  {
927  // we loop through the list in case updates were received since the start of the function
928  for (std::pair<std::string, bool>& known_collision_object : known_collision_objects_)
929  if (known_collision_object.first == data.first)
930  {
931  known_collision_object.second = checked;
932  break;
933  }
934  ps->processAttachedCollisionObjectMsg(aco);
935  rs = ps->getCurrentState();
936  }
937 
938  selectedCollisionObjectChanged();
939  setLocalSceneEdited();
942 }
943 
944 void MotionPlanningFrame::populateCollisionObjectsList()
945 {
946  ui_->collision_objects_list->setUpdatesEnabled(false);
947  bool old_state = ui_->collision_objects_list->blockSignals(true);
948  bool octomap_in_scene = false;
949 
950  {
951  QList<QListWidgetItem*> sel = ui_->collision_objects_list->selectedItems();
952  std::set<std::string> to_select;
953  for (QListWidgetItem* item : sel)
954  to_select.insert(item->text().toStdString());
955  ui_->collision_objects_list->clear();
956  known_collision_objects_.clear();
957  known_collision_objects_version_++;
958 
960  if (ps)
961  {
962  const std::vector<std::string>& collision_object_names = ps->getWorld()->getObjectIds();
963  for (std::size_t i = 0; i < collision_object_names.size(); ++i)
964  {
965  if (collision_object_names[i] == planning_scene::PlanningScene::OCTOMAP_NS)
966  {
967  octomap_in_scene = true;
968  continue;
969  }
970 
971  QListWidgetItem* item = new QListWidgetItem(QString::fromStdString(collision_object_names[i]),
972  ui_->collision_objects_list, static_cast<int>(i));
973  item->setFlags(item->flags() | Qt::ItemIsEditable);
974  item->setToolTip(item->text());
975  item->setCheckState(Qt::Unchecked);
976  if (to_select.find(collision_object_names[i]) != to_select.end())
977  item->setSelected(true);
978  ui_->collision_objects_list->addItem(item);
979  known_collision_objects_.push_back(std::make_pair(collision_object_names[i], false));
980  }
981 
982  const moveit::core::RobotState& cs = ps->getCurrentState();
983  std::vector<const moveit::core::AttachedBody*> attached_bodies;
984  cs.getAttachedBodies(attached_bodies);
985  for (std::size_t i = 0; i < attached_bodies.size(); ++i)
986  {
987  QListWidgetItem* item =
988  new QListWidgetItem(QString::fromStdString(attached_bodies[i]->getName()), ui_->collision_objects_list,
989  static_cast<int>(i + collision_object_names.size()));
990  item->setFlags(item->flags() | Qt::ItemIsEditable);
991  item->setToolTip(item->text());
992  item->setCheckState(Qt::Checked);
993  if (to_select.find(attached_bodies[i]->getName()) != to_select.end())
994  item->setSelected(true);
995  ui_->collision_objects_list->addItem(item);
996  known_collision_objects_.push_back(std::make_pair(attached_bodies[i]->getName(), true));
997  }
998  }
999  }
1000 
1001  ui_->clear_octomap_button->setEnabled(octomap_in_scene);
1002  ui_->collision_objects_list->blockSignals(old_state);
1003  ui_->collision_objects_list->setUpdatesEnabled(true);
1004  selectedCollisionObjectChanged();
1005 }
1006 
1007 void MotionPlanningFrame::exportGeometryAsTextButtonClicked()
1008 {
1009  QString path =
1010  QFileDialog::getSaveFileName(this, tr("Export Scene Geometry"), tr(""), tr("Scene Geometry (*.scene)"));
1011  if (!path.isEmpty())
1012  planning_display_->addBackgroundJob([this, path = path.toStdString()] { computeExportGeometryAsText(path); },
1013  "export as text");
1014 }
1015 
1016 void MotionPlanningFrame::computeExportGeometryAsText(const std::string& path)
1017 {
1019  if (ps)
1020  {
1021  std::string p = (path.length() < 7 || path.substr(path.length() - 6) != ".scene") ? path + ".scene" : path;
1022  std::ofstream fout(p.c_str());
1023  if (fout.good())
1024  {
1025  ps->saveGeometryToStream(fout);
1026  fout.close();
1027  RCLCPP_INFO(LOGGER, "Saved current scene geometry to '%s'", p.c_str());
1028  }
1029  else
1030  RCLCPP_WARN(LOGGER, "Unable to save current scene geometry to '%s'", p.c_str());
1031  }
1032 }
1033 
1034 void MotionPlanningFrame::computeImportGeometryFromText(const std::string& path)
1035 {
1037  if (ps)
1038  {
1039  std::ifstream fin(path.c_str());
1040  if (ps->loadGeometryFromStream(fin))
1041  {
1042  RCLCPP_INFO(LOGGER, "Loaded scene geometry from '%s'", path.c_str());
1043  planning_display_->addMainLoopJob([this] { populateCollisionObjectsList(); });
1045  setLocalSceneEdited();
1046  }
1047  else
1048  {
1049  QMessageBox::warning(nullptr, "Loading scene geometry",
1050  "Failed to load scene geometry.\n"
1051  "See console output for more details.");
1052  }
1053  }
1054 }
1055 
1056 void MotionPlanningFrame::importGeometryFromTextButtonClicked()
1057 {
1058  QString path =
1059  QFileDialog::getOpenFileName(this, tr("Import Scene Geometry"), tr(""), tr("Scene Geometry (*.scene)"));
1060  if (!path.isEmpty())
1061  planning_display_->addBackgroundJob([this, path = path.toStdString()] { computeImportGeometryFromText(path); },
1062  "import from text");
1063 }
1064 } // namespace moveit_rviz_plugin
World::ObjectConstPtr ObjectConstPtr
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
Definition: attached_body.h:92
const std::set< std::string > & getTouchLinks() const
Get the links that the attached body is allowed to touch.
const trajectory_msgs::msg::JointTrajectory & getDetachPosture() const
Return the posture that is necessary for the object to be released, (if any). This is useful for exam...
const moveit::core::FixedTransformsMap & getSubframes() const
Get subframes of this object (relative to the object pose). The returned transforms are guaranteed to...
const std::string & getName() const
Get the name of the attached body.
Definition: attached_body.h:74
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
const LinkModel * getAttachedLink() const
Get the model of the link this body is attached to.
Definition: attached_body.h:98
const Eigen::Isometry3d & getPose() const
Get the pose of the attached body relative to the parent link.
Definition: attached_body.h:80
const EigenSTL::vector_Isometry3d & getShapePoses() const
Get the shape poses (the transforms to the shapes of this body, relative to the pose)....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
bool clearAttachedBody(const std::string &id)
Remove the attached body named id. Return false if the object was not found (and thus not removed)....
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return nullptr if not found.
void setQueryGoalState(const moveit::core::RobotState &goal)
void setQueryStartState(const moveit::core::RobotState &start)
void updateQueryStates(const moveit::core::RobotState &current_state)
moveit::core::RobotStateConstPtr getQueryStartState() const
moveit::core::RobotStateConstPtr getQueryGoalState() const
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
std::shared_ptr< rviz_default_plugins::displays::InteractiveMarker > scene_marker_
void constructPlanningRequest(moveit_msgs::msg::MotionPlanRequest &mreq)
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene
planning_scene_monitor::LockedPlanningSceneRW getPlanningSceneRW()
get write access to planning scene
void addMainLoopJob(const std::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
const moveit::core::RobotModelConstPtr & getRobotModel() const
void addBackgroundJob(const std::function< void()> &job, const std::string &name)
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor()
static const std::string OCTOMAP_NS
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
Definition: transforms.h:53
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningScene >::ConstPtr PlanningSceneWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::MotionPlanRequest >::ConstPtr MotionPlanRequestWithMetadata
scene
Definition: pick.py:52
p
Definition: pick.py:62
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
std::string append(const std::string &left, const std::string &right)
visualization_msgs::msg::InteractiveMarker make6DOFMarker(const std::string &name, const geometry_msgs::msg::PoseStamped &stamped, double scale, bool orientation_fixed=false)
version
Definition: setup.py:8
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31