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
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050 #include "ros/ros.h"
00051 #include "header_widget.h"
00052 #include "planning_groups_widget.h"
00053 #include <boost/thread.hpp>
00054 #include <boost/lexical_cast.hpp>
00055
00056 #include <QApplication>
00057 #include <QDebug>
00058 #include <QVBoxLayout>
00059 #include <QHBoxLayout>
00060 #include <QLabel>
00061 #include <QPushButton>
00062 #include <QMessageBox>
00063 #include <QString>
00064 #include <QLineEdit>
00065 #include <QTreeWidgetItem>
00066 #include <QHeaderView>
00067
00068 #include <boost/utility.hpp>
00069 #include <boost/graph/adjacency_list.hpp>
00070 #include <boost/graph/depth_first_search.hpp>
00071 #include <boost/graph/visitors.hpp>
00072
00073 namespace moveit_setup_assistant
00074 {
00075
00076 static const std::string VIS_TOPIC_NAME = "planning_components_visualization";
00077
00078
00079 struct cycle_detector : public boost::dfs_visitor<>
00080 {
00081 cycle_detector(bool& has_cycle) : m_has_cycle(has_cycle)
00082 {
00083 }
00084
00085 template <class Edge, class Graph>
00086 void back_edge(Edge, Graph&)
00087 {
00088 m_has_cycle = true;
00089 }
00090
00091 protected:
00092 bool& m_has_cycle;
00093 };
00094
00095
00096
00097
00098 PlanningGroupsWidget::PlanningGroupsWidget(QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data)
00099 : SetupScreenWidget(parent), config_data_(config_data)
00100 {
00101
00102 QVBoxLayout* layout = new QVBoxLayout();
00103
00104
00105 HeaderWidget* header =
00106 new HeaderWidget("Planning Groups", "Create and edit planning groups for your robot based on joint collections, "
00107 "link collections, kinematic chains and subgroups.",
00108 this);
00109 layout->addWidget(header);
00110
00111
00112
00113
00114 groups_tree_widget_ = createContentsWidget();
00115
00116
00117 joints_widget_ = new DoubleListWidget(this, config_data_, "Joint Collection", "Joint");
00118 connect(joints_widget_, SIGNAL(cancelEditing()), this, SLOT(cancelEditing()));
00119 connect(joints_widget_, SIGNAL(doneEditing()), this, SLOT(saveJointsScreen()));
00120 connect(joints_widget_, SIGNAL(previewSelected(std::vector<std::string>)), this,
00121 SLOT(previewSelectedJoints(std::vector<std::string>)));
00122
00123
00124 links_widget_ = new DoubleListWidget(this, config_data_, "Link Collection", "Link");
00125 connect(links_widget_, SIGNAL(cancelEditing()), this, SLOT(cancelEditing()));
00126 connect(links_widget_, SIGNAL(doneEditing()), this, SLOT(saveLinksScreen()));
00127 connect(links_widget_, SIGNAL(previewSelected(std::vector<std::string>)), this,
00128 SLOT(previewSelectedLink(std::vector<std::string>)));
00129
00130
00131 chain_widget_ = new KinematicChainWidget(this, config_data);
00132 connect(chain_widget_, SIGNAL(cancelEditing()), this, SLOT(cancelEditing()));
00133 connect(chain_widget_, SIGNAL(doneEditing()), this, SLOT(saveChainScreen()));
00134 connect(chain_widget_, SIGNAL(unhighlightAll()), this, SIGNAL(unhighlightAll()));
00135 connect(chain_widget_, SIGNAL(highlightLink(const std::string&, const QColor&)), this,
00136 SIGNAL(highlightLink(const std::string&, const QColor&)));
00137
00138
00139 subgroups_widget_ = new DoubleListWidget(this, config_data_, "Subgroup", "Subgroup");
00140 connect(subgroups_widget_, SIGNAL(cancelEditing()), this, SLOT(cancelEditing()));
00141 connect(subgroups_widget_, SIGNAL(doneEditing()), this, SLOT(saveSubgroupsScreen()));
00142 connect(subgroups_widget_, SIGNAL(previewSelected(std::vector<std::string>)), this,
00143 SLOT(previewSelectedSubgroup(std::vector<std::string>)));
00144
00145
00146 group_edit_widget_ = new GroupEditWidget(this, config_data_);
00147 connect(group_edit_widget_, SIGNAL(cancelEditing()), this, SLOT(cancelEditing()));
00148 connect(group_edit_widget_, SIGNAL(deleteGroup()), this, SLOT(deleteGroup()));
00149 connect(group_edit_widget_, SIGNAL(save()), this, SLOT(saveGroupScreenEdit()));
00150 connect(group_edit_widget_, SIGNAL(saveJoints()), this, SLOT(saveGroupScreenJoints()));
00151 connect(group_edit_widget_, SIGNAL(saveLinks()), this, SLOT(saveGroupScreenLinks()));
00152 connect(group_edit_widget_, SIGNAL(saveChain()), this, SLOT(saveGroupScreenChain()));
00153 connect(group_edit_widget_, SIGNAL(saveSubgroups()), this, SLOT(saveGroupScreenSubgroups()));
00154
00155
00156 stacked_layout_ = new QStackedLayout(this);
00157 stacked_layout_->addWidget(groups_tree_widget_);
00158 stacked_layout_->addWidget(joints_widget_);
00159 stacked_layout_->addWidget(links_widget_);
00160 stacked_layout_->addWidget(chain_widget_);
00161 stacked_layout_->addWidget(subgroups_widget_);
00162 stacked_layout_->addWidget(group_edit_widget_);
00163
00164 showMainScreen();
00165
00166
00167
00168
00169 QWidget* stacked_layout_widget = new QWidget(this);
00170 stacked_layout_widget->setLayout(stacked_layout_);
00171
00172 layout->addWidget(stacked_layout_widget);
00173
00174 setLayout(layout);
00175
00176
00177 QApplication::processEvents();
00178 }
00179
00180
00181
00182
00183 QWidget* PlanningGroupsWidget::createContentsWidget()
00184 {
00185
00186 QWidget* content_widget = new QWidget(this);
00187
00188
00189 QVBoxLayout* layout = new QVBoxLayout(this);
00190
00191
00192
00193 groups_tree_ = new QTreeWidget(this);
00194 groups_tree_->setHeaderLabel("Current Groups");
00195 connect(groups_tree_, SIGNAL(itemDoubleClicked(QTreeWidgetItem*, int)), this, SLOT(editSelected()));
00196 connect(groups_tree_, SIGNAL(itemClicked(QTreeWidgetItem*, int)), this, SLOT(previewSelected()));
00197 layout->addWidget(groups_tree_);
00198
00199
00200
00201 QHBoxLayout* controls_layout = new QHBoxLayout();
00202
00203
00204 QLabel* expand_controls = new QLabel(this);
00205 expand_controls->setText("<a href='expand'>Expand All</a> <a href='contract'>Collapse All</a>");
00206 connect(expand_controls, SIGNAL(linkActivated(const QString)), this, SLOT(alterTree(const QString)));
00207 controls_layout->addWidget(expand_controls);
00208
00209
00210 QWidget* spacer = new QWidget(this);
00211 spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00212 controls_layout->addWidget(spacer);
00213
00214
00215 btn_delete_ = new QPushButton("&Delete Selected", this);
00216 btn_delete_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00217 btn_delete_->setMaximumWidth(300);
00218 connect(btn_delete_, SIGNAL(clicked()), this, SLOT(deleteGroup()));
00219 controls_layout->addWidget(btn_delete_);
00220 controls_layout->setAlignment(btn_delete_, Qt::AlignRight);
00221
00222
00223 btn_edit_ = new QPushButton("&Edit Selected", this);
00224 btn_edit_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00225 btn_edit_->setMaximumWidth(300);
00226 btn_edit_->hide();
00227 connect(btn_edit_, SIGNAL(clicked()), this, SLOT(editSelected()));
00228 controls_layout->addWidget(btn_edit_);
00229 controls_layout->setAlignment(btn_edit_, Qt::AlignRight);
00230
00231
00232 QPushButton* btn_add = new QPushButton("&Add Group", this);
00233 btn_add->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00234 btn_add->setMaximumWidth(300);
00235 connect(btn_add, SIGNAL(clicked()), this, SLOT(addGroup()));
00236 controls_layout->addWidget(btn_add);
00237 controls_layout->setAlignment(btn_add, Qt::AlignRight);
00238
00239
00240 layout->addLayout(controls_layout);
00241
00242
00243 content_widget->setLayout(layout);
00244
00245 return content_widget;
00246 }
00247
00248
00249
00250
00251 void PlanningGroupsWidget::loadGroupsTree()
00252 {
00253
00254 groups_tree_->setUpdatesEnabled(false);
00255 groups_tree_->setDisabled(true);
00256 groups_tree_->clear();
00257
00258
00259 for (std::vector<srdf::Model::Group>::iterator group_it = config_data_->srdf_->groups_.begin();
00260 group_it != config_data_->srdf_->groups_.end(); ++group_it)
00261 {
00262 loadGroupsTreeRecursive(*group_it, NULL);
00263 }
00264
00265
00266 groups_tree_->setUpdatesEnabled(true);
00267 groups_tree_->setDisabled(false);
00268
00269
00270 if (!config_data_->srdf_->groups_.empty())
00271 {
00272 btn_edit_->show();
00273 btn_delete_->show();
00274 }
00275 else
00276 {
00277 btn_edit_->hide();
00278 btn_delete_->hide();
00279 }
00280
00281 alterTree("expand");
00282 }
00283
00284
00285
00286
00287 void PlanningGroupsWidget::loadGroupsTreeRecursive(srdf::Model::Group& group_it, QTreeWidgetItem* parent)
00288 {
00289
00290 const QFont top_level_font("Arial", 11, QFont::Bold);
00291 const QFont type_font("Arial", 11, QFont::Normal, QFont::StyleItalic);
00292
00293 QTreeWidgetItem* group;
00294
00295
00296 if (parent == NULL)
00297 {
00298 group = new QTreeWidgetItem(groups_tree_);
00299 group->setText(0, group_it.name_.c_str());
00300 group->setFont(0, top_level_font);
00301 group->setData(0, Qt::UserRole, QVariant::fromValue(PlanGroupType(&group_it, GROUP)));
00302 groups_tree_->addTopLevelItem(group);
00303 }
00304 else
00305 {
00306 group = new QTreeWidgetItem(parent);
00307 group->setText(0, group_it.name_.c_str());
00308 group->setFont(0, top_level_font);
00309 group->setData(0, Qt::UserRole, QVariant::fromValue(PlanGroupType(&group_it, GROUP)));
00310 parent->addChild(group);
00311 }
00312
00313
00314 QTreeWidgetItem* joints = new QTreeWidgetItem(group);
00315 joints->setText(0, "Joints");
00316 joints->setFont(0, type_font);
00317 joints->setData(0, Qt::UserRole, QVariant::fromValue(PlanGroupType(&group_it, JOINT)));
00318 group->addChild(joints);
00319
00320
00321 const robot_model::RobotModelConstPtr& model = config_data_->getRobotModel();
00322
00323
00324 for (std::vector<std::string>::const_iterator joint_it = group_it.joints_.begin(); joint_it != group_it.joints_.end();
00325 ++joint_it)
00326 {
00327 QTreeWidgetItem* j = new QTreeWidgetItem(joints);
00328 j->setData(0, Qt::UserRole, QVariant::fromValue(PlanGroupType(&group_it, JOINT)));
00329 std::string joint_name;
00330
00331
00332 const robot_model::JointModel* jm = model->getJointModel(*joint_it);
00333 if (jm)
00334 {
00335 joint_name = *joint_it + " - " + jm->getTypeName();
00336 }
00337 else
00338 {
00339 joint_name = *joint_it;
00340 }
00341
00342
00343 j->setText(0, joint_name.c_str());
00344 joints->addChild(j);
00345 }
00346
00347
00348 QTreeWidgetItem* links = new QTreeWidgetItem(group);
00349 links->setText(0, "Links");
00350 links->setFont(0, type_font);
00351 links->setData(0, Qt::UserRole, QVariant::fromValue(PlanGroupType(&group_it, LINK)));
00352 group->addChild(links);
00353
00354
00355 for (std::vector<std::string>::const_iterator joint_it = group_it.links_.begin(); joint_it != group_it.links_.end();
00356 ++joint_it)
00357 {
00358 QTreeWidgetItem* j = new QTreeWidgetItem(links);
00359 j->setData(0, Qt::UserRole, QVariant::fromValue(PlanGroupType(&group_it, LINK)));
00360 j->setText(0, joint_it->c_str());
00361 links->addChild(j);
00362 }
00363
00364
00365 QTreeWidgetItem* chains = new QTreeWidgetItem(group);
00366 chains->setText(0, "Chain");
00367 chains->setFont(0, type_font);
00368 chains->setData(0, Qt::UserRole, QVariant::fromValue(PlanGroupType(&group_it, CHAIN)));
00369 group->addChild(chains);
00370
00371
00372 static bool warn_once = true;
00373 if (group_it.chains_.size() > 1 && warn_once)
00374 {
00375 warn_once = false;
00376 QMessageBox::warning(this, "Group with Multiple Kinematic Chains",
00377 "Warning: this MoveIt Setup Assistant is only designed to handle one kinematic chain per "
00378 "group. The loaded SRDF has more than one kinematic chain for a group. A possible loss of "
00379 "data may occur.");
00380 }
00381
00382
00383 for (std::vector<std::pair<std::string, std::string> >::const_iterator chain_it = group_it.chains_.begin();
00384 chain_it != group_it.chains_.end(); ++chain_it)
00385 {
00386 QTreeWidgetItem* j = new QTreeWidgetItem(chains);
00387 j->setData(0, Qt::UserRole, QVariant::fromValue(PlanGroupType(&group_it, CHAIN)));
00388 j->setText(0, QString(chain_it->first.c_str()).append(" -> ").append(chain_it->second.c_str()));
00389 chains->addChild(j);
00390 }
00391
00392
00393 QTreeWidgetItem* subgroups = new QTreeWidgetItem(group);
00394 subgroups->setText(0, "Subgroups");
00395 subgroups->setFont(0, type_font);
00396 subgroups->setData(0, Qt::UserRole, QVariant::fromValue(PlanGroupType(&group_it, SUBGROUP)));
00397 group->addChild(subgroups);
00398
00399
00400 for (std::vector<std::string>::iterator subgroup_it = group_it.subgroups_.begin();
00401 subgroup_it != group_it.subgroups_.end(); ++subgroup_it)
00402 {
00403
00404
00405 srdf::Model::Group* searched_group = NULL;
00406
00407 for (std::vector<srdf::Model::Group>::iterator group2_it = config_data_->srdf_->groups_.begin();
00408 group2_it != config_data_->srdf_->groups_.end(); ++group2_it)
00409 {
00410 if (group2_it->name_ == *subgroup_it)
00411 {
00412 searched_group = &(*group2_it);
00413 break;
00414 }
00415 }
00416
00417
00418 if (searched_group == NULL)
00419 {
00420 QMessageBox::critical(this, "Error Loading SRDF", QString("Subgroup '")
00421 .append(subgroup_it->c_str())
00422 .append("' of group '")
00423 .append(group_it.name_.c_str())
00424 .append("' not found. Your SRDF is invalid"));
00425 return;
00426 }
00427
00428
00429
00430
00431 loadGroupsTreeRecursive(*searched_group, subgroups);
00432 }
00433 }
00434
00435
00436
00437
00438 void PlanningGroupsWidget::previewSelected()
00439 {
00440 QTreeWidgetItem* item = groups_tree_->currentItem();
00441
00442
00443 if (item == NULL)
00444 return;
00445
00446
00447 PlanGroupType plan_group = item->data(0, Qt::UserRole).value<PlanGroupType>();
00448
00449
00450 Q_EMIT unhighlightAll();
00451
00452
00453 Q_EMIT(highlightGroup(plan_group.group_->name_));
00454 }
00455
00456
00457
00458
00459 void PlanningGroupsWidget::editSelected()
00460 {
00461 QTreeWidgetItem* item = groups_tree_->currentItem();
00462
00463
00464 if (item == NULL)
00465 return;
00466
00467 adding_new_group_ = false;
00468
00469
00470 PlanGroupType plan_group = item->data(0, Qt::UserRole).value<PlanGroupType>();
00471
00472 if (plan_group.type_ == JOINT)
00473 {
00474
00475 loadJointsScreen(plan_group.group_);
00476
00477
00478 changeScreen(1);
00479 }
00480 else if (plan_group.type_ == LINK)
00481 {
00482
00483 loadLinksScreen(plan_group.group_);
00484
00485
00486 changeScreen(2);
00487 }
00488 else if (plan_group.type_ == CHAIN)
00489 {
00490
00491 loadChainScreen(plan_group.group_);
00492
00493
00494 changeScreen(3);
00495 }
00496 else if (plan_group.type_ == SUBGROUP)
00497 {
00498
00499 loadSubgroupsScreen(plan_group.group_);
00500
00501
00502 changeScreen(4);
00503 }
00504 else if (plan_group.type_ == GROUP)
00505 {
00506
00507 loadGroupScreen(plan_group.group_);
00508
00509
00510 changeScreen(5);
00511 }
00512 else
00513 {
00514 QMessageBox::critical(this, "Error Loading", "An internal error has occured while loading.");
00515 }
00516 }
00517
00518
00519
00520
00521 void PlanningGroupsWidget::loadJointsScreen(srdf::Model::Group* this_group)
00522 {
00523
00524 const robot_model::RobotModelConstPtr& model = config_data_->getRobotModel();
00525
00526
00527 const std::vector<std::string>& joints = model->getJointModelNames();
00528
00529 if (joints.size() == 0)
00530 {
00531 QMessageBox::critical(this, "Error Loading", "No joints found for robot model");
00532 return;
00533 }
00534
00535
00536 joints_widget_->setAvailable(joints);
00537
00538
00539 joints_widget_->setSelected(this_group->joints_);
00540
00541
00542 joints_widget_->title_->setText(
00543 QString("Edit '").append(QString::fromUtf8(this_group->name_.c_str())).append("' Joint Collection"));
00544
00545
00546 current_edit_group_ = this_group->name_;
00547 current_edit_element_ = JOINT;
00548 }
00549
00550
00551
00552
00553 void PlanningGroupsWidget::loadLinksScreen(srdf::Model::Group* this_group)
00554 {
00555
00556 const robot_model::RobotModelConstPtr& model = config_data_->getRobotModel();
00557
00558
00559 const std::vector<std::string>& links = model->getLinkModelNames();
00560
00561 if (links.size() == 0)
00562 {
00563 QMessageBox::critical(this, "Error Loading", "No links found for robot model");
00564 return;
00565 }
00566
00567
00568 links_widget_->setAvailable(links);
00569
00570
00571 links_widget_->setSelected(this_group->links_);
00572
00573
00574 links_widget_->title_->setText(
00575 QString("Edit '").append(QString::fromUtf8(this_group->name_.c_str())).append("' Link Collection"));
00576
00577
00578 current_edit_group_ = this_group->name_;
00579 current_edit_element_ = LINK;
00580 }
00581
00582
00583
00584
00585 void PlanningGroupsWidget::loadChainScreen(srdf::Model::Group* this_group)
00586 {
00587
00588 chain_widget_->setAvailable();
00589
00590
00591 if (this_group->chains_.size() > 1)
00592 {
00593 QMessageBox::warning(this, "Multiple Kinematic Chains", "Warning: This setup assistant is only designed to handle "
00594 "one kinematic chain per group. The loaded SRDF has more "
00595 "than one kinematic chain for a group. A possible loss of "
00596 "data may occur.");
00597 }
00598
00599
00600 if (this_group->chains_.size() > 0)
00601 {
00602 chain_widget_->setSelected(this_group->chains_[0].first, this_group->chains_[0].second);
00603 }
00604
00605
00606 chain_widget_->title_->setText(
00607 QString("Edit '").append(QString::fromUtf8(this_group->name_.c_str())).append("' Kinematic Chain"));
00608
00609
00610 current_edit_group_ = this_group->name_;
00611 current_edit_element_ = CHAIN;
00612 }
00613
00614
00615
00616
00617 void PlanningGroupsWidget::loadSubgroupsScreen(srdf::Model::Group* this_group)
00618 {
00619
00620 std::vector<std::string> subgroups;
00621
00622
00623 for (std::vector<srdf::Model::Group>::iterator group_it = config_data_->srdf_->groups_.begin();
00624 group_it != config_data_->srdf_->groups_.end(); ++group_it)
00625 {
00626 if (group_it->name_ != this_group->name_)
00627 {
00628
00629 subgroups.push_back(group_it->name_);
00630 }
00631 }
00632
00633
00634 subgroups_widget_->setAvailable(subgroups);
00635
00636
00637 subgroups_widget_->setSelected(this_group->subgroups_);
00638
00639
00640 subgroups_widget_->title_->setText(
00641 QString("Edit '").append(QString::fromUtf8(this_group->name_.c_str())).append("' Subgroups"));
00642
00643
00644 current_edit_group_ = this_group->name_;
00645 current_edit_element_ = SUBGROUP;
00646 }
00647
00648
00649
00650
00651 void PlanningGroupsWidget::loadGroupScreen(srdf::Model::Group* this_group)
00652 {
00653
00654 group_edit_widget_->loadKinematicPlannersComboBox();
00655
00656 if (this_group == NULL)
00657 {
00658 current_edit_group_.clear();
00659 group_edit_widget_->title_->setText("Create New Planning Group");
00660 group_edit_widget_->btn_delete_->hide();
00661 group_edit_widget_->new_buttons_widget_->show();
00662 group_edit_widget_->btn_save_->hide();
00663 }
00664 else
00665 {
00666 current_edit_group_ = this_group->name_;
00667 group_edit_widget_->title_->setText(
00668 QString("Edit Planning Group '").append(current_edit_group_.c_str()).append("'"));
00669 group_edit_widget_->btn_delete_->show();
00670 group_edit_widget_->new_buttons_widget_->hide();
00671 group_edit_widget_->btn_save_->show();
00672 }
00673
00674
00675 group_edit_widget_->setSelected(current_edit_group_);
00676
00677
00678 current_edit_element_ = GROUP;
00679 }
00680
00681
00682
00683
00684 void PlanningGroupsWidget::deleteGroup()
00685 {
00686 std::string group = current_edit_group_;
00687 if (group.empty())
00688 {
00689 QTreeWidgetItem* item = groups_tree_->currentItem();
00690
00691 if (item == NULL)
00692 return;
00693
00694 PlanGroupType plan_group = item->data(0, Qt::UserRole).value<PlanGroupType>();
00695 if (plan_group.group_)
00696 group = plan_group.group_->name_;
00697 }
00698 else
00699 current_edit_group_.clear();
00700 if (group.empty())
00701 return;
00702
00703
00704 srdf::Model::Group* searched_group = config_data_->findGroupByName(group);
00705
00706
00707 if (QMessageBox::question(
00708 this, "Confirm Group Deletion",
00709 QString("Are you sure you want to delete the planning group '")
00710 .append(searched_group->name_.c_str())
00711 .append("'? This will also delete all references in subgroups, robot poses and end effectors."),
00712 QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Cancel)
00713 {
00714 return;
00715 }
00716
00717
00718 bool haveConfirmedGroupStateDeletion = false;
00719 bool haveDeletedGroupState = true;
00720 while (haveDeletedGroupState)
00721 {
00722 haveDeletedGroupState = false;
00723 for (std::vector<srdf::Model::GroupState>::iterator pose_it = config_data_->srdf_->group_states_.begin();
00724 pose_it != config_data_->srdf_->group_states_.end(); ++pose_it)
00725 {
00726
00727 if (pose_it->group_ == searched_group->name_)
00728 {
00729 if (!haveConfirmedGroupStateDeletion)
00730 {
00731 haveConfirmedGroupStateDeletion = true;
00732
00733
00734 if (QMessageBox::question(
00735 this, "Confirm Group State Deletion",
00736 QString("The group that is about to be deleted has robot poses (robot states) that depend on this "
00737 "group. Are you sure you want to delete this group as well as all dependend robot poses?"),
00738 QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Cancel)
00739 {
00740 return;
00741 }
00742 }
00743 config_data_->changes |= MoveItConfigData::POSES;
00744
00745
00746 config_data_->srdf_->group_states_.erase(pose_it);
00747 haveDeletedGroupState = true;
00748 break;
00749 }
00750 }
00751 }
00752
00753
00754 bool haveConfirmedEndEffectorDeletion = false;
00755 bool haveDeletedEndEffector = true;
00756 while (haveDeletedEndEffector)
00757 {
00758 haveDeletedEndEffector = false;
00759 for (std::vector<srdf::Model::EndEffector>::iterator effector_it = config_data_->srdf_->end_effectors_.begin();
00760 effector_it != config_data_->srdf_->end_effectors_.end(); ++effector_it)
00761 {
00762
00763 if (effector_it->component_group_ == searched_group->name_)
00764 {
00765 if (!haveConfirmedEndEffectorDeletion)
00766 {
00767 haveConfirmedEndEffectorDeletion = true;
00768
00769
00770 if (QMessageBox::question(
00771 this, "Confirm End Effector Deletion",
00772 QString("The group that is about to be deleted has end effectors (grippers) that depend on this "
00773 "group. Are you sure you want to delete this group as well as all dependend end effectors?"),
00774 QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Cancel)
00775 {
00776 return;
00777 }
00778 }
00779 config_data_->changes |= MoveItConfigData::END_EFFECTORS;
00780
00781
00782 config_data_->srdf_->end_effectors_.erase(effector_it);
00783 haveDeletedEndEffector = true;
00784 break;
00785 }
00786 }
00787 }
00788
00789 config_data_->changes |= MoveItConfigData::GROUPS;
00790
00791
00792 for (std::vector<srdf::Model::Group>::iterator group_it = config_data_->srdf_->groups_.begin();
00793 group_it != config_data_->srdf_->groups_.end(); ++group_it)
00794 {
00795
00796 if (group_it->name_ == group)
00797 {
00798 config_data_->srdf_->groups_.erase(group_it);
00799 break;
00800 }
00801 }
00802
00803
00804 for (std::vector<srdf::Model::Group>::iterator group_it = config_data_->srdf_->groups_.begin();
00805 group_it != config_data_->srdf_->groups_.end(); ++group_it)
00806 {
00807
00808 bool deleted_subgroup = true;
00809 while (deleted_subgroup)
00810 {
00811 deleted_subgroup = false;
00812
00813
00814 for (std::vector<std::string>::iterator subgroup_it = group_it->subgroups_.begin();
00815 subgroup_it != group_it->subgroups_.end(); ++subgroup_it)
00816 {
00817
00818 if (subgroup_it->compare(group) == 0)
00819 {
00820 group_it->subgroups_.erase(subgroup_it);
00821 deleted_subgroup = true;
00822 break;
00823 }
00824 }
00825 }
00826 }
00827
00828
00829 showMainScreen();
00830
00831
00832 loadGroupsTree();
00833
00834
00835 config_data_->updateRobotModel();
00836 }
00837
00838
00839
00840
00841 void PlanningGroupsWidget::addGroup()
00842 {
00843 adding_new_group_ = true;
00844
00845
00846 loadGroupScreen(NULL);
00847
00848
00849 changeScreen(5);
00850 }
00851
00852
00853
00854
00855 void PlanningGroupsWidget::saveJointsScreen()
00856 {
00857
00858 srdf::Model::Group* searched_group = config_data_->findGroupByName(current_edit_group_);
00859
00860
00861 searched_group->joints_.clear();
00862
00863
00864 for (int i = 0; i < joints_widget_->selected_data_table_->rowCount(); ++i)
00865 {
00866 searched_group->joints_.push_back(joints_widget_->selected_data_table_->item(i, 0)->text().toStdString());
00867 }
00868
00869
00870 showMainScreen();
00871
00872
00873 loadGroupsTree();
00874
00875
00876 config_data_->updateRobotModel();
00877 config_data_->changes |= MoveItConfigData::GROUP_CONTENTS;
00878 }
00879
00880
00881
00882
00883 void PlanningGroupsWidget::saveLinksScreen()
00884 {
00885
00886 srdf::Model::Group* searched_group = config_data_->findGroupByName(current_edit_group_);
00887
00888
00889
00890 searched_group->links_.clear();
00891
00892
00893 for (int i = 0; i < links_widget_->selected_data_table_->rowCount(); ++i)
00894 {
00895 searched_group->links_.push_back(links_widget_->selected_data_table_->item(i, 0)->text().toStdString());
00896 }
00897
00898
00899 showMainScreen();
00900
00901
00902 loadGroupsTree();
00903
00904
00905 config_data_->updateRobotModel();
00906 config_data_->changes |= MoveItConfigData::GROUP_CONTENTS;
00907 }
00908
00909
00910
00911
00912 void PlanningGroupsWidget::saveChainScreen()
00913 {
00914
00915 srdf::Model::Group* searched_group = config_data_->findGroupByName(current_edit_group_);
00916
00917
00918 const std::string& tip = chain_widget_->tip_link_field_->text().toStdString();
00919 const std::string& base = chain_widget_->base_link_field_->text().toStdString();
00920
00921
00922 if ((!tip.empty() && base.empty()) || (tip.empty() && !base.empty()))
00923 {
00924 QMessageBox::warning(this, "Error Saving", "You must specify a link for both the base and tip, or leave both "
00925 "blank.");
00926 return;
00927 }
00928
00929
00930 if (!tip.empty() && !base.empty())
00931 {
00932
00933 if (tip.compare(base) == 0)
00934 {
00935 QMessageBox::warning(this, "Error Saving", "Tip and base link cannot be the same link.");
00936 return;
00937 }
00938
00939 bool found_tip = false;
00940 bool found_base = false;
00941 const std::vector<std::string>& links = config_data_->getRobotModel()->getLinkModelNames();
00942
00943 for (std::vector<std::string>::const_iterator link_it = links.begin(); link_it != links.end(); ++link_it)
00944 {
00945
00946 if (link_it->compare(tip) == 0)
00947 found_tip = true;
00948 else if (link_it->compare(base) == 0)
00949 found_base = true;
00950
00951
00952 if (found_tip && found_base)
00953 break;
00954 }
00955
00956
00957 if (!found_tip || !found_base)
00958 {
00959 QMessageBox::warning(this, "Error Saving", "Tip or base link(s) were not found in kinematic chain.");
00960 return;
00961 }
00962 }
00963
00964
00965 searched_group->chains_.clear();
00966
00967
00968 if (!tip.empty() && !base.empty())
00969 {
00970 searched_group->chains_.push_back(std::pair<std::string, std::string>(base, tip));
00971 }
00972
00973
00974 showMainScreen();
00975
00976
00977 loadGroupsTree();
00978
00979
00980 config_data_->updateRobotModel();
00981 config_data_->changes |= MoveItConfigData::GROUP_CONTENTS;
00982 }
00983
00984
00985
00986
00987 void PlanningGroupsWidget::saveSubgroupsScreen()
00988 {
00989
00990 srdf::Model::Group* searched_group = config_data_->findGroupByName(current_edit_group_);
00991
00992
00993
00994
00995 std::map<std::string, int> group_nodes;
00996
00997
00998 int node_id = 0;
00999 for (std::vector<srdf::Model::Group>::iterator group_it = config_data_->srdf_->groups_.begin();
01000 group_it != config_data_->srdf_->groups_.end(); ++group_it)
01001 {
01002
01003 group_nodes.insert(std::pair<std::string, int>(group_it->name_, node_id));
01004 ++node_id;
01005 }
01006
01007
01008 typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS> Graph;
01009 typedef boost::graph_traits<Graph>::vertex_descriptor Vertex;
01010 Graph g(group_nodes.size());
01011
01012
01013 int from_id = 0;
01014 for (std::vector<srdf::Model::Group>::iterator group_it = config_data_->srdf_->groups_.begin();
01015 group_it != config_data_->srdf_->groups_.end(); ++group_it)
01016 {
01017
01018 if (group_it->name_ == searched_group->name_)
01019 {
01020
01021 for (int i = 0; i < subgroups_widget_->selected_data_table_->rowCount(); ++i)
01022 {
01023
01024 const std::string to_string = subgroups_widget_->selected_data_table_->item(i, 0)->text().toStdString();
01025
01026
01027 int to_id = group_nodes[to_string];
01028
01029
01030 add_edge(from_id, to_id, g);
01031 }
01032 }
01033 else
01034 {
01035
01036 for (unsigned int i = 0; i < group_it->subgroups_.size(); ++i)
01037 {
01038
01039 const std::string to_string = group_it->subgroups_.at(i);
01040
01041
01042 int to_id = group_nodes[to_string];
01043
01044
01045 add_edge(from_id, to_id, g);
01046 }
01047 }
01048
01049 ++from_id;
01050 }
01051
01052
01053 bool has_cycle = false;
01054 cycle_detector vis(has_cycle);
01055 boost::depth_first_search(g, visitor(vis));
01056
01057 if (has_cycle)
01058 {
01059
01060 QMessageBox::warning(this, "Error Saving", "Depth first search reveals a cycle in the subgroups");
01061 return;
01062 }
01063
01064
01065 searched_group->subgroups_.clear();
01066
01067
01068 for (int i = 0; i < subgroups_widget_->selected_data_table_->rowCount(); ++i)
01069 {
01070 searched_group->subgroups_.push_back(subgroups_widget_->selected_data_table_->item(i, 0)->text().toStdString());
01071 }
01072
01073
01074 showMainScreen();
01075
01076
01077 loadGroupsTree();
01078
01079
01080 config_data_->updateRobotModel();
01081 config_data_->changes |= MoveItConfigData::GROUP_CONTENTS;
01082 }
01083
01084
01085
01086
01087 bool PlanningGroupsWidget::saveGroupScreen()
01088 {
01089
01090 const std::string& group_name = group_edit_widget_->group_name_field_->text().toStdString();
01091 const std::string& kinematics_solver = group_edit_widget_->kinematics_solver_field_->currentText().toStdString();
01092 const std::string& kinematics_resolution = group_edit_widget_->kinematics_resolution_field_->text().toStdString();
01093 const std::string& kinematics_timeout = group_edit_widget_->kinematics_timeout_field_->text().toStdString();
01094 const std::string& kinematics_attempts = group_edit_widget_->kinematics_attempts_field_->text().toStdString();
01095
01096
01097 srdf::Model::Group* searched_group = NULL;
01098
01099
01100 if (group_name.empty())
01101 {
01102 QMessageBox::warning(this, "Error Saving", "A name must be given for the group!");
01103 return false;
01104 }
01105
01106
01107 if (!current_edit_group_.empty())
01108 {
01109
01110 searched_group = config_data_->findGroupByName(current_edit_group_);
01111 }
01112
01113
01114 for (std::vector<srdf::Model::Group>::const_iterator group_it = config_data_->srdf_->groups_.begin();
01115 group_it != config_data_->srdf_->groups_.end(); ++group_it)
01116 {
01117 if (group_it->name_.compare(group_name) == 0)
01118 {
01119
01120 if (&(*group_it) != searched_group)
01121 {
01122 QMessageBox::warning(this, "Error Saving", "A group already exists with that name!");
01123 return false;
01124 }
01125 }
01126 }
01127
01128
01129 double kinematics_resolution_double;
01130 try
01131 {
01132 kinematics_resolution_double = boost::lexical_cast<double>(kinematics_resolution);
01133 }
01134 catch (boost::bad_lexical_cast&)
01135 {
01136 QMessageBox::warning(this, "Error Saving", "Unable to convert kinematics resolution to a double number.");
01137 return false;
01138 }
01139
01140
01141 double kinematics_timeout_double;
01142 try
01143 {
01144 kinematics_timeout_double = boost::lexical_cast<double>(kinematics_timeout);
01145 }
01146 catch (boost::bad_lexical_cast&)
01147 {
01148 QMessageBox::warning(this, "Error Saving", "Unable to convert kinematics solver timeout to a double number.");
01149 return false;
01150 }
01151
01152
01153 int kinematics_attempts_int;
01154 try
01155 {
01156 kinematics_attempts_int = boost::lexical_cast<int>(kinematics_attempts);
01157 }
01158 catch (boost::bad_lexical_cast&)
01159 {
01160 QMessageBox::warning(this, "Error Saving", "Unable to convert kinematics solver attempts to an int number.");
01161 return false;
01162 }
01163
01164
01165 if (kinematics_resolution_double <= 0)
01166 {
01167 QMessageBox::warning(this, "Error Saving", "Kinematics solver search resolution must be greater than 0.");
01168 return false;
01169 }
01170 if (kinematics_timeout_double <= 0)
01171 {
01172 QMessageBox::warning(this, "Error Saving", "Kinematics solver search timeout must be greater than 0.");
01173 return false;
01174 }
01175 if (kinematics_attempts_int <= 0)
01176 {
01177 QMessageBox::warning(this, "Error Saving", "Kinematics solver attempts must be greater than 0.");
01178 return false;
01179 }
01180
01181 adding_new_group_ = false;
01182
01183
01184 if (searched_group == NULL)
01185 {
01186 srdf::Model::Group new_group;
01187 new_group.name_ = group_name;
01188 config_data_->srdf_->groups_.push_back(new_group);
01189 adding_new_group_ = true;
01190 config_data_->changes |= MoveItConfigData::GROUPS;
01191 }
01192 else
01193 {
01194
01195 const std::string old_group_name = searched_group->name_;
01196
01197
01198 searched_group->name_ = group_name;
01199
01200
01201
01202 for (std::vector<srdf::Model::Group>::iterator group_it = config_data_->srdf_->groups_.begin();
01203 group_it != config_data_->srdf_->groups_.end(); ++group_it)
01204 {
01205
01206 for (std::vector<std::string>::iterator subgroup_it = group_it->subgroups_.begin();
01207 subgroup_it != group_it->subgroups_.end(); ++subgroup_it)
01208 {
01209
01210 if (subgroup_it->compare(old_group_name) == 0)
01211 {
01212 subgroup_it->assign(group_name);
01213 config_data_->changes |= MoveItConfigData::GROUP_CONTENTS;
01214 }
01215 }
01216 }
01217
01218
01219 for (std::vector<srdf::Model::EndEffector>::iterator eef_it = config_data_->srdf_->end_effectors_.begin();
01220 eef_it != config_data_->srdf_->end_effectors_.end(); ++eef_it)
01221 {
01222
01223 if (eef_it->parent_group_.compare(old_group_name) == 0)
01224 {
01225 ROS_DEBUG_STREAM_NAMED("setup_assistant", "Changed eef '" << eef_it->name_ << "' to new parent group name "
01226 << group_name);
01227 eef_it->parent_group_ = group_name;
01228 config_data_->changes |= MoveItConfigData::END_EFFECTORS;
01229 }
01230
01231
01232 if (eef_it->component_group_.compare(old_group_name) == 0)
01233 {
01234 ROS_DEBUG_STREAM_NAMED("setup_assistant", "Changed eef '" << eef_it->name_ << "' to new group name "
01235 << group_name);
01236 eef_it->component_group_ = group_name;
01237 config_data_->changes |= MoveItConfigData::END_EFFECTORS;
01238 }
01239 }
01240
01241
01242 for (std::vector<srdf::Model::GroupState>::iterator state_it = config_data_->srdf_->group_states_.begin();
01243 state_it != config_data_->srdf_->group_states_.end(); ++state_it)
01244 {
01245
01246 if (state_it->group_.compare(old_group_name) == 0)
01247 {
01248 ROS_DEBUG_STREAM_NAMED("setup_assistant", "Changed group state group '" << state_it->group_
01249 << "' to new parent group name "
01250 << group_name);
01251 state_it->group_ = group_name;
01252 config_data_->changes |= MoveItConfigData::POSES;
01253 }
01254 }
01255
01256
01257 config_data_->updateRobotModel();
01258 }
01259
01260
01261 config_data_->group_meta_data_[group_name].kinematics_solver_ = kinematics_solver;
01262 config_data_->group_meta_data_[group_name].kinematics_solver_search_resolution_ = kinematics_resolution_double;
01263 config_data_->group_meta_data_[group_name].kinematics_solver_timeout_ = kinematics_timeout_double;
01264 config_data_->group_meta_data_[group_name].kinematics_solver_attempts_ = kinematics_attempts_int;
01265 config_data_->changes |= MoveItConfigData::GROUP_KINEMATICS;
01266
01267
01268 loadGroupsTree();
01269
01270
01271 current_edit_group_ = group_name;
01272
01273 return true;
01274 }
01275
01276
01277
01278
01279 void PlanningGroupsWidget::saveGroupScreenEdit()
01280 {
01281
01282 if (!saveGroupScreen())
01283 return;
01284
01285
01286 showMainScreen();
01287 }
01288
01289
01290
01291
01292 void PlanningGroupsWidget::saveGroupScreenJoints()
01293 {
01294
01295 if (!saveGroupScreen())
01296 return;
01297
01298
01299 loadJointsScreen(config_data_->findGroupByName(current_edit_group_));
01300
01301
01302 changeScreen(1);
01303 }
01304
01305
01306
01307
01308 void PlanningGroupsWidget::saveGroupScreenLinks()
01309 {
01310
01311 if (!saveGroupScreen())
01312 return;
01313
01314
01315 loadLinksScreen(config_data_->findGroupByName(current_edit_group_));
01316
01317
01318 changeScreen(2);
01319 }
01320
01321
01322
01323
01324 void PlanningGroupsWidget::saveGroupScreenChain()
01325 {
01326
01327 if (!saveGroupScreen())
01328 return;
01329
01330
01331 loadChainScreen(config_data_->findGroupByName(current_edit_group_));
01332
01333
01334 changeScreen(3);
01335 }
01336
01337
01338
01339
01340 void PlanningGroupsWidget::saveGroupScreenSubgroups()
01341 {
01342
01343 if (!saveGroupScreen())
01344 return;
01345
01346
01347 loadSubgroupsScreen(config_data_->findGroupByName(current_edit_group_));
01348
01349
01350 changeScreen(4);
01351 }
01352
01353
01354
01355
01356 void PlanningGroupsWidget::cancelEditing()
01357 {
01358 if (!current_edit_group_.empty() && adding_new_group_)
01359 {
01360 srdf::Model::Group* editing = config_data_->findGroupByName(current_edit_group_);
01361 if (editing && editing->joints_.empty() && editing->links_.empty() && editing->chains_.empty() &&
01362 editing->subgroups_.empty())
01363 {
01364 config_data_->group_meta_data_.erase(editing->name_);
01365 for (std::vector<srdf::Model::Group>::iterator group_it = config_data_->srdf_->groups_.begin();
01366 group_it != config_data_->srdf_->groups_.end(); ++group_it)
01367 if (&(*group_it) == editing)
01368 {
01369 config_data_->srdf_->groups_.erase(group_it);
01370 break;
01371 }
01372 current_edit_group_.clear();
01373
01374 loadGroupsTree();
01375 }
01376 }
01377
01378
01379 showMainScreen();
01380 }
01381
01382
01383
01384
01385 void PlanningGroupsWidget::focusGiven()
01386 {
01387
01388 showMainScreen();
01389
01390
01391 loadGroupsTree();
01392 }
01393
01394
01395
01396
01397 void PlanningGroupsWidget::alterTree(const QString& link)
01398 {
01399 if (link.contains("expand"))
01400 groups_tree_->expandAll();
01401 else
01402 groups_tree_->collapseAll();
01403 }
01404
01405
01406
01407
01408 void PlanningGroupsWidget::showMainScreen()
01409 {
01410 stacked_layout_->setCurrentIndex(0);
01411
01412
01413 Q_EMIT isModal(false);
01414 }
01415
01416
01417
01418
01419 void PlanningGroupsWidget::changeScreen(int index)
01420 {
01421 stacked_layout_->setCurrentIndex(index);
01422
01423
01424 Q_EMIT isModal(index != 0);
01425 }
01426
01427
01428
01429
01430 void PlanningGroupsWidget::previewSelectedLink(std::vector<std::string> links)
01431 {
01432
01433 Q_EMIT unhighlightAll();
01434
01435 for (int i = 0; i < links.size(); ++i)
01436 {
01437 if (links[i].empty())
01438 {
01439 continue;
01440 }
01441
01442
01443 Q_EMIT highlightLink(links[i], QColor(255, 0, 0));
01444 }
01445 }
01446
01447
01448
01449
01450 void PlanningGroupsWidget::previewSelectedJoints(std::vector<std::string> joints)
01451 {
01452
01453 Q_EMIT unhighlightAll();
01454
01455 for (int i = 0; i < joints.size(); ++i)
01456 {
01457 const robot_model::JointModel* joint_model = config_data_->getRobotModel()->getJointModel(joints[i]);
01458
01459
01460 if (!joint_model)
01461 {
01462 continue;
01463 }
01464
01465
01466 const std::string link = joint_model->getChildLinkModel()->getName();
01467
01468 if (link.empty())
01469 {
01470 continue;
01471 }
01472
01473
01474 Q_EMIT highlightLink(link, QColor(255, 0, 0));
01475 }
01476 }
01477
01478
01479
01480
01481 void PlanningGroupsWidget::previewSelectedSubgroup(std::vector<std::string> groups)
01482 {
01483
01484 Q_EMIT unhighlightAll();
01485
01486 for (int i = 0; i < groups.size(); ++i)
01487 {
01488
01489 Q_EMIT highlightGroup(groups[i]);
01490 }
01491 }
01492
01493 }
01494
01495
01496
01497
01498
01499
01500
01501 PlanGroupType::PlanGroupType(srdf::Model::Group* group, const moveit_setup_assistant::GroupType type)
01502 : group_(group), type_(type)
01503 {
01504 }