00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #include <moveit/warehouse/planning_scene_storage.h>
00033 #include <moveit/warehouse/constraints_storage.h>
00034 #include <moveit/warehouse/state_storage.h>
00035
00036 #include <moveit/motion_planning_rviz_plugin/motion_planning_frame.h>
00037 #include <moveit/motion_planning_rviz_plugin/motion_planning_display.h>
00038 #include <moveit/kinematic_constraints/utils.h>
00039 #include <moveit/robot_state/conversions.h>
00040 #include <moveit/robot_interaction/interactive_marker_helpers.h>
00041
00042 #include <interactive_markers/tools.h>
00043
00044 #include <rviz/display_context.h>
00045 #include <rviz/window_manager_interface.h>
00046
00047 #include <eigen_conversions/eigen_msg.h>
00048
00049 #include <QMessageBox>
00050 #include <QInputDialog>
00051
00052 #include "ui_motion_planning_rviz_plugin_frame.h"
00053
00054 #include <boost/math/constants/constants.hpp>
00055
00056 namespace moveit_rviz_plugin
00057 {
00058
00059 void MotionPlanningFrame::saveSceneButtonClicked()
00060 {
00061 if (planning_scene_storage_)
00062 {
00063 const std::string &name = planning_display_->getPlanningSceneRO()->getName();
00064 if (name.empty() || planning_scene_storage_->hasPlanningScene(name))
00065 {
00066 boost::scoped_ptr<QMessageBox> q;
00067 if (name.empty())
00068 q.reset(new QMessageBox(QMessageBox::Question, "Change Planning Scene Name",
00069 QString("The name for the planning scene should not be empty. Would you like to rename the planning scene?'"),
00070 QMessageBox::Cancel,
00071 this));
00072 else
00073 q.reset(new QMessageBox(QMessageBox::Question, "Confirm Planning Scene Overwrite",
00074 QString("A planning scene named '")
00075 .append( name.c_str() )
00076 .append( "' already exists. Do you wish to overwrite that scene?"),
00077 QMessageBox::Yes | QMessageBox::No,
00078 this));
00079 boost::scoped_ptr<QPushButton> rename(q->addButton("&Rename", QMessageBox::AcceptRole));
00080 if (q->exec() != QMessageBox::Yes)
00081 {
00082 if (q->clickedButton() == rename.get())
00083 {
00084 bool ok = false;
00085 QString new_name = QInputDialog::getText(this, "Rename Planning Scene", "New name for the planning scene:", QLineEdit::Normal, QString::fromStdString(name), &ok);
00086 if (ok)
00087 {
00088 planning_display_->getPlanningSceneRW()->setName(new_name.toStdString());
00089 rviz::Property *prop = planning_display_->subProp("Scene Geometry")->subProp("Scene Name");
00090 if (prop)
00091 {
00092 bool old = prop->blockSignals(true);
00093 prop->setValue(new_name);
00094 prop->blockSignals(old);
00095 }
00096 saveSceneButtonClicked();
00097 }
00098 return;
00099 }
00100 return;
00101 }
00102 }
00103
00104 planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeSaveSceneButtonClicked, this), "save scene");
00105 }
00106 }
00107
00108 void MotionPlanningFrame::planningSceneItemClicked()
00109 {
00110 checkPlanningSceneTreeEnabledButtons();
00111 }
00112
00113 void MotionPlanningFrame::saveQueryButtonClicked()
00114 {
00115 if (planning_scene_storage_)
00116 {
00117 QList<QTreeWidgetItem *> sel = ui_->planning_scene_tree->selectedItems();
00118 if (!sel.empty())
00119 {
00120 QTreeWidgetItem *s = sel.front();
00121
00122
00123 if (s->type() == ITEM_TYPE_SCENE)
00124 {
00125 std::string scene = s->text(0).toStdString();
00126 planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeSaveQueryButtonClicked, this, scene, ""), "save query");
00127 }
00128 else
00129 {
00130
00131 std::string scene = s->parent()->text(0).toStdString();
00132 std::string query_name = s->text(0).toStdString();
00133
00134 while (query_name.empty() || planning_scene_storage_->hasPlanningQuery(scene, query_name))
00135 {
00136 boost::scoped_ptr<QMessageBox> q;
00137 if (query_name.empty())
00138 q.reset(new QMessageBox(QMessageBox::Question, "Change Planning Query Name",
00139 QString("The name for the planning query should not be empty. Would you like to rename the planning query?'"),
00140 QMessageBox::Cancel,
00141 this));
00142 else
00143 q.reset(new QMessageBox(QMessageBox::Question, "Confirm Planning Query Overwrite",
00144 QString("A planning query named '")
00145 .append( query_name.c_str() )
00146 .append( "' already exists. Do you wish to overwrite that query?"),
00147 QMessageBox::Yes | QMessageBox::No,
00148 this));
00149 boost::scoped_ptr<QPushButton> rename(q->addButton("&Rename", QMessageBox::AcceptRole));
00150 if (q->exec() == QMessageBox::Yes)
00151 break;
00152 else
00153 {
00154 if (q->clickedButton() == rename.get())
00155 {
00156 bool ok = false;
00157 QString new_name = QInputDialog::getText(this, "Rename Planning Query", "New name for the planning query:", QLineEdit::Normal, QString::fromStdString(query_name), &ok);
00158 if (ok)
00159 query_name = new_name.toStdString();
00160 else
00161 return;
00162 }
00163 else
00164 return;
00165 }
00166 }
00167 planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeSaveQueryButtonClicked, this, scene, query_name), "save query");
00168 }
00169 }
00170 }
00171 }
00172
00173 void MotionPlanningFrame::deleteSceneButtonClicked()
00174 {
00175 planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeDeleteSceneButtonClicked, this), "delete scene");
00176 }
00177
00178 void MotionPlanningFrame::deleteQueryButtonClicked()
00179 {
00180 planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeDeleteQueryButtonClicked, this), "delete query");
00181 }
00182
00183 void MotionPlanningFrame::loadSceneButtonClicked()
00184 {
00185 planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeLoadSceneButtonClicked, this), "load scene");
00186 }
00187
00188 void MotionPlanningFrame::loadQueryButtonClicked()
00189 {
00190 planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeLoadQueryButtonClicked, this), "load query");
00191 }
00192
00193 void MotionPlanningFrame::warehouseItemNameChanged(QTreeWidgetItem *item, int column)
00194 {
00195 if (item->text(column) == item->toolTip(column) || item->toolTip(column).length() == 0)
00196 return;
00197 boost::shared_ptr<moveit_warehouse::PlanningSceneStorage> planning_scene_storage = planning_scene_storage_;
00198 if (!planning_scene_storage)
00199 return;
00200
00201 if (item->type() == ITEM_TYPE_SCENE)
00202 {
00203 std::string new_name = item->text(column).toStdString();
00204
00205 if (planning_scene_storage->hasPlanningScene(new_name))
00206 {
00207 planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this));
00208 QMessageBox::warning(this, "Scene not renamed", QString("The scene name '").append(item->text(column)).append("' already exists"));
00209 return;
00210 }
00211 else
00212 {
00213 std::string old_name = item->toolTip(column).toStdString();
00214 planning_scene_storage->renamePlanningScene(old_name, new_name);
00215 item->setToolTip(column, item->text(column));
00216 }
00217 }
00218 else
00219 {
00220 std::string scene = item->parent()->text(0).toStdString();
00221 std::string new_name = item->text(column).toStdString();
00222 if (planning_scene_storage->hasPlanningQuery(scene, new_name))
00223 {
00224 planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this));
00225 QMessageBox::warning(this, "Query not renamed", QString("The query name '").append(item->text(column)).
00226 append("' already exists for scene ").append(item->parent()->text(0)));
00227 return;
00228 }
00229 else
00230 {
00231 std::string old_name = item->toolTip(column).toStdString();
00232 planning_scene_storage->renamePlanningQuery(scene, old_name, new_name);
00233 item->setToolTip(column, item->text(column));
00234 }
00235 }
00236 }
00237
00238 void MotionPlanningFrame::populatePlanningSceneTreeView()
00239 {
00240 boost::shared_ptr<moveit_warehouse::PlanningSceneStorage> planning_scene_storage = planning_scene_storage_;
00241 if (!planning_scene_storage)
00242 return;
00243
00244 ui_->planning_scene_tree->setUpdatesEnabled(false);
00245
00246
00247 std::set<std::string> expanded;
00248 for (int i = 0 ; i < ui_->planning_scene_tree->topLevelItemCount() ; ++i)
00249 {
00250 QTreeWidgetItem *it = ui_->planning_scene_tree->topLevelItem(i);
00251 if (it->isExpanded())
00252 expanded.insert(it->text(0).toStdString());
00253 }
00254
00255 ui_->planning_scene_tree->clear();
00256 std::vector<std::string> names;
00257 planning_scene_storage->getPlanningSceneNames(names);
00258
00259 for (std::size_t i = 0; i < names.size(); ++i)
00260 {
00261 std::vector<std::string> query_names;
00262 planning_scene_storage->getPlanningQueriesNames(query_names, names[i]);
00263 QTreeWidgetItem *item = new QTreeWidgetItem(ui_->planning_scene_tree, QStringList(QString::fromStdString(names[i])), ITEM_TYPE_SCENE);
00264 item->setFlags(item->flags() | Qt::ItemIsEditable);
00265 item->setToolTip(0, item->text(0));
00266 for (std::size_t j = 0 ; j < query_names.size() ; ++j)
00267 {
00268 QTreeWidgetItem *subitem = new QTreeWidgetItem(item, QStringList(QString::fromStdString(query_names[j])), ITEM_TYPE_QUERY);
00269 subitem->setFlags(subitem->flags() | Qt::ItemIsEditable);
00270 subitem->setToolTip(0, subitem->text(0));
00271 item->addChild(subitem);
00272 }
00273
00274 ui_->planning_scene_tree->insertTopLevelItem(ui_->planning_scene_tree->topLevelItemCount(), item);
00275 if (expanded.find(names[i]) != expanded.end())
00276 ui_->planning_scene_tree->expandItem(item);
00277 }
00278 ui_->planning_scene_tree->sortItems(0, Qt::AscendingOrder);
00279 ui_->planning_scene_tree->setUpdatesEnabled(true);
00280 checkPlanningSceneTreeEnabledButtons();
00281 }
00282
00283 }