moveit2
The MoveIt Motion Planning Framework for ROS 2.
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Pages
motion_planning_frame_scenes.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 */
39 
45 
46 #include <interactive_markers/tools.hpp>
47 
48 #include <rviz_common/display_context.hpp>
49 #include <rviz_common/window_manager_interface.hpp>
50 
51 #include <QMessageBox>
52 #include <QInputDialog>
53 
54 #include "ui_motion_planning_rviz_plugin_frame.h"
55 
56 #include <memory>
57 
58 namespace moveit_rviz_plugin
59 {
60 
61 void MotionPlanningFrame::saveSceneButtonClicked()
62 {
64  {
65  const std::string& name = planning_display_->getPlanningSceneRO()->getName();
66  if (name.empty() || planning_scene_storage_->hasPlanningScene(name))
67  {
68  std::unique_ptr<QMessageBox> q;
69  if (name.empty())
70  {
71  q = std::make_unique<QMessageBox>(
72  QMessageBox::Question, "Change Planning Scene Name",
73  QString("The name for the planning scene should not be empty. Would you like to rename "
74  "the planning scene?'"),
75  QMessageBox::Cancel, this);
76  }
77  else
78  {
79  q = std::make_unique<QMessageBox>(QMessageBox::Question, "Confirm Planning Scene Overwrite",
80  QString("A planning scene named '")
81  .append(name.c_str())
82  .append("' already exists. Do you wish to "
83  "overwrite that scene?"),
84  QMessageBox::Yes | QMessageBox::No, this);
85  }
86  std::unique_ptr<QPushButton> rename(q->addButton("&Rename", QMessageBox::AcceptRole));
87  if (q->exec() != QMessageBox::Yes)
88  {
89  if (q->clickedButton() == rename.get())
90  {
91  bool ok = false;
92  QString new_name = QInputDialog::getText(this, "Rename Planning Scene",
93  "New name for the planning scene:", QLineEdit::Normal,
94  QString::fromStdString(name), &ok);
95  if (ok)
96  {
97  planning_display_->getPlanningSceneRW()->setName(new_name.toStdString());
98  rviz_common::properties::Property* prop =
99  planning_display_->subProp("Scene Geometry")->subProp("Scene Name");
100  if (prop)
101  {
102  bool old = prop->blockSignals(true);
103  prop->setValue(new_name);
104  prop->blockSignals(old);
105  }
106  saveSceneButtonClicked();
107  }
108  return;
109  }
110  return;
111  }
112  }
113 
114  planning_display_->addBackgroundJob([this] { computeSaveSceneButtonClicked(); }, "save scene");
115  }
116 }
117 
118 void MotionPlanningFrame::planningSceneItemClicked()
119 {
120  checkPlanningSceneTreeEnabledButtons();
121 }
122 
123 void MotionPlanningFrame::saveQueryButtonClicked()
124 {
126  {
127  QList<QTreeWidgetItem*> sel = ui_->planning_scene_tree->selectedItems();
128  if (!sel.empty())
129  {
130  QTreeWidgetItem* s = sel.front();
131 
132  // if we have selected a PlanningScene, add the query as a new one, under that planning scene
133  if (s->type() == ITEM_TYPE_SCENE)
134  {
135  std::string scene = s->text(0).toStdString();
136  planning_display_->addBackgroundJob([this, scene] { computeSaveQueryButtonClicked(scene, ""); }, "save query");
137  }
138  else
139  {
140  // if we selected a query name, then we overwrite that query
141  std::string scene = s->parent()->text(0).toStdString();
142  std::string query_name = s->text(0).toStdString();
143 
144  while (query_name.empty() || planning_scene_storage_->hasPlanningQuery(scene, query_name))
145  {
146  std::unique_ptr<QMessageBox> q;
147  if (query_name.empty())
148  {
149  q = std::make_unique<QMessageBox>(
150  QMessageBox::Question, "Change Planning Query Name",
151  QString("The name for the planning query should not be empty. Would you like to"
152  "rename the planning query?'"),
153  QMessageBox::Cancel, this);
154  }
155  else
156  {
157  q = std::make_unique<QMessageBox>(QMessageBox::Question, "Confirm Planning Query Overwrite",
158  QString("A planning query named '")
159  .append(query_name.c_str())
160  .append("' already exists. Do you wish "
161  "to overwrite that query?"),
162  QMessageBox::Yes | QMessageBox::No, this);
163  }
164  std::unique_ptr<QPushButton> rename(q->addButton("&Rename", QMessageBox::AcceptRole));
165  if (q->exec() == QMessageBox::Yes)
166  {
167  break;
168  }
169  else
170  {
171  if (q->clickedButton() == rename.get())
172  {
173  bool ok = false;
174  QString new_name = QInputDialog::getText(this, "Rename Planning Query",
175  "New name for the planning query:", QLineEdit::Normal,
176  QString::fromStdString(query_name), &ok);
177  if (ok)
178  {
179  query_name = new_name.toStdString();
180  }
181  else
182  {
183  return;
184  }
185  }
186  else
187  return;
188  }
189  }
191  [this, scene, query_name] { computeSaveQueryButtonClicked(scene, query_name); }, "save query");
192  }
193  }
194  }
195 }
196 
197 void MotionPlanningFrame::deleteSceneButtonClicked()
198 {
199  planning_display_->addBackgroundJob([this] { computeDeleteSceneButtonClicked(); }, "delete scene");
200 }
201 
202 void MotionPlanningFrame::deleteQueryButtonClicked()
203 {
204  planning_display_->addBackgroundJob([this] { computeDeleteQueryButtonClicked(); }, "delete query");
205 }
206 
207 void MotionPlanningFrame::loadSceneButtonClicked()
208 {
209  planning_display_->addBackgroundJob([this] { computeLoadSceneButtonClicked(); }, "load scene");
210 }
211 
212 void MotionPlanningFrame::loadQueryButtonClicked()
213 {
214  planning_display_->addBackgroundJob([this] { computeLoadQueryButtonClicked(); }, "load query");
215 }
216 
217 void MotionPlanningFrame::warehouseItemNameChanged(QTreeWidgetItem* item, int column)
218 {
219  if (item->text(column) == item->toolTip(column) || item->toolTip(column).length() == 0)
220  return;
221  moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage = planning_scene_storage_;
222  if (!planning_scene_storage)
223  return;
224 
225  if (item->type() == ITEM_TYPE_SCENE)
226  {
227  std::string new_name = item->text(column).toStdString();
228 
229  if (planning_scene_storage->hasPlanningScene(new_name))
230  {
231  planning_display_->addMainLoopJob([this] { populatePlanningSceneTreeView(); });
232  QMessageBox::warning(this, "Scene not renamed",
233  QString("The scene name '").append(item->text(column)).append("' already exists"));
234  return;
235  }
236  else
237  {
238  std::string old_name = item->toolTip(column).toStdString();
239  planning_scene_storage->renamePlanningScene(old_name, new_name);
240  item->setToolTip(column, item->text(column));
241  }
242  }
243  else
244  {
245  std::string scene = item->parent()->text(0).toStdString();
246  std::string new_name = item->text(column).toStdString();
247  if (planning_scene_storage->hasPlanningQuery(scene, new_name))
248  {
249  planning_display_->addMainLoopJob([this] { populatePlanningSceneTreeView(); });
250  QMessageBox::warning(this, "Query not renamed",
251  QString("The query name '")
252  .append(item->text(column))
253  .append("' already exists for scene ")
254  .append(item->parent()->text(0)));
255  return;
256  }
257  else
258  {
259  std::string old_name = item->toolTip(column).toStdString();
260  planning_scene_storage->renamePlanningQuery(scene, old_name, new_name);
261  item->setToolTip(column, item->text(column));
262  }
263  }
264 }
265 
266 void MotionPlanningFrame::populatePlanningSceneTreeView()
267 {
268  moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage = planning_scene_storage_;
269  if (!planning_scene_storage)
270  return;
271 
272  ui_->planning_scene_tree->setUpdatesEnabled(false);
273 
274  // remember which items were expanded
275  std::set<std::string> expanded;
276  for (int i = 0; i < ui_->planning_scene_tree->topLevelItemCount(); ++i)
277  {
278  QTreeWidgetItem* it = ui_->planning_scene_tree->topLevelItem(i);
279  if (it->isExpanded())
280  expanded.insert(it->text(0).toStdString());
281  }
282 
283  ui_->planning_scene_tree->clear();
284  std::vector<std::string> names;
285  planning_scene_storage->getPlanningSceneNames(names);
286 
287  for (const std::string& name : names)
288  {
289  std::vector<std::string> query_names;
290  planning_scene_storage->getPlanningQueriesNames(query_names, name);
291  QTreeWidgetItem* item =
292  new QTreeWidgetItem(ui_->planning_scene_tree, QStringList(QString::fromStdString(name)), ITEM_TYPE_SCENE);
293  item->setFlags(item->flags() | Qt::ItemIsEditable);
294  item->setToolTip(0, item->text(0)); // we use the tool tip as a backup of the old name when renaming
295  for (const std::string& query_name : query_names)
296  {
297  QTreeWidgetItem* subitem =
298  new QTreeWidgetItem(item, QStringList(QString::fromStdString(query_name)), ITEM_TYPE_QUERY);
299  subitem->setFlags(subitem->flags() | Qt::ItemIsEditable);
300  subitem->setToolTip(0, subitem->text(0));
301  item->addChild(subitem);
302  }
303 
304  ui_->planning_scene_tree->insertTopLevelItem(ui_->planning_scene_tree->topLevelItemCount(), item);
305  if (expanded.find(name) != expanded.end())
306  ui_->planning_scene_tree->expandItem(item);
307  }
308  ui_->planning_scene_tree->sortItems(0, Qt::AscendingOrder);
309  ui_->planning_scene_tree->setUpdatesEnabled(true);
310  checkPlanningSceneTreeEnabledButtons();
311 }
312 } // namespace moveit_rviz_plugin
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
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
void addBackgroundJob(const std::function< void()> &job, const std::string &name)
std::string append(const std::string &left, const std::string &right)
name
Definition: setup.py:7