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
00033
00034
00035
00036
00037 #include <moveit/motion_planning_rviz_plugin/motion_planning_frame.h>
00038 #include <moveit/motion_planning_rviz_plugin/motion_planning_display.h>
00039 #include <moveit/move_group/capability_names.h>
00040
00041 #include <geometric_shapes/shape_operations.h>
00042
00043 #include <rviz/display_context.h>
00044 #include <rviz/frame_manager.h>
00045
00046 #include <std_srvs/Empty.h>
00047
00048 #include <QMessageBox>
00049 #include <QInputDialog>
00050 #include <QShortcut>
00051
00052 #include "ui_motion_planning_rviz_plugin_frame.h"
00053
00054 namespace moveit_rviz_plugin
00055 {
00056 MotionPlanningFrame::MotionPlanningFrame(MotionPlanningDisplay* pdisplay, rviz::DisplayContext* context,
00057 QWidget* parent)
00058 : QWidget(parent)
00059 , planning_display_(pdisplay)
00060 , context_(context)
00061 , ui_(new Ui::MotionPlanningUI())
00062 , first_time_(true)
00063 , clear_octomap_service_client_(nh_.serviceClient<std_srvs::Empty>(move_group::CLEAR_OCTOMAP_SERVICE_NAME))
00064 {
00065
00066 ui_->setupUi(this);
00067
00068
00069
00070 connect(ui_->plan_button, SIGNAL(clicked()), this, SLOT(planButtonClicked()));
00071 connect(ui_->execute_button, SIGNAL(clicked()), this, SLOT(executeButtonClicked()));
00072 connect(ui_->plan_and_execute_button, SIGNAL(clicked()), this, SLOT(planAndExecuteButtonClicked()));
00073 connect(ui_->stop_button, SIGNAL(clicked()), this, SLOT(stopButtonClicked()));
00074 connect(ui_->use_start_state_button, SIGNAL(clicked()), this, SLOT(useStartStateButtonClicked()));
00075 connect(ui_->use_goal_state_button, SIGNAL(clicked()), this, SLOT(useGoalStateButtonClicked()));
00076 connect(ui_->database_connect_button, SIGNAL(clicked()), this, SLOT(databaseConnectButtonClicked()));
00077 connect(ui_->save_scene_button, SIGNAL(clicked()), this, SLOT(saveSceneButtonClicked()));
00078 connect(ui_->save_query_button, SIGNAL(clicked()), this, SLOT(saveQueryButtonClicked()));
00079 connect(ui_->delete_scene_button, SIGNAL(clicked()), this, SLOT(deleteSceneButtonClicked()));
00080 connect(ui_->delete_query_button, SIGNAL(clicked()), this, SLOT(deleteQueryButtonClicked()));
00081 connect(ui_->planning_scene_tree, SIGNAL(itemSelectionChanged()), this, SLOT(planningSceneItemClicked()));
00082 connect(ui_->load_scene_button, SIGNAL(clicked()), this, SLOT(loadSceneButtonClicked()));
00083 connect(ui_->load_query_button, SIGNAL(clicked()), this, SLOT(loadQueryButtonClicked()));
00084 connect(ui_->allow_looking, SIGNAL(toggled(bool)), this, SLOT(allowLookingToggled(bool)));
00085 connect(ui_->allow_replanning, SIGNAL(toggled(bool)), this, SLOT(allowReplanningToggled(bool)));
00086 connect(ui_->allow_external_program, SIGNAL(toggled(bool)), this, SLOT(allowExternalProgramCommunication(bool)));
00087 connect(ui_->planning_algorithm_combo_box, SIGNAL(currentIndexChanged(int)), this,
00088 SLOT(planningAlgorithmIndexChanged(int)));
00089 connect(ui_->planning_algorithm_combo_box, SIGNAL(currentIndexChanged(int)), this,
00090 SLOT(planningAlgorithmIndexChanged(int)));
00091 connect(ui_->import_file_button, SIGNAL(clicked()), this, SLOT(importFileButtonClicked()));
00092 connect(ui_->import_url_button, SIGNAL(clicked()), this, SLOT(importUrlButtonClicked()));
00093 connect(ui_->clear_scene_button, SIGNAL(clicked()), this, SLOT(clearSceneButtonClicked()));
00094 connect(ui_->scene_scale, SIGNAL(valueChanged(int)), this, SLOT(sceneScaleChanged(int)));
00095 connect(ui_->scene_scale, SIGNAL(sliderPressed()), this, SLOT(sceneScaleStartChange()));
00096 connect(ui_->scene_scale, SIGNAL(sliderReleased()), this, SLOT(sceneScaleEndChange()));
00097 connect(ui_->remove_object_button, SIGNAL(clicked()), this, SLOT(removeObjectButtonClicked()));
00098 connect(ui_->object_x, SIGNAL(valueChanged(double)), this, SLOT(objectPoseValueChanged(double)));
00099 connect(ui_->object_y, SIGNAL(valueChanged(double)), this, SLOT(objectPoseValueChanged(double)));
00100 connect(ui_->object_z, SIGNAL(valueChanged(double)), this, SLOT(objectPoseValueChanged(double)));
00101 connect(ui_->object_rx, SIGNAL(valueChanged(double)), this, SLOT(objectPoseValueChanged(double)));
00102 connect(ui_->object_ry, SIGNAL(valueChanged(double)), this, SLOT(objectPoseValueChanged(double)));
00103 connect(ui_->object_rz, SIGNAL(valueChanged(double)), this, SLOT(objectPoseValueChanged(double)));
00104 connect(ui_->publish_current_scene_button, SIGNAL(clicked()), this, SLOT(publishSceneButtonClicked()));
00105 connect(ui_->collision_objects_list, SIGNAL(itemSelectionChanged()), this, SLOT(selectedCollisionObjectChanged()));
00106 connect(ui_->collision_objects_list, SIGNAL(itemChanged(QListWidgetItem*)), this,
00107 SLOT(collisionObjectChanged(QListWidgetItem*)));
00108 connect(ui_->path_constraints_combo_box, SIGNAL(currentIndexChanged(int)), this,
00109 SLOT(pathConstraintsIndexChanged(int)));
00110 connect(ui_->clear_octomap_button, SIGNAL(clicked()), this, SLOT(onClearOctomapClicked()));
00111 connect(ui_->planning_scene_tree, SIGNAL(itemChanged(QTreeWidgetItem*, int)), this,
00112 SLOT(warehouseItemNameChanged(QTreeWidgetItem*, int)));
00113 connect(ui_->reset_db_button, SIGNAL(clicked()), this, SLOT(resetDbButtonClicked()));
00114 connect(ui_->export_scene_text_button, SIGNAL(clicked()), this, SLOT(exportAsTextButtonClicked()));
00115 connect(ui_->import_scene_text_button, SIGNAL(clicked()), this, SLOT(importFromTextButtonClicked()));
00116 connect(ui_->load_state_button, SIGNAL(clicked()), this, SLOT(loadStateButtonClicked()));
00117 connect(ui_->save_start_state_button, SIGNAL(clicked()), this, SLOT(saveStartStateButtonClicked()));
00118 connect(ui_->save_goal_state_button, SIGNAL(clicked()), this, SLOT(saveGoalStateButtonClicked()));
00119 connect(ui_->set_as_start_state_button, SIGNAL(clicked()), this, SLOT(setAsStartStateButtonClicked()));
00120 connect(ui_->set_as_goal_state_button, SIGNAL(clicked()), this, SLOT(setAsGoalStateButtonClicked()));
00121 connect(ui_->remove_state_button, SIGNAL(clicked()), this, SLOT(removeStateButtonClicked()));
00122 connect(ui_->clear_states_button, SIGNAL(clicked()), this, SLOT(clearStatesButtonClicked()));
00123 connect(ui_->approximate_ik, SIGNAL(stateChanged(int)), this, SLOT(approximateIKChanged(int)));
00124
00125 connect(ui_->detect_objects_button, SIGNAL(clicked()), this, SLOT(detectObjectsButtonClicked()));
00126 connect(ui_->pick_button, SIGNAL(clicked()), this, SLOT(pickObjectButtonClicked()));
00127 connect(ui_->place_button, SIGNAL(clicked()), this, SLOT(placeObjectButtonClicked()));
00128 connect(ui_->detected_objects_list, SIGNAL(itemSelectionChanged()), this, SLOT(selectedDetectedObjectChanged()));
00129 connect(ui_->detected_objects_list, SIGNAL(itemChanged(QListWidgetItem*)), this,
00130 SLOT(detectedObjectChanged(QListWidgetItem*)));
00131 connect(ui_->support_surfaces_list, SIGNAL(itemSelectionChanged()), this, SLOT(selectedSupportSurfaceChanged()));
00132
00133 connect(ui_->tabWidget, SIGNAL(currentChanged(int)), this, SLOT(tabChanged(int)));
00134
00135 QShortcut* copy_object_shortcut = new QShortcut(QKeySequence(Qt::CTRL + Qt::Key_C), ui_->collision_objects_list);
00136 connect(copy_object_shortcut, SIGNAL(activated()), this, SLOT(copySelectedCollisionObject()));
00137
00138 ui_->reset_db_button->hide();
00139 ui_->background_job_progress->hide();
00140 ui_->background_job_progress->setMaximum(0);
00141
00142 ui_->tabWidget->setCurrentIndex(0);
00143
00144 known_collision_objects_version_ = 0;
00145
00146 planning_scene_publisher_ = nh_.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);
00147 planning_scene_world_publisher_ = nh_.advertise<moveit_msgs::PlanningSceneWorld>("planning_scene_world", 1);
00148
00149
00150 object_recognition_client_.reset(new actionlib::SimpleActionClient<object_recognition_msgs::ObjectRecognitionAction>(
00151 OBJECT_RECOGNITION_ACTION, false));
00152 object_recognition_subscriber_ =
00153 nh_.subscribe("recognized_object_array", 1, &MotionPlanningFrame::listenDetectedObjects, this);
00154
00155 if (object_recognition_client_)
00156 {
00157 try
00158 {
00159 waitForAction(object_recognition_client_, nh_, ros::Duration(3.0), OBJECT_RECOGNITION_ACTION);
00160 }
00161 catch (std::runtime_error& ex)
00162 {
00163
00164 object_recognition_client_.reset();
00165 }
00166 }
00167 try
00168 {
00169 planning_scene_interface_.reset(new moveit::planning_interface::PlanningSceneInterface());
00170 }
00171 catch (std::runtime_error& ex)
00172 {
00173 ROS_ERROR("%s", ex.what());
00174 }
00175
00176 try
00177 {
00178 const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
00179 if (ps)
00180 {
00181 semantic_world_.reset(new moveit::semantic_world::SemanticWorld(ps));
00182 }
00183 else
00184 semantic_world_.reset();
00185 if (semantic_world_)
00186 {
00187 semantic_world_->addTableCallback(boost::bind(&MotionPlanningFrame::updateTables, this));
00188 }
00189 }
00190 catch (std::runtime_error& ex)
00191 {
00192 ROS_ERROR("%s", ex.what());
00193 }
00194 }
00195
00196 MotionPlanningFrame::~MotionPlanningFrame()
00197 {
00198 }
00199
00200 void MotionPlanningFrame::approximateIKChanged(int state)
00201 {
00202 planning_display_->useApproximateIK(state == Qt::Checked);
00203 }
00204
00205 void MotionPlanningFrame::setItemSelectionInList(const std::string& item_name, bool selection, QListWidget* list)
00206 {
00207 QList<QListWidgetItem*> found_items = list->findItems(QString(item_name.c_str()), Qt::MatchExactly);
00208 for (std::size_t i = 0; i < found_items.size(); ++i)
00209 found_items[i]->setSelected(selection);
00210 }
00211
00212 void MotionPlanningFrame::allowExternalProgramCommunication(bool enable)
00213 {
00214 planning_display_->getRobotInteraction()->toggleMoveInteractiveMarkerTopic(enable);
00215 planning_display_->toggleSelectPlanningGroupSubscription(enable);
00216 if (enable)
00217 {
00218 ros::NodeHandle nh;
00219 plan_subscriber_ = nh.subscribe("/rviz/moveit/plan", 1, &MotionPlanningFrame::remotePlanCallback, this);
00220 execute_subscriber_ = nh.subscribe("/rviz/moveit/execute", 1, &MotionPlanningFrame::remoteExecuteCallback, this);
00221 update_start_state_subscriber_ =
00222 nh.subscribe("/rviz/moveit/update_start_state", 1, &MotionPlanningFrame::remoteUpdateStartStateCallback, this);
00223 update_goal_state_subscriber_ =
00224 nh.subscribe("/rviz/moveit/update_goal_state", 1, &MotionPlanningFrame::remoteUpdateGoalStateCallback, this);
00225 }
00226 else
00227 {
00228 plan_subscriber_.shutdown();
00229 execute_subscriber_.shutdown();
00230 update_start_state_subscriber_.shutdown();
00231 update_goal_state_subscriber_.shutdown();
00232 }
00233 }
00234
00235 void MotionPlanningFrame::fillStateSelectionOptions()
00236 {
00237 ui_->start_state_selection->clear();
00238 ui_->goal_state_selection->clear();
00239
00240 if (!planning_display_->getPlanningSceneMonitor())
00241 return;
00242
00243 const robot_model::RobotModelConstPtr& kmodel = planning_display_->getRobotModel();
00244 std::string group = planning_display_->getCurrentPlanningGroup();
00245 if (group.empty())
00246 return;
00247 const robot_model::JointModelGroup* jmg = kmodel->getJointModelGroup(group);
00248 if (jmg)
00249 {
00250 ui_->start_state_selection->addItem(QString("<random valid>"));
00251 ui_->start_state_selection->addItem(QString("<random>"));
00252 ui_->start_state_selection->addItem(QString("<current>"));
00253 ui_->start_state_selection->addItem(QString("<same as goal>"));
00254
00255 ui_->goal_state_selection->addItem(QString("<random valid>"));
00256 ui_->goal_state_selection->addItem(QString("<random>"));
00257 ui_->goal_state_selection->addItem(QString("<current>"));
00258 ui_->goal_state_selection->addItem(QString("<same as start>"));
00259
00260 const std::vector<std::string>& known_states = jmg->getDefaultStateNames();
00261 if (!known_states.empty())
00262 {
00263 ui_->start_state_selection->insertSeparator(ui_->start_state_selection->count());
00264 ui_->goal_state_selection->insertSeparator(ui_->goal_state_selection->count());
00265 for (std::size_t i = 0; i < known_states.size(); ++i)
00266 {
00267 ui_->start_state_selection->addItem(QString::fromStdString(known_states[i]));
00268 ui_->goal_state_selection->addItem(QString::fromStdString(known_states[i]));
00269 }
00270 }
00271 ui_->start_state_selection->setCurrentIndex(2);
00272 ui_->goal_state_selection->setCurrentIndex(0);
00273 }
00274 }
00275
00276 void MotionPlanningFrame::changePlanningGroupHelper()
00277 {
00278 if (!planning_display_->getPlanningSceneMonitor())
00279 return;
00280
00281 planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::fillStateSelectionOptions, this));
00282 planning_display_->addMainLoopJob(
00283 boost::bind(&MotionPlanningFrame::populateConstraintsList, this, std::vector<std::string>()));
00284
00285 const robot_model::RobotModelConstPtr& kmodel = planning_display_->getRobotModel();
00286 std::string group = planning_display_->getCurrentPlanningGroup();
00287 planning_display_->addMainLoopJob(
00288 boost::bind(&MotionPlanningParamWidget::setGroupName, ui_->planner_param_treeview, group));
00289
00290 if (!group.empty() && kmodel)
00291 {
00292 if (move_group_ && move_group_->getName() == group)
00293 return;
00294 ROS_INFO("Constructing new MoveGroup connection for group '%s' in namespace '%s'", group.c_str(),
00295 planning_display_->getMoveGroupNS().c_str());
00296 moveit::planning_interface::MoveGroup::Options opt(group);
00297 opt.robot_model_ = kmodel;
00298 opt.robot_description_.clear();
00299 opt.node_handle_ = ros::NodeHandle(planning_display_->getMoveGroupNS());
00300 try
00301 {
00302 move_group_.reset(new moveit::planning_interface::MoveGroup(opt, context_->getFrameManager()->getTFClientPtr(),
00303 ros::WallDuration(30, 0)));
00304 if (planning_scene_storage_)
00305 move_group_->setConstraintsDatabase(ui_->database_host->text().toStdString(), ui_->database_port->value());
00306 }
00307 catch (std::runtime_error& ex)
00308 {
00309 ROS_ERROR("%s", ex.what());
00310 }
00311 planning_display_->addMainLoopJob(
00312 boost::bind(&MotionPlanningParamWidget::setMoveGroup, ui_->planner_param_treeview, move_group_));
00313 if (move_group_)
00314 {
00315 move_group_->allowLooking(ui_->allow_looking->isChecked());
00316 move_group_->allowReplanning(ui_->allow_replanning->isChecked());
00317 moveit_msgs::PlannerInterfaceDescription desc;
00318 if (move_group_->getInterfaceDescription(desc))
00319 planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populatePlannersList, this, desc));
00320 planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::populateConstraintsList, this),
00321 "populateConstraintsList");
00322
00323 if (first_time_)
00324 {
00325 first_time_ = false;
00326 const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
00327 if (ps)
00328 {
00329 planning_display_->setQueryStartState(ps->getCurrentState());
00330 planning_display_->setQueryGoalState(ps->getCurrentState());
00331 }
00332 }
00333 }
00334 }
00335 }
00336
00337 void MotionPlanningFrame::changePlanningGroup()
00338 {
00339 planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::changePlanningGroupHelper, this),
00340 "Frame::changePlanningGroup");
00341 }
00342
00343 void MotionPlanningFrame::sceneUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
00344 {
00345 if (update_type & planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY)
00346 planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populateCollisionObjectsList, this));
00347 }
00348
00349 void MotionPlanningFrame::importResource(const std::string& path)
00350 {
00351 if (planning_display_->getPlanningSceneMonitor())
00352 {
00353 shapes::Mesh* mesh = shapes::createMeshFromResource(path);
00354 if (mesh)
00355 {
00356 std::size_t slash = path.find_last_of("/\\");
00357 std::string name = path.substr(slash + 1);
00358 shapes::ShapeConstPtr shape(mesh);
00359 Eigen::Affine3d pose;
00360 pose.setIdentity();
00361
00362 if (planning_display_->getPlanningSceneRO()->getCurrentState().hasAttachedBody(name))
00363 {
00364 QMessageBox::warning(this, QString("Duplicate names"), QString("An attached object named '")
00365 .append(name.c_str())
00366 .append("' already exists. Please rename the "
00367 "attached object before importing."));
00368 return;
00369 }
00370
00371
00372 if (planning_display_->getPlanningSceneRO()->getWorld()->hasObject(name))
00373 {
00374 QMessageBox msgBox;
00375 msgBox.setText("There exists another object with the same name.");
00376 msgBox.setInformativeText("Would you like to overwrite it?");
00377 msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
00378 msgBox.setDefaultButton(QMessageBox::No);
00379 int ret = msgBox.exec();
00380
00381 switch (ret)
00382 {
00383 case QMessageBox::Yes:
00384
00385 {
00386 planning_scene_monitor::LockedPlanningSceneRW ps = planning_display_->getPlanningSceneRW();
00387 if (ps)
00388 {
00389 ps->getWorldNonConst()->removeObject(name);
00390 addObject(ps->getWorldNonConst(), name, shape, pose);
00391 }
00392 }
00393 break;
00394 case QMessageBox::No:
00395 {
00396
00397 bool ok = false;
00398 QString text = QInputDialog::getText(
00399 this, tr("Choose a new name"), tr("Import the new object under the name:"), QLineEdit::Normal,
00400 QString::fromStdString(name + "-" + boost::lexical_cast<std::string>(
00401 planning_display_->getPlanningSceneRO()->getWorld()->size())),
00402 &ok);
00403 if (ok)
00404 {
00405 if (!text.isEmpty())
00406 {
00407 name = text.toStdString();
00408 planning_scene_monitor::LockedPlanningSceneRW ps = planning_display_->getPlanningSceneRW();
00409 if (ps)
00410 {
00411 if (ps->getWorld()->hasObject(name))
00412 QMessageBox::warning(
00413 this, "Name already exists",
00414 QString("The name '").append(name.c_str()).append("' already exists. Not importing object."));
00415 else
00416 addObject(ps->getWorldNonConst(), name, shape, pose);
00417 }
00418 }
00419 else
00420 QMessageBox::warning(this, "Object not imported", "Cannot use an empty name for an imported object");
00421 }
00422 break;
00423 }
00424 default:
00425
00426 break;
00427 }
00428 }
00429 else
00430 {
00431 planning_scene_monitor::LockedPlanningSceneRW ps = planning_display_->getPlanningSceneRW();
00432 if (ps)
00433 addObject(ps->getWorldNonConst(), name, shape, pose);
00434 }
00435 }
00436 else
00437 {
00438 QMessageBox::warning(this, QString("Import error"), QString("Unable to import scene"));
00439 return;
00440 }
00441 }
00442 }
00443
00444 void MotionPlanningFrame::enable()
00445 {
00446 ui_->planning_algorithm_combo_box->clear();
00447 ui_->library_label->setText("NO PLANNING LIBRARY LOADED");
00448 ui_->library_label->setStyleSheet("QLabel { color : red; font: bold }");
00449 ui_->object_status->setText("");
00450
00451
00452 parentWidget()->show();
00453 show();
00454 }
00455
00456 void MotionPlanningFrame::disable()
00457 {
00458 move_group_.reset();
00459 parentWidget()->hide();
00460 hide();
00461 }
00462
00463 void MotionPlanningFrame::tabChanged(int index)
00464 {
00465 if (scene_marker_ && ui_->tabWidget->tabText(index).toStdString() != TAB_OBJECTS)
00466 scene_marker_.reset();
00467 else if (ui_->tabWidget->tabText(index).toStdString() == TAB_OBJECTS)
00468 selectedCollisionObjectChanged();
00469 }
00470
00471 void MotionPlanningFrame::updateSceneMarkers(float wall_dt, float ros_dt)
00472 {
00473 if (scene_marker_)
00474 scene_marker_->update(wall_dt);
00475 }
00476
00477 void MotionPlanningFrame::updateExternalCommunication()
00478 {
00479 if (ui_->allow_external_program->isChecked())
00480 {
00481 planning_display_->getRobotInteraction()->toggleMoveInteractiveMarkerTopic(true);
00482 }
00483 }
00484
00485 }