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 "robot_poses_widget.h"
00039 #include <moveit_msgs/JointLimits.h>
00040
00041 #include <QFormLayout>
00042 #include <QMessageBox>
00043 #include <QDoubleValidator>
00044 #include <QApplication>
00045
00046 #include <moveit/robot_state/conversions.h>
00047 #include <moveit_msgs/DisplayRobotState.h>
00048
00049 namespace moveit_setup_assistant
00050 {
00051
00052
00053
00054 RobotPosesWidget::RobotPosesWidget(QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data)
00055 : SetupScreenWidget(parent), config_data_(config_data)
00056 {
00057
00058 joint_list_layout_ = NULL;
00059
00060
00061 QVBoxLayout* layout = new QVBoxLayout();
00062
00063
00064
00065 HeaderWidget* header =
00066 new HeaderWidget("Robot Poses", "Create poses for the robot. Poses are defined as sets of joint values for "
00067 "particular planning groups. This is useful for things like <i>folded arms</i>.",
00068 this);
00069 layout->addWidget(header);
00070
00071
00072 pose_list_widget_ = createContentsWidget();
00073 pose_edit_widget_ = createEditWidget();
00074
00075
00076 stacked_layout_ = new QStackedLayout(this);
00077 stacked_layout_->addWidget(pose_list_widget_);
00078 stacked_layout_->addWidget(pose_edit_widget_);
00079
00080
00081 QWidget* stacked_layout_widget = new QWidget(this);
00082 stacked_layout_widget->setLayout(stacked_layout_);
00083
00084 layout->addWidget(stacked_layout_widget);
00085
00086
00087 this->setLayout(layout);
00088
00089
00090 ros::NodeHandle nh;
00091
00092
00093 pub_robot_state_ = nh.advertise<moveit_msgs::DisplayRobotState>(MOVEIT_ROBOT_STATE, 1);
00094
00095
00096 config_data_->getPlanningScene()->setName("MoveIt Planning Scene");
00097
00098
00099
00100
00101 request.contacts = true;
00102 request.max_contacts = 1;
00103 request.max_contacts_per_pair = 1;
00104 request.verbose = false;
00105 }
00106
00107
00108
00109
00110 QWidget* RobotPosesWidget::createContentsWidget()
00111 {
00112
00113 QWidget* content_widget = new QWidget(this);
00114
00115
00116 QVBoxLayout* layout = new QVBoxLayout(this);
00117
00118
00119
00120 data_table_ = new QTableWidget(this);
00121 data_table_->setColumnCount(2);
00122 data_table_->setSortingEnabled(true);
00123 data_table_->setSelectionBehavior(QAbstractItemView::SelectRows);
00124 connect(data_table_, SIGNAL(cellDoubleClicked(int, int)), this, SLOT(editDoubleClicked(int, int)));
00125 connect(data_table_, SIGNAL(cellClicked(int, int)), this, SLOT(previewClicked(int, int)));
00126 layout->addWidget(data_table_);
00127
00128
00129 QStringList header_list;
00130 header_list.append("Pose Name");
00131 header_list.append("Group Name");
00132 data_table_->setHorizontalHeaderLabels(header_list);
00133
00134
00135
00136 QHBoxLayout* controls_layout = new QHBoxLayout();
00137
00138
00139 QPushButton* btn_default = new QPushButton("&Show Default Pose", this);
00140 btn_default->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00141 btn_default->setMaximumWidth(300);
00142 connect(btn_default, SIGNAL(clicked()), this, SLOT(showDefaultPose()));
00143 controls_layout->addWidget(btn_default);
00144 controls_layout->setAlignment(btn_default, Qt::AlignLeft);
00145
00146
00147 QPushButton* btn_play = new QPushButton("&MoveIt!", this);
00148 btn_play->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00149 btn_play->setMaximumWidth(300);
00150 connect(btn_play, SIGNAL(clicked()), this, SLOT(playPoses()));
00151 controls_layout->addWidget(btn_play);
00152 controls_layout->setAlignment(btn_play, Qt::AlignLeft);
00153
00154
00155 QWidget* spacer = new QWidget(this);
00156 spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00157 controls_layout->addWidget(spacer);
00158
00159
00160 btn_edit_ = new QPushButton("&Edit Selected", this);
00161 btn_edit_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00162 btn_edit_->setMaximumWidth(300);
00163 btn_edit_->hide();
00164 connect(btn_edit_, SIGNAL(clicked()), this, SLOT(editSelected()));
00165 controls_layout->addWidget(btn_edit_);
00166 controls_layout->setAlignment(btn_edit_, Qt::AlignRight);
00167
00168
00169 btn_delete_ = new QPushButton("&Delete Selected", this);
00170 connect(btn_delete_, SIGNAL(clicked()), this, SLOT(deleteSelected()));
00171 controls_layout->addWidget(btn_delete_);
00172 controls_layout->setAlignment(btn_delete_, Qt::AlignRight);
00173
00174
00175 QPushButton* btn_add = new QPushButton("&Add Pose", this);
00176 btn_add->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00177 btn_add->setMaximumWidth(300);
00178 connect(btn_add, SIGNAL(clicked()), this, SLOT(showNewScreen()));
00179 controls_layout->addWidget(btn_add);
00180 controls_layout->setAlignment(btn_add, Qt::AlignRight);
00181
00182
00183 layout->addLayout(controls_layout);
00184
00185
00186 content_widget->setLayout(layout);
00187
00188 return content_widget;
00189 }
00190
00191
00192
00193
00194 QWidget* RobotPosesWidget::createEditWidget()
00195 {
00196
00197 QWidget* edit_widget = new QWidget(this);
00198
00199 QVBoxLayout* layout = new QVBoxLayout();
00200
00201
00202
00203 QHBoxLayout* columns_layout = new QHBoxLayout();
00204 QVBoxLayout* column1 = new QVBoxLayout();
00205 column2_ = new QVBoxLayout();
00206
00207
00208
00209
00210 QFormLayout* form_layout = new QFormLayout();
00211
00212 form_layout->setRowWrapPolicy(QFormLayout::WrapAllRows);
00213
00214
00215 pose_name_field_ = new QLineEdit(this);
00216
00217 form_layout->addRow("Pose Name:", pose_name_field_);
00218
00219
00220 group_name_field_ = new QComboBox(this);
00221 group_name_field_->setEditable(false);
00222
00223 connect(group_name_field_, SIGNAL(currentIndexChanged(const QString&)), this, SLOT(loadJointSliders(const QString&)));
00224
00225 form_layout->addRow("Planning Group:", group_name_field_);
00226
00227
00228 collision_warning_ = new QLabel("<font color='red'><b>Robot in Collision State</b></font>", this);
00229 collision_warning_->setTextFormat(Qt::RichText);
00230 collision_warning_->hide();
00231 form_layout->addRow(" ", collision_warning_);
00232
00233 column1->addLayout(form_layout);
00234 columns_layout->addLayout(column1);
00235
00236
00237
00238
00239 joint_list_widget_ = new QWidget(this);
00240
00241
00242 scroll_area_ = new QScrollArea(this);
00243
00244 scroll_area_->setWidget(joint_list_widget_);
00245
00246 column2_->addWidget(scroll_area_);
00247
00248 columns_layout->addLayout(column2_);
00249
00250
00251 layout->addLayout(columns_layout);
00252
00253
00254
00255 QHBoxLayout* controls_layout = new QHBoxLayout();
00256 controls_layout->setContentsMargins(0, 25, 0, 15);
00257
00258
00259 QWidget* spacer = new QWidget(this);
00260 spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00261 controls_layout->addWidget(spacer);
00262
00263
00264 QPushButton* btn_save_ = new QPushButton("&Save", this);
00265 btn_save_->setMaximumWidth(200);
00266 connect(btn_save_, SIGNAL(clicked()), this, SLOT(doneEditing()));
00267 controls_layout->addWidget(btn_save_);
00268 controls_layout->setAlignment(btn_save_, Qt::AlignRight);
00269
00270
00271 QPushButton* btn_cancel_ = new QPushButton("&Cancel", this);
00272 btn_cancel_->setMaximumWidth(200);
00273 connect(btn_cancel_, SIGNAL(clicked()), this, SLOT(cancelEditing()));
00274 controls_layout->addWidget(btn_cancel_);
00275 controls_layout->setAlignment(btn_cancel_, Qt::AlignRight);
00276
00277
00278 layout->addLayout(controls_layout);
00279
00280
00281 edit_widget->setLayout(layout);
00282
00283 return edit_widget;
00284 }
00285
00286
00287
00288
00289 void RobotPosesWidget::showNewScreen()
00290 {
00291
00292 stacked_layout_->setCurrentIndex(1);
00293
00294
00295 current_edit_pose_.clear();
00296
00297
00298 if (!group_name_field_->currentText().isEmpty())
00299 loadJointSliders(group_name_field_->currentText());
00300
00301
00302 pose_name_field_->setText("");
00303
00304
00305 Q_EMIT isModal(true);
00306 }
00307
00308
00309
00310
00311 void RobotPosesWidget::editDoubleClicked(int row, int column)
00312 {
00313
00314 editSelected();
00315 }
00316
00317
00318
00319
00320 void RobotPosesWidget::previewClicked(int row, int column)
00321 {
00322
00323 QList<QTableWidgetItem*> selected = data_table_->selectedItems();
00324
00325
00326 if (!selected.size())
00327 return;
00328
00329
00330 srdf::Model::GroupState* pose = findPoseByName(selected[0]->text().toStdString());
00331
00332 showPose(pose);
00333 }
00334
00335
00336
00337
00338 void RobotPosesWidget::showPose(srdf::Model::GroupState* pose)
00339 {
00340
00341 for (std::map<std::string, std::vector<double> >::const_iterator value_it = pose->joint_values_.begin();
00342 value_it != pose->joint_values_.end(); ++value_it)
00343 {
00344
00345 joint_state_map_[value_it->first] = value_it->second[0];
00346 }
00347
00348
00349 publishJoints();
00350
00351
00352 Q_EMIT unhighlightAll();
00353
00354
00355 Q_EMIT highlightGroup(pose->group_);
00356 }
00357
00358
00359
00360
00361 void RobotPosesWidget::showDefaultPose()
00362 {
00363
00364 std::vector<const robot_model::JointModel*> joint_models = config_data_->getRobotModel()->getJointModels();
00365
00366
00367 for (std::vector<const robot_model::JointModel*>::const_iterator joint_it = joint_models.begin();
00368 joint_it < joint_models.end(); ++joint_it)
00369 {
00370
00371 if ((*joint_it)->getVariableCount() == 1)
00372 {
00373 double init_value;
00374
00375
00376 (*joint_it)->getVariableDefaultPositions(&init_value);
00377
00378
00379 joint_state_map_[(*joint_it)->getName()] = init_value;
00380 }
00381 }
00382
00383
00384 publishJoints();
00385
00386
00387 Q_EMIT unhighlightAll();
00388 }
00389
00390
00391
00392
00393 void RobotPosesWidget::playPoses()
00394 {
00395
00396 for (std::vector<srdf::Model::GroupState>::iterator pose_it = config_data_->srdf_->group_states_.begin();
00397 pose_it != config_data_->srdf_->group_states_.end(); ++pose_it)
00398 {
00399 ROS_INFO_STREAM("Showing pose " << pose_it->name_);
00400 showPose(&(*pose_it));
00401 ros::Duration(0.05).sleep();
00402 QApplication::processEvents();
00403 ros::Duration(0.45).sleep();
00404 }
00405 }
00406
00407
00408
00409
00410 void RobotPosesWidget::editSelected()
00411 {
00412
00413 QList<QTableWidgetItem*> selected = data_table_->selectedItems();
00414
00415
00416 if (!selected.size())
00417 return;
00418
00419
00420 edit(selected[0]->text().toStdString());
00421 }
00422
00423
00424
00425
00426 void RobotPosesWidget::edit(const std::string& name)
00427 {
00428
00429 current_edit_pose_ = name;
00430
00431
00432 srdf::Model::GroupState* pose = findPoseByName(name);
00433
00434
00435 pose_name_field_->setText(pose->name_.c_str());
00436
00437
00438 for (std::map<std::string, std::vector<double> >::const_iterator value_it = pose->joint_values_.begin();
00439 value_it != pose->joint_values_.end(); ++value_it)
00440 {
00441
00442 joint_state_map_[value_it->first] = value_it->second[0];
00443 }
00444
00445
00446 publishJoints();
00447
00448
00449 int index = group_name_field_->findText(pose->group_.c_str());
00450 if (index == -1)
00451 {
00452 QMessageBox::critical(this, "Error Loading", "Unable to find group name in drop down box");
00453 return;
00454 }
00455
00456
00457 group_name_field_->setCurrentIndex(index);
00458
00459
00460 stacked_layout_->setCurrentIndex(1);
00461
00462
00463 Q_EMIT isModal(true);
00464
00465
00466 loadJointSliders(QString(pose->group_.c_str()));
00467 }
00468
00469
00470
00471
00472 void RobotPosesWidget::loadGroupsComboBox()
00473 {
00474
00475 group_name_field_->clear();
00476
00477
00478 for (std::vector<srdf::Model::Group>::iterator group_it = config_data_->srdf_->groups_.begin();
00479 group_it != config_data_->srdf_->groups_.end(); ++group_it)
00480 {
00481 group_name_field_->addItem(group_it->name_.c_str());
00482 }
00483 }
00484
00485
00486
00487
00488 void RobotPosesWidget::loadJointSliders(const QString& selected)
00489 {
00490
00491
00492 if (!group_name_field_->count() || selected.isEmpty() || stacked_layout_->currentIndex() == 0)
00493 return;
00494
00495
00496 const std::string group_name = selected.toStdString();
00497
00498
00499 if (!config_data_->getRobotModel()->hasJointModelGroup(group_name))
00500 {
00501 QMessageBox::critical(this, "Error Loading", QString("Unable to find joint model group for group: ")
00502 .append(group_name.c_str())
00503 .append(" Are you sure this group has associated joints/links?"));
00504 return;
00505 }
00506
00507
00508 if (joint_list_layout_)
00509 {
00510 delete joint_list_layout_;
00511 qDeleteAll(joint_list_widget_->children());
00512 }
00513
00514
00515 joint_list_layout_ = new QVBoxLayout();
00516 joint_list_widget_->setLayout(joint_list_layout_);
00517
00518 joint_list_widget_->setSizePolicy(QSizePolicy::Ignored, QSizePolicy::Ignored);
00519 joint_list_widget_->setMinimumSize(50, 50);
00520
00521
00522 const robot_model::JointModelGroup* joint_model_group = config_data_->getRobotModel()->getJointModelGroup(group_name);
00523 joint_models_ = joint_model_group->getJointModels();
00524
00525
00526 int num_joints = 0;
00527 for (std::vector<const robot_model::JointModel*>::const_iterator joint_it = joint_models_.begin();
00528 joint_it < joint_models_.end(); ++joint_it)
00529 {
00530
00531 if ((*joint_it)->getVariableCount() == 1)
00532 {
00533 double init_value;
00534
00535
00536 if (joint_state_map_.find((*joint_it)->getName()) == joint_state_map_.end())
00537 {
00538
00539
00540
00541 (*joint_it)->getVariableDefaultPositions(&init_value);
00542 }
00543 else
00544 {
00545 init_value = joint_state_map_[(*joint_it)->getName()];
00546 }
00547
00548
00549 SliderWidget* sw = new SliderWidget(this, *joint_it, init_value);
00550 joint_list_layout_->addWidget(sw);
00551
00552
00553 connect(sw, SIGNAL(jointValueChanged(const std::string&, double)), this,
00554 SLOT(updateRobotModel(const std::string&, double)));
00555
00556 ++num_joints;
00557 }
00558 }
00559
00560
00561 joint_list_widget_->resize(300, num_joints * 70);
00562
00563
00564 publishJoints();
00565
00566
00567 Q_EMIT unhighlightAll();
00568 Q_EMIT highlightGroup(group_name);
00569 }
00570
00571
00572
00573
00574 srdf::Model::GroupState* RobotPosesWidget::findPoseByName(const std::string& name)
00575 {
00576
00577 srdf::Model::GroupState* searched_group = NULL;
00578
00579 for (std::vector<srdf::Model::GroupState>::iterator pose_it = config_data_->srdf_->group_states_.begin();
00580 pose_it != config_data_->srdf_->group_states_.end(); ++pose_it)
00581 {
00582 if (pose_it->name_ == name)
00583 {
00584 searched_group = &(*pose_it);
00585 break;
00586 }
00587 }
00588
00589
00590 if (searched_group == NULL)
00591 {
00592 QMessageBox::critical(this, "Error Saving", "An internal error has occured while saving. Quitting.");
00593 QApplication::quit();
00594 }
00595
00596 return searched_group;
00597 }
00598
00599
00600
00601
00602 void RobotPosesWidget::deleteSelected()
00603 {
00604
00605 QList<QTableWidgetItem*> selected = data_table_->selectedItems();
00606
00607
00608 if (!selected.size())
00609 return;
00610
00611
00612 current_edit_pose_ = selected[0]->text().toStdString();
00613
00614
00615 if (QMessageBox::question(
00616 this, "Confirm Pose Deletion",
00617 QString("Are you sure you want to delete the pose '").append(current_edit_pose_.c_str()).append("'?"),
00618 QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Cancel)
00619 {
00620 return;
00621 }
00622
00623
00624 for (std::vector<srdf::Model::GroupState>::iterator pose_it = config_data_->srdf_->group_states_.begin();
00625 pose_it != config_data_->srdf_->group_states_.end(); ++pose_it)
00626 {
00627
00628 if (pose_it->name_ == current_edit_pose_)
00629 {
00630 config_data_->srdf_->group_states_.erase(pose_it);
00631 break;
00632 }
00633 }
00634
00635
00636 loadDataTable();
00637 config_data_->changes |= MoveItConfigData::POSES;
00638 }
00639
00640
00641
00642
00643 void RobotPosesWidget::doneEditing()
00644 {
00645
00646 const std::string pose_name = pose_name_field_->text().toStdString();
00647
00648
00649 srdf::Model::GroupState* searched_data = NULL;
00650
00651
00652 if (pose_name.empty())
00653 {
00654 QMessageBox::warning(this, "Error Saving", "A name must be given for the pose!");
00655 return;
00656 }
00657
00658
00659 if (!current_edit_pose_.empty())
00660 {
00661
00662 searched_data = findPoseByName(current_edit_pose_);
00663 }
00664
00665
00666 for (std::vector<srdf::Model::GroupState>::const_iterator data_it = config_data_->srdf_->group_states_.begin();
00667 data_it != config_data_->srdf_->group_states_.end(); ++data_it)
00668 {
00669 if (data_it->name_.compare(pose_name) == 0)
00670 {
00671
00672 if (&(*data_it) != searched_data)
00673 {
00674 QMessageBox::warning(this, "Error Saving", "A pose already exists with that name!");
00675 return;
00676 }
00677 }
00678 }
00679
00680
00681 if (group_name_field_->currentText().isEmpty())
00682 {
00683 QMessageBox::warning(this, "Error Saving", "A planning group must be chosen!");
00684 return;
00685 }
00686
00687 config_data_->changes |= MoveItConfigData::POSES;
00688
00689
00690 bool isNew = false;
00691
00692 if (searched_data == NULL)
00693 {
00694 isNew = true;
00695
00696 searched_data = new srdf::Model::GroupState();
00697 }
00698
00699
00700 searched_data->name_ = pose_name;
00701 searched_data->group_ = group_name_field_->currentText().toStdString();
00702
00703
00704
00705
00706 searched_data->joint_values_.clear();
00707
00708
00709 for (std::vector<const robot_model::JointModel*>::const_iterator joint_it = joint_models_.begin();
00710 joint_it < joint_models_.end(); ++joint_it)
00711 {
00712
00713 if ((*joint_it)->getVariableCount() == 1)
00714 {
00715
00716 std::vector<double> joint_value;
00717 joint_value.push_back(joint_state_map_[(*joint_it)->getName()]);
00718
00719
00720 searched_data->joint_values_[(*joint_it)->getName()] = joint_value;
00721 }
00722 }
00723
00724
00725 if (isNew)
00726 {
00727 config_data_->srdf_->group_states_.push_back(*searched_data);
00728 }
00729
00730
00731
00732
00733 loadDataTable();
00734
00735
00736 stacked_layout_->setCurrentIndex(0);
00737
00738
00739 Q_EMIT isModal(false);
00740 }
00741
00742
00743
00744
00745 void RobotPosesWidget::cancelEditing()
00746 {
00747
00748 stacked_layout_->setCurrentIndex(0);
00749
00750
00751 Q_EMIT isModal(false);
00752 }
00753
00754
00755
00756
00757 void RobotPosesWidget::loadDataTable()
00758 {
00759
00760 data_table_->setUpdatesEnabled(false);
00761 data_table_->setDisabled(true);
00762 data_table_->clearContents();
00763
00764
00765 data_table_->setRowCount(config_data_->srdf_->group_states_.size());
00766
00767
00768 int row = 0;
00769 for (std::vector<srdf::Model::GroupState>::const_iterator data_it = config_data_->srdf_->group_states_.begin();
00770 data_it != config_data_->srdf_->group_states_.end(); ++data_it)
00771 {
00772
00773 QTableWidgetItem* data_name = new QTableWidgetItem(data_it->name_.c_str());
00774 data_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
00775 QTableWidgetItem* group_name = new QTableWidgetItem(data_it->group_.c_str());
00776 group_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
00777
00778
00779 data_table_->setItem(row, 0, data_name);
00780 data_table_->setItem(row, 1, group_name);
00781
00782
00783 ++row;
00784 }
00785
00786
00787 data_table_->setUpdatesEnabled(true);
00788 data_table_->setDisabled(false);
00789
00790
00791 data_table_->resizeColumnToContents(0);
00792 data_table_->resizeColumnToContents(1);
00793
00794
00795 if (config_data_->srdf_->group_states_.size())
00796 btn_edit_->show();
00797 }
00798
00799
00800
00801
00802 void RobotPosesWidget::focusGiven()
00803 {
00804
00805 stacked_layout_->setCurrentIndex(0);
00806
00807
00808 loadDataTable();
00809
00810
00811 loadGroupsComboBox();
00812 }
00813
00814
00815
00816
00817 void RobotPosesWidget::updateRobotModel(const std::string& name, double value)
00818 {
00819
00820 joint_state_map_[name] = value;
00821
00822
00823 publishJoints();
00824 }
00825
00826
00827
00828
00829 void RobotPosesWidget::publishJoints()
00830 {
00831
00832
00833
00834
00835
00836 config_data_->getPlanningScene()->getCurrentStateNonConst().setVariablePositions(joint_state_map_);
00837
00838
00839 moveit_msgs::DisplayRobotState msg;
00840 robot_state::robotStateToRobotStateMsg(config_data_->getPlanningScene()->getCurrentState(), msg.state);
00841
00842
00843 pub_robot_state_.publish(msg);
00844
00845
00846 config_data_->getPlanningScene()->getCurrentStateNonConst().update();
00847
00848
00849 collision_detection::CollisionResult result;
00850 config_data_->getPlanningScene()->checkSelfCollision(
00851 request, result, config_data_->getPlanningScene()->getCurrentState(), config_data_->allowed_collision_matrix_);
00852
00853 if (result.contacts.size())
00854 {
00855 collision_warning_->show();
00856 }
00857 else
00858 {
00859 collision_warning_->hide();
00860 }
00861 }
00862
00863
00864
00865
00866
00867
00868
00869
00870
00871
00872 SliderWidget::SliderWidget(QWidget* parent, const robot_model::JointModel* joint_model, double init_value)
00873 : QWidget(parent), joint_model_(joint_model)
00874 {
00875
00876 QVBoxLayout* layout = new QVBoxLayout();
00877 QHBoxLayout* row2 = new QHBoxLayout();
00878
00879
00880 joint_label_ = new QLabel(joint_model_->getName().c_str(), this);
00881 joint_label_->setContentsMargins(0, 0, 0, 0);
00882 layout->addWidget(joint_label_);
00883
00884
00885 joint_slider_ = new QSlider(Qt::Horizontal, this);
00886 joint_slider_->setTickPosition(QSlider::TicksBelow);
00887 joint_slider_->setSingleStep(10);
00888 joint_slider_->setPageStep(500);
00889 joint_slider_->setTickInterval(1000);
00890 joint_slider_->setContentsMargins(0, 0, 0, 0);
00891 row2->addWidget(joint_slider_);
00892
00893
00894 joint_value_ = new QLineEdit(this);
00895 joint_value_->setMaximumWidth(62);
00896 joint_value_->setContentsMargins(0, 0, 0, 0);
00897 connect(joint_value_, SIGNAL(editingFinished()), this, SLOT(changeJointSlider()));
00898 row2->addWidget(joint_value_);
00899
00900
00901 const std::vector<moveit_msgs::JointLimits>& limits = joint_model_->getVariableBoundsMsg();
00902 if (limits.empty())
00903 {
00904 QMessageBox::critical(this, "Error Loading", "An internal error has occured while loading the joints");
00905 return;
00906 }
00907
00908
00909 moveit_msgs::JointLimits joint_limit = limits[0];
00910 max_position_ = joint_limit.max_position;
00911 min_position_ = joint_limit.min_position;
00912
00913
00914 joint_slider_->setMaximum(max_position_ * 10000);
00915 joint_slider_->setMinimum(min_position_ * 10000);
00916
00917
00918 connect(joint_slider_, SIGNAL(valueChanged(int)), this, SLOT(changeJointValue(int)));
00919
00920
00921 int value = init_value * 10000;
00922 joint_slider_->setSliderPosition(value);
00923 changeJointValue(value);
00924
00925
00926 layout->addLayout(row2);
00927
00928 this->setContentsMargins(0, 0, 0, 0);
00929
00930 this->setGeometry(QRect(110, 80, 120, 80));
00931 this->setLayout(layout);
00932
00933
00934 qRegisterMetaType<std::string>("std::string");
00935 }
00936
00937
00938
00939
00940 SliderWidget::~SliderWidget()
00941 {
00942 }
00943
00944
00945
00946
00947 void SliderWidget::changeJointValue(int value)
00948 {
00949
00950 const double double_value = double(value) / 10000;
00951
00952
00953 joint_value_->setText(QString("%1").arg(double_value, 0, 'f', 4));
00954
00955
00956 Q_EMIT jointValueChanged(joint_model_->getName(), double_value);
00957 }
00958
00959
00960
00961
00962 void SliderWidget::changeJointSlider()
00963 {
00964
00965 double value = joint_value_->text().toDouble();
00966
00967 if (min_position_ > value || value > max_position_)
00968 {
00969 value = (min_position_ > value) ? min_position_ : max_position_;
00970 joint_value_->setText(QString("%1").arg(value, 0, 'f', 4));
00971 }
00972
00973
00974 joint_slider_->setSliderPosition(value * 10000);
00975
00976
00977 Q_EMIT jointValueChanged(joint_model_->getName(), value);
00978 }
00979
00980 }