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 #include "virtual_joints_widget.h"
00039
00040 #include <QFormLayout>
00041 #include <QMessageBox>
00042 #include <QApplication>
00043
00044 namespace moveit_setup_assistant
00045 {
00046
00047
00048
00049 VirtualJointsWidget::VirtualJointsWidget(QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data)
00050 : SetupScreenWidget(parent), config_data_(config_data)
00051 {
00052
00053 QVBoxLayout* layout = new QVBoxLayout();
00054
00055
00056
00057 HeaderWidget* header =
00058 new HeaderWidget("Virtual Joints", "Define a virtual joint between a robot link and an external frame of "
00059 "reference (considered fixed with respect to the robot).",
00060 this);
00061 layout->addWidget(header);
00062
00063
00064
00065 vjoint_list_widget_ = createContentsWidget();
00066 vjoint_edit_widget_ = createEditWidget();
00067
00068
00069 stacked_layout_ = new QStackedLayout(this);
00070 stacked_layout_->addWidget(vjoint_list_widget_);
00071 stacked_layout_->addWidget(vjoint_edit_widget_);
00072
00073
00074 QWidget* stacked_layout_widget = new QWidget(this);
00075 stacked_layout_widget->setLayout(stacked_layout_);
00076
00077 layout->addWidget(stacked_layout_widget);
00078
00079
00080 this->setLayout(layout);
00081 }
00082
00083
00084
00085
00086 QWidget* VirtualJointsWidget::createContentsWidget()
00087 {
00088
00089 QWidget* content_widget = new QWidget(this);
00090
00091
00092 QVBoxLayout* layout = new QVBoxLayout(this);
00093
00094
00095
00096 data_table_ = new QTableWidget(this);
00097 data_table_->setColumnCount(4);
00098 data_table_->setSortingEnabled(true);
00099 data_table_->setSelectionBehavior(QAbstractItemView::SelectRows);
00100 connect(data_table_, SIGNAL(cellDoubleClicked(int, int)), this, SLOT(editDoubleClicked(int, int)));
00101 connect(data_table_, SIGNAL(cellClicked(int, int)), this, SLOT(previewClicked(int, int)));
00102 layout->addWidget(data_table_);
00103
00104
00105 QStringList header_list;
00106 header_list.append("Virtual Joint Name");
00107 header_list.append("Child Link");
00108 header_list.append("Parent Frame");
00109 header_list.append("Type");
00110 data_table_->setHorizontalHeaderLabels(header_list);
00111
00112
00113
00114 QHBoxLayout* controls_layout = new QHBoxLayout();
00115
00116
00117 QWidget* spacer = new QWidget(this);
00118 spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00119 controls_layout->addWidget(spacer);
00120
00121
00122 btn_edit_ = new QPushButton("&Edit Selected", this);
00123 btn_edit_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00124 btn_edit_->setMaximumWidth(300);
00125 btn_edit_->hide();
00126 connect(btn_edit_, SIGNAL(clicked()), this, SLOT(editSelected()));
00127 controls_layout->addWidget(btn_edit_);
00128 controls_layout->setAlignment(btn_edit_, Qt::AlignRight);
00129
00130
00131 btn_delete_ = new QPushButton("&Delete Selected", this);
00132 connect(btn_delete_, SIGNAL(clicked()), this, SLOT(deleteSelected()));
00133 controls_layout->addWidget(btn_delete_);
00134 controls_layout->setAlignment(btn_delete_, Qt::AlignRight);
00135
00136
00137 QPushButton* btn_add = new QPushButton("&Add Virtual Joint", this);
00138 btn_add->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00139 btn_add->setMaximumWidth(300);
00140 connect(btn_add, SIGNAL(clicked()), this, SLOT(showNewScreen()));
00141 controls_layout->addWidget(btn_add);
00142 controls_layout->setAlignment(btn_add, Qt::AlignRight);
00143
00144
00145 layout->addLayout(controls_layout);
00146
00147
00148 content_widget->setLayout(layout);
00149
00150 return content_widget;
00151 }
00152
00153
00154
00155
00156 QWidget* VirtualJointsWidget::createEditWidget()
00157 {
00158
00159 QWidget* edit_widget = new QWidget(this);
00160
00161 QVBoxLayout* layout = new QVBoxLayout();
00162
00163
00164 QFormLayout* form_layout = new QFormLayout();
00165
00166 form_layout->setRowWrapPolicy(QFormLayout::WrapAllRows);
00167
00168
00169 vjoint_name_field_ = new QLineEdit(this);
00170 form_layout->addRow("Virtual Joint Name:", vjoint_name_field_);
00171
00172
00173 child_link_field_ = new QComboBox(this);
00174 child_link_field_->setEditable(false);
00175 form_layout->addRow("Child Link:", child_link_field_);
00176
00177
00178 parent_name_field_ = new QLineEdit(this);
00179 form_layout->addRow("Parent Frame Name:", parent_name_field_);
00180
00181
00182 joint_type_field_ = new QComboBox(this);
00183 joint_type_field_->setEditable(false);
00184 loadJointTypesComboBox();
00185
00186
00187 form_layout->addRow("Joint Type:", joint_type_field_);
00188
00189 layout->addLayout(form_layout);
00190
00191
00192
00193 QHBoxLayout* controls_layout = new QHBoxLayout();
00194 controls_layout->setContentsMargins(0, 25, 0, 15);
00195
00196
00197 QWidget* spacer = new QWidget(this);
00198 spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00199 controls_layout->addWidget(spacer);
00200
00201
00202 QPushButton* btn_save_ = new QPushButton("&Save", this);
00203 btn_save_->setMaximumWidth(200);
00204 connect(btn_save_, SIGNAL(clicked()), this, SLOT(doneEditing()));
00205 controls_layout->addWidget(btn_save_);
00206 controls_layout->setAlignment(btn_save_, Qt::AlignRight);
00207
00208
00209 QPushButton* btn_cancel_ = new QPushButton("&Cancel", this);
00210 btn_cancel_->setMaximumWidth(200);
00211 connect(btn_cancel_, SIGNAL(clicked()), this, SLOT(cancelEditing()));
00212 controls_layout->addWidget(btn_cancel_);
00213 controls_layout->setAlignment(btn_cancel_, Qt::AlignRight);
00214
00215
00216 layout->addLayout(controls_layout);
00217
00218
00219 edit_widget->setLayout(layout);
00220
00221 return edit_widget;
00222 }
00223
00224
00225
00226
00227 void VirtualJointsWidget::showNewScreen()
00228 {
00229
00230 current_edit_vjoint_.clear();
00231
00232
00233 vjoint_name_field_->setText("");
00234 parent_name_field_->setText("");
00235 child_link_field_->clearEditText();
00236 joint_type_field_->clearEditText();
00237
00238
00239 stacked_layout_->setCurrentIndex(1);
00240
00241
00242 Q_EMIT isModal(true);
00243 }
00244
00245
00246
00247
00248 void VirtualJointsWidget::editDoubleClicked(int row, int column)
00249 {
00250 editSelected();
00251 }
00252
00253
00254
00255
00256 void VirtualJointsWidget::previewClicked(int row, int column)
00257 {
00258
00259
00260
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276
00277
00278
00279
00280
00281 }
00282
00283
00284
00285
00286 void VirtualJointsWidget::editSelected()
00287 {
00288
00289 QList<QTableWidgetItem*> selected = data_table_->selectedItems();
00290
00291
00292 if (!selected.size())
00293 return;
00294
00295
00296 edit(selected[0]->text().toStdString());
00297 }
00298
00299
00300
00301
00302 void VirtualJointsWidget::edit(const std::string& name)
00303 {
00304
00305 current_edit_vjoint_ = name;
00306
00307
00308 srdf::Model::VirtualJoint* vjoint = findVJointByName(name);
00309
00310
00311 vjoint_name_field_->setText(vjoint->name_.c_str());
00312 parent_name_field_->setText(vjoint->parent_frame_.c_str());
00313
00314
00315 int index = child_link_field_->findText(vjoint->child_link_.c_str());
00316 if (index == -1)
00317 {
00318 QMessageBox::critical(this, "Error Loading", "Unable to find child link in drop down box");
00319 return;
00320 }
00321 child_link_field_->setCurrentIndex(index);
00322
00323
00324 index = joint_type_field_->findText(vjoint->type_.c_str());
00325 if (index == -1)
00326 {
00327 QMessageBox::critical(this, "Error Loading", "Unable to find joint type in drop down box");
00328 return;
00329 }
00330 joint_type_field_->setCurrentIndex(index);
00331
00332
00333 stacked_layout_->setCurrentIndex(1);
00334
00335
00336 Q_EMIT isModal(true);
00337 }
00338
00339
00340
00341
00342 void VirtualJointsWidget::loadJointTypesComboBox()
00343 {
00344
00345 joint_type_field_->clear();
00346
00347
00348 joint_type_field_->addItem("fixed");
00349 joint_type_field_->addItem("floating");
00350 joint_type_field_->addItem("planar");
00351 }
00352
00353
00354
00355
00356 void VirtualJointsWidget::loadChildLinksComboBox()
00357 {
00358
00359 child_link_field_->clear();
00360
00361
00362 std::vector<const robot_model::LinkModel*> link_models = config_data_->getRobotModel()->getLinkModels();
00363
00364
00365 for (std::vector<const robot_model::LinkModel*>::const_iterator link_it = link_models.begin();
00366 link_it < link_models.end(); ++link_it)
00367 {
00368 child_link_field_->addItem((*link_it)->getName().c_str());
00369 }
00370 }
00371
00372
00373
00374
00375 srdf::Model::VirtualJoint* VirtualJointsWidget::findVJointByName(const std::string& name)
00376 {
00377
00378 srdf::Model::VirtualJoint* searched_group = NULL;
00379
00380 for (std::vector<srdf::Model::VirtualJoint>::iterator vjoint_it = config_data_->srdf_->virtual_joints_.begin();
00381 vjoint_it != config_data_->srdf_->virtual_joints_.end(); ++vjoint_it)
00382 {
00383 if (vjoint_it->name_ == name)
00384 {
00385 searched_group = &(*vjoint_it);
00386 break;
00387 }
00388 }
00389
00390
00391 if (searched_group == NULL)
00392 {
00393 QMessageBox::critical(this, "Error Saving", "An internal error has occured while saving. Quitting.");
00394 QApplication::quit();
00395 }
00396
00397 return searched_group;
00398 }
00399
00400
00401
00402
00403 void VirtualJointsWidget::deleteSelected()
00404 {
00405
00406 QList<QTableWidgetItem*> selected = data_table_->selectedItems();
00407
00408
00409 if (!selected.size())
00410 return;
00411
00412
00413 current_edit_vjoint_ = selected[0]->text().toStdString();
00414
00415
00416 if (QMessageBox::question(this, "Confirm Virtual Joint Deletion",
00417 QString("Are you sure you want to delete the virtual joint '")
00418 .append(current_edit_vjoint_.c_str())
00419 .append("'?"),
00420 QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Cancel)
00421 {
00422 return;
00423 }
00424
00425
00426 for (std::vector<srdf::Model::VirtualJoint>::iterator vjoint_it = config_data_->srdf_->virtual_joints_.begin();
00427 vjoint_it != config_data_->srdf_->virtual_joints_.end(); ++vjoint_it)
00428 {
00429
00430 if (vjoint_it->name_ == current_edit_vjoint_)
00431 {
00432 config_data_->srdf_->virtual_joints_.erase(vjoint_it);
00433 break;
00434 }
00435 }
00436
00437
00438 loadDataTable();
00439 config_data_->changes |= MoveItConfigData::VIRTUAL_JOINTS;
00440 }
00441
00442
00443
00444
00445 void VirtualJointsWidget::doneEditing()
00446 {
00447
00448 const std::string vjoint_name = vjoint_name_field_->text().toStdString();
00449 const std::string parent_name = parent_name_field_->text().toStdString();
00450
00451
00452 srdf::Model::VirtualJoint* searched_data = NULL;
00453
00454
00455 if (vjoint_name.empty())
00456 {
00457 QMessageBox::warning(this, "Error Saving", "A name must be given for the virtual joint!");
00458 return;
00459 }
00460
00461
00462 if (parent_name.empty())
00463 {
00464 QMessageBox::warning(this, "Error Saving", "A name must be given for the parent frame");
00465 return;
00466 }
00467
00468
00469 if (!current_edit_vjoint_.empty())
00470 {
00471
00472 searched_data = findVJointByName(current_edit_vjoint_);
00473 }
00474
00475
00476 for (std::vector<srdf::Model::VirtualJoint>::const_iterator data_it = config_data_->srdf_->virtual_joints_.begin();
00477 data_it != config_data_->srdf_->virtual_joints_.end(); ++data_it)
00478 {
00479 if (data_it->name_.compare(vjoint_name) == 0)
00480 {
00481
00482 if (&(*data_it) != searched_data)
00483 {
00484 QMessageBox::warning(this, "Error Saving", "A virtual joint already exists with that name!");
00485 return;
00486 }
00487 }
00488 }
00489
00490
00491 if (joint_type_field_->currentText().isEmpty())
00492 {
00493 QMessageBox::warning(this, "Error Saving", "A joint type must be chosen!");
00494 return;
00495 }
00496
00497
00498 if (child_link_field_->currentText().isEmpty())
00499 {
00500 QMessageBox::warning(this, "Error Saving", "A child link must be chosen!");
00501 return;
00502 }
00503
00504 config_data_->changes |= MoveItConfigData::VIRTUAL_JOINTS;
00505
00506
00507 bool isNew = false;
00508
00509 if (searched_data == NULL)
00510 {
00511 isNew = true;
00512
00513 searched_data = new srdf::Model::VirtualJoint();
00514 }
00515
00516
00517 searched_data->name_ = vjoint_name;
00518 searched_data->parent_frame_ = parent_name;
00519 searched_data->child_link_ = child_link_field_->currentText().toStdString();
00520 searched_data->type_ = joint_type_field_->currentText().toStdString();
00521
00522 bool emit_frame_notice = false;
00523
00524
00525 if (isNew)
00526 {
00527 if (searched_data->child_link_ == config_data_->getRobotModel()->getRootLinkName())
00528 emit_frame_notice = true;
00529 config_data_->srdf_->virtual_joints_.push_back(*searched_data);
00530 config_data_->updateRobotModel();
00531 }
00532
00533
00534
00535
00536 loadDataTable();
00537
00538
00539 stacked_layout_->setCurrentIndex(0);
00540
00541
00542 Q_EMIT isModal(false);
00543
00544
00545 if (emit_frame_notice)
00546 {
00547 Q_EMIT referenceFrameChanged();
00548 }
00549 }
00550
00551
00552
00553
00554 void VirtualJointsWidget::cancelEditing()
00555 {
00556
00557 stacked_layout_->setCurrentIndex(0);
00558
00559
00560 Q_EMIT isModal(false);
00561 }
00562
00563
00564
00565
00566 void VirtualJointsWidget::loadDataTable()
00567 {
00568
00569 data_table_->setUpdatesEnabled(false);
00570 data_table_->setDisabled(true);
00571 data_table_->clearContents();
00572
00573
00574 data_table_->setRowCount(config_data_->srdf_->virtual_joints_.size());
00575
00576
00577 int row = 0;
00578 for (std::vector<srdf::Model::VirtualJoint>::const_iterator data_it = config_data_->srdf_->virtual_joints_.begin();
00579 data_it != config_data_->srdf_->virtual_joints_.end(); ++data_it)
00580 {
00581
00582 QTableWidgetItem* data_name = new QTableWidgetItem(data_it->name_.c_str());
00583 data_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
00584 QTableWidgetItem* child_link_name = new QTableWidgetItem(data_it->child_link_.c_str());
00585 child_link_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
00586 QTableWidgetItem* parent_frame_name = new QTableWidgetItem(data_it->parent_frame_.c_str());
00587 parent_frame_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
00588 QTableWidgetItem* type_name = new QTableWidgetItem(data_it->type_.c_str());
00589 type_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
00590
00591
00592 data_table_->setItem(row, 0, data_name);
00593 data_table_->setItem(row, 1, child_link_name);
00594 data_table_->setItem(row, 2, parent_frame_name);
00595 data_table_->setItem(row, 3, type_name);
00596
00597
00598 ++row;
00599 }
00600
00601
00602 data_table_->setUpdatesEnabled(true);
00603 data_table_->setDisabled(false);
00604
00605
00606 data_table_->resizeColumnToContents(0);
00607 data_table_->resizeColumnToContents(1);
00608 data_table_->resizeColumnToContents(2);
00609 data_table_->resizeColumnToContents(3);
00610
00611
00612 if (config_data_->srdf_->virtual_joints_.size())
00613 btn_edit_->show();
00614 }
00615
00616
00617
00618
00619 void VirtualJointsWidget::focusGiven()
00620 {
00621
00622 stacked_layout_->setCurrentIndex(0);
00623
00624
00625 loadDataTable();
00626
00627
00628 loadChildLinksComboBox();
00629 }
00630
00631 }