Go to the documentation of this file.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 #ifndef PLANNING_SCENE_WAREHOUSE_H
00033 #define PLANNING_SCENE_WAREHOUSE_H
00034
00035 #include <termios.h>
00036 #include <signal.h>
00037 #include <cstdio>
00038 #include <cstdlib>
00039 #include <unistd.h>
00040 #include <math.h>
00041 #include <string>
00042 #include <map>
00043
00044 #include <ros/ros.h>
00045
00046 #include <move_arm_warehouse/move_arm_utils.h>
00047 #include <move_arm_warehouse/trajectory_stats.h>
00048
00049 #include <qt4/QtGui/qwidget.h>
00050 #include <qt4/QtGui/qmenubar.h>
00051 #include <qt4/QtGui/qmenu.h>
00052 #include <qt4/QtGui/qprogressbar.h>
00053 #include <qt4/QtGui/qdialog.h>
00054 #include <qt4/QtGui/qtablewidget.h>
00055 #include <qt4/QtGui/qlayout.h>
00056 #include <qt4/QtGui/qpushbutton.h>
00057 #include <qt4/Qt/qthread.h>
00058 #include <qt4/QtGui/qslider.h>
00059 #include <qt4/QtGui/qspinbox.h>
00060 #include <qt4/QtGui/qlabel.h>
00061 #include <qt4/QtGui/qgroupbox.h>
00062 #include <qt4/QtGui/qcombobox.h>
00063 #include <qt4/QtGui/qcheckbox.h>
00064 #include <qt4/QtGui/qcolordialog.h>
00065 #include <qt4/QtGui/qtreewidget.h>
00066 #include <qt4/QtGui/qpalette.h>
00067 #include <qt4/QtGui/qformlayout.h>
00068 #include <qt4/QtGui/qlineedit.h>
00069 #include <qt4/QtGui/qfiledialog.h>
00070 #include <qt4/QtGui/qmessagebox.h>
00071 #include <qt4/QtGui/qmainwindow.h>
00072 #include <qt4/QtGui/qlistwidget.h>
00073 #include <QDateTime>
00074
00075 static const std::string VIS_TOPIC_NAME = "planning_scene_visualizer_markers";
00076
00077
00078 static const unsigned int CONTROL_SPEED = 5;
00079 static const std::string EXECUTE_RIGHT_TRAJECTORY = "/r_arm_controller/follow_joint_trajectory";
00080 static const std::string EXECUTE_LEFT_TRAJECTORY = "/l_arm_controller/follow_joint_trajectory";
00081 static const std::string LEFT_IK_NAME = "/pr2_left_arm_kinematics/get_constraint_aware_ik";
00082 static const std::string RIGHT_IK_NAME = "/pr2_right_arm_kinematics/get_constraint_aware_ik";
00083 static const std::string NON_COLL_LEFT_IK_NAME = "/pr2_left_arm_kinematics/get_ik";
00084 static const std::string NON_COLL_RIGHT_IK_NAME = "/pr2_right_arm_kinematics/get_ik";
00085 static const std::string RIGHT_ARM_GROUP = "right_arm";
00086 static const std::string LEFT_ARM_GROUP = "left_arm";
00087 static const std::string RIGHT_ARM_REDUNDANCY = "r_upper_arm_roll_joint";
00088 static const std::string LEFT_ARM_REDUNDANCY = "l_upper_arm_roll_joint";
00089 static const std::string LEFT_IK_LINK = "l_wrist_roll_link";
00090 static const std::string RIGHT_IK_LINK = "r_wrist_roll_link";
00091 static const std::string PLANNER_1_SERVICE_NAME = "/ompl_planning/plan_kinematic_path";
00092 static const std::string PLANNER_2_SERVICE_NAME = "/chomp_planner_longrange";
00093 static const std::string LEFT_INTERPOLATE_SERVICE_NAME = "/l_interpolated_ik_motion_plan";
00094 static const std::string RIGHT_INTERPOLATE_SERVICE_NAME = "/r_interpolated_ik_motion_plan";
00095 static const std::string TRAJECTORY_FILTER_1_SERVICE_NAME = "/trajectory_shortcutting_filter_server/filter_trajectory_with_constraints";
00096 static const std::string TRAJECTORY_FILTER_2_SERVICE_NAME = "/trajectory_smoothing_filter_server/filter_trajectory_with_constraints";
00097 static const std::string PROXIMITY_SPACE_SERVICE_NAME = "/collision_proximity_server_test/get_distance_aware_plan";
00098 static const std::string PROXIMITY_SPACE_VALIDITY_NAME = "/collision_proximity_server_test/get_state_validity";
00099 static const std::string PROXIMITY_SPACE_PLANNER_NAME = "/collision_proximity_planner/plan";
00100 static const std::string LIST_CONTROLLERS_SERVICE = "/pr2_controller_manager/list_controllers";
00101 static const std::string LOAD_CONTROLLERS_SERVICE = "/pr2_controller_manager/load_controller";
00102 static const std::string UNLOAD_CONTROLLERS_SERVICE = "/pr2_controller_manager/unload_controller";
00103 static const std::string SWITCH_CONTROLLERS_SERVICE = "/pr2_controller_manager/switch_controller";
00104 static const std::string GAZEBO_ROBOT_MODEL = "pr2";
00105 static const std::string ROBOT_DESCRIPTION_PARAM = "robot_description";
00106 static const ros::Duration PLANNING_DURATION = ros::Duration(5.0);
00107 static const std::string SET_PLANNING_SCENE_DIFF_NAME = "environment_server/set_planning_scene_diff";
00108
00112 class ParameterDialog: public QDialog
00113 {
00114 public:
00115 planning_scene_utils::PlanningSceneParameters params_;
00116 ParameterDialog(planning_scene_utils::PlanningSceneParameters params, QWidget* parent = NULL) :
00117 QDialog(parent)
00118 {
00119 params_ = params;
00120 setMinimumWidth(640);
00121 setup();
00122 }
00123
00127 void setup()
00128 {
00129 QGroupBox* groupBox = new QGroupBox(this);
00130 groupBox->setTitle("Planning Scene Editor Parameters");
00131 QVBoxLayout* boxLayout = new QVBoxLayout(this);
00132
00133 layout = new QFormLayout(groupBox);
00134 left_ik_name_ = new QLineEdit(groupBox);
00135 layout->addRow("Left IK Service", left_ik_name_);
00136 left_ik_name_->setText(QString::fromStdString(params_.left_ik_name_));
00137
00138 right_ik_name_ = new QLineEdit(groupBox);
00139 layout->addRow("Right IK Service", right_ik_name_);
00140 right_ik_name_->setText(QString::fromStdString(params_.right_ik_name_));
00141
00142 non_coll_left_ik_name_ = new QLineEdit(groupBox);
00143 layout->addRow("Non Collision-Aware Left IK Service", non_coll_left_ik_name_);
00144 non_coll_left_ik_name_->setText(QString::fromStdString(params_.non_coll_left_ik_name_));
00145
00146 non_coll_right_ik_name_ = new QLineEdit(groupBox);
00147 layout->addRow("Non Collision-Aware Right IK Service", non_coll_right_ik_name_);
00148 non_coll_right_ik_name_->setText(QString::fromStdString(params_.non_coll_right_ik_name_));
00149
00150 right_arm_group_ = new QLineEdit(groupBox);
00151 layout->addRow("Right Arm Group", right_arm_group_);
00152 right_arm_group_->setText(QString::fromStdString(params_.right_arm_group_));
00153
00154 left_arm_group_ = new QLineEdit(groupBox);
00155 layout->addRow("Left Arm Group", left_arm_group_);
00156 left_arm_group_->setText(QString::fromStdString(params_.left_arm_group_));
00157
00158 right_arm_redundancy_ = new QLineEdit(groupBox);
00159 layout->addRow("Right Arm Redundancy DOF", right_arm_redundancy_);
00160 right_arm_redundancy_->setText(QString::fromStdString(params_.right_redundancy_));
00161
00162 left_arm_redundancy_ = new QLineEdit(groupBox);
00163 layout->addRow("Left Arm Redundancy DOF", left_arm_redundancy_);
00164 left_arm_redundancy_->setText(QString::fromStdString(params_.left_redundancy_));
00165
00166 left_ik_link_ = new QLineEdit(groupBox);
00167 layout->addRow("Left IK Link", left_ik_link_);
00168 left_ik_link_ ->setText(QString::fromStdString(params_.left_ik_link_));
00169
00170 right_ik_link_ = new QLineEdit(groupBox);
00171 layout->addRow("Right IK Link", right_ik_link_);
00172 right_ik_link_->setText(QString::fromStdString(params_.right_ik_link_));
00173
00174 planner_1_service_name_ = new QLineEdit(groupBox);
00175 layout->addRow("Planner 1 Service", planner_1_service_name_);
00176 planner_1_service_name_->setText(QString::fromStdString(params_.planner_1_service_name_));
00177
00178 planner_2_service_name_ = new QLineEdit(groupBox);
00179 layout->addRow("Planner 2 Service", planner_2_service_name_);
00180 planner_2_service_name_->setText(QString::fromStdString(params_.planner_2_service_name_));
00181
00182 left_interpolate_service_name_ = new QLineEdit(groupBox);
00183 layout->addRow("Left Interpolation Service", left_interpolate_service_name_);
00184 left_interpolate_service_name_->setText(QString::fromStdString(params_.left_interpolate_service_name_));
00185
00186 right_interpolate_service_name_ = new QLineEdit(groupBox);
00187 layout->addRow("Right Interpolation Service", right_interpolate_service_name_);
00188 right_interpolate_service_name_->setText(QString::fromStdString(params_.right_interpolate_service_name_));
00189
00190 trajectory_filter_1_service_name_ = new QLineEdit(groupBox);
00191 layout->addRow("Trajectory Filter Service 1", trajectory_filter_1_service_name_);
00192 trajectory_filter_1_service_name_->setText(QString::fromStdString(params_.trajectory_filter_1_service_name_));
00193
00194 trajectory_filter_2_service_name_ = new QLineEdit(groupBox);
00195 layout->addRow("Trajectory Filter Service 2", trajectory_filter_2_service_name_);
00196 trajectory_filter_2_service_name_->setText(QString::fromStdString(params_.trajectory_filter_2_service_name_));
00197
00198 proximity_space_service_name_ = new QLineEdit(groupBox);
00199 layout->addRow("Proximity Space Service", proximity_space_service_name_);
00200 proximity_space_service_name_ ->setText(QString::fromStdString(params_.proximity_space_service_name_));
00201
00202 proximity_space_validity_name_ = new QLineEdit(groupBox);
00203 layout->addRow("Proximity Space Validity Service", proximity_space_validity_name_);
00204 proximity_space_validity_name_ ->setText(QString::fromStdString(params_.proximity_space_validity_name_));
00205
00206 proximity_space_planner_name_ = new QLineEdit(groupBox);
00207 layout->addRow("Proximity Space Planner", proximity_space_planner_name_);
00208 proximity_space_planner_name_ ->setText(QString::fromStdString(params_.proximity_space_planner_name_));
00209
00210 execute_left_trajectory_ = new QLineEdit(groupBox);
00211 layout->addRow("Execute Left Trajectory", execute_left_trajectory_);
00212 execute_left_trajectory_ ->setText(QString::fromStdString(params_.execute_left_trajectory_));
00213
00214 execute_right_trajectory_ = new QLineEdit(groupBox);
00215 layout->addRow("Execute Right Trajectory", execute_right_trajectory_);
00216 execute_right_trajectory_ ->setText(QString::fromStdString(params_.execute_right_trajectory_));
00217
00218 use_robot_data_ = new QCheckBox(groupBox);
00219 use_robot_data_->setText("Use Robot Data");
00220 use_robot_data_->setChecked(params_.use_robot_data_);
00221 layout->addRow("Use Data From Simulated/Real Robot?", use_robot_data_);
00222 use_robot_data_->setToolTip("When this is checked, a robot state publisher will not be created. Instead, TF data\n\
00223 will be taken from the robot's actual state.");
00224 sync_with_gazebo_ = new QCheckBox(groupBox);
00225 sync_with_gazebo_->setText("Sync With Gazebo");
00226 sync_with_gazebo_->setChecked(false);
00227 sync_with_gazebo_->setToolTip("When this is checked, the warehouse viewer will attempt to set the robot state\n\
00228 to the start state of any motion plan requests played.");
00229 layout->addRow("Synchronize Robot State With Gazebo?", sync_with_gazebo_);
00230
00231 QPushButton* button = new QPushButton(groupBox);
00232 button->setText("Accept");
00233 button->setSizePolicy(QSizePolicy::Maximum, QSizePolicy::Maximum);
00234 connect(button, SIGNAL(clicked()), this, SLOT(accept()));
00235
00236 boxLayout->addWidget(groupBox);
00237 boxLayout->addWidget(button);
00238 groupBox->setLayout(layout);
00239 setLayout(boxLayout);
00240
00241 }
00242
00246 void updateParams()
00247 {
00248 params_.left_ik_name_ = left_ik_name_->text().toStdString();
00249 params_.right_ik_name_ = right_ik_name_->text().toStdString();
00250 params_.non_coll_left_ik_name_ = non_coll_left_ik_name_ ->text().toStdString();
00251 params_.non_coll_right_ik_name_ = non_coll_right_ik_name_ ->text().toStdString();
00252 params_.right_arm_group_ = right_arm_group_->text().toStdString();
00253 params_.left_arm_group_ = left_arm_group_ ->text().toStdString();
00254 params_.right_redundancy_ = right_arm_redundancy_->text().toStdString();
00255 params_.left_redundancy_ = left_arm_redundancy_->text().toStdString();
00256 params_.left_ik_link_ = left_ik_link_->text().toStdString();
00257 params_.right_ik_link_ = right_ik_link_->text().toStdString();
00258 params_.planner_1_service_name_ = planner_1_service_name_->text().toStdString();
00259 params_.planner_2_service_name_ = planner_2_service_name_->text().toStdString();
00260 params_.left_interpolate_service_name_ = left_interpolate_service_name_->text().toStdString();
00261 params_.right_interpolate_service_name_ = right_interpolate_service_name_->text().toStdString();
00262 params_.trajectory_filter_1_service_name_ = trajectory_filter_1_service_name_->text().toStdString();
00263 params_.trajectory_filter_2_service_name_ = trajectory_filter_2_service_name_->text().toStdString();
00264 params_.proximity_space_service_name_ = proximity_space_service_name_->text().toStdString();
00265 params_.proximity_space_validity_name_ = proximity_space_validity_name_->text().toStdString();
00266 params_.proximity_space_planner_name_ = proximity_space_planner_name_->text().toStdString();
00267 params_.execute_left_trajectory_ = execute_left_trajectory_->text().toStdString();
00268 params_.execute_right_trajectory_ = execute_right_trajectory_->text().toStdString();
00269 params_.use_robot_data_ = use_robot_data_->isChecked();
00270 params_.sync_robot_state_with_gazebo_ = sync_with_gazebo_->isChecked();
00271 }
00272
00273 private:
00274 QFormLayout* layout;
00275 QLineEdit* left_ik_name_;
00276 QLineEdit* right_ik_name_;
00277 QLineEdit* non_coll_left_ik_name_;
00278 QLineEdit* non_coll_right_ik_name_;
00279 QLineEdit* right_arm_group_;
00280 QLineEdit* left_arm_group_;
00281 QLineEdit* right_arm_redundancy_;
00282 QLineEdit* left_arm_redundancy_;
00283 QLineEdit* left_ik_link_;
00284 QLineEdit* right_ik_link_;
00285 QLineEdit* planner_1_service_name_;
00286 QLineEdit* planner_2_service_name_;
00287 QLineEdit* left_interpolate_service_name_;
00288 QLineEdit* right_interpolate_service_name_;
00289 QLineEdit* trajectory_filter_1_service_name_;
00290 QLineEdit* trajectory_filter_2_service_name_;
00291 QLineEdit* proximity_space_service_name_;
00292 QLineEdit* proximity_space_validity_name_;
00293 QLineEdit* proximity_space_planner_name_;
00294 QLineEdit* execute_left_trajectory_;
00295 QLineEdit* execute_right_trajectory_;
00296 QCheckBox* use_robot_data_;
00297 QCheckBox* sync_with_gazebo_;
00298
00299 };
00300
00301 class PlanningSceneNameTableItem: public QObject, public QTableWidgetItem
00302 {
00303 Q_OBJECT
00304 public:
00305
00306 PlanningSceneNameTableItem(const QString& qs) : QTableWidgetItem(qs) {}
00307
00308 bool operator< (const QTableWidgetItem& other) const {
00309 unsigned int other_id = planning_scene_utils::getPlanningSceneIdFromName(other.text().toStdString());
00310 unsigned int my_id = planning_scene_utils::getPlanningSceneIdFromName(this->text().toStdString());
00311 if(my_id < other_id) {
00312 return true;
00313 } else {
00314 return false;
00315 }
00316 }
00317 };
00318
00319 class PlanningSceneDateTableItem: public QObject, public QTableWidgetItem
00320 {
00321 Q_OBJECT
00322 public:
00323
00324 PlanningSceneDateTableItem(const QString& qs) : QTableWidgetItem(qs) {}
00325
00326 bool operator< (const QTableWidgetItem& other) const {
00327 QDateTime other_time = QDateTime::fromString(other.text());
00328 QDateTime my_time = QDateTime::fromString(this->text());
00329 if(my_time < other_time) {
00330 return true;
00331 } else {
00332 return false;
00333 }
00334 }
00335 };
00336
00340 class WarehouseViewer: public QMainWindow, public planning_scene_utils::PlanningSceneEditor
00341 {
00342 Q_OBJECT
00343 public:
00345 bool quit_threads_;
00346
00350 class TableLoadThread: public QThread
00351 {
00352 public:
00353 WarehouseViewer* visualizer_;
00354 TableLoadThread(WarehouseViewer* visualizer) :
00355 QThread(visualizer), visualizer_(visualizer)
00356 {
00357 }
00358
00359 void run()
00360 {
00361 visualizer_->createPlanningSceneTable();
00362 }
00363 };
00364
00365 WarehouseViewer(QWidget* parent, planning_scene_utils::PlanningSceneParameters& params);
00366 ~WarehouseViewer();
00367
00369 void initQtWidgets();
00371 void setupPlanningSceneDialog();
00373 void createPlanningSceneTable();
00375 void createTrajectoryTable();
00377 void createMotionPlanTable();
00379 void createNewObjectDialog();
00381 void createNewMeshDialog();
00383 void createRequestDialog();
00384
00385 void createSetPathConstraintsDialog(planning_scene_utils::MotionPlanRequestData& data);
00386
00388 void updateState();
00390 void onPlanningSceneLoaded(int scene, int numScenes);
00391 void createOutcomeDialog();
00392 void createAlterLinkPaddingDialog();
00393 void createAlterAllowedCollisionDialog();
00394 void createAttachObjectDialog(const std::string& name);
00395 bool createNewPlanningSceneConfirm();
00396 void createRobotStateEditor();
00397
00399 QGroupBox *createMotionPlanBox();
00401 QGroupBox *createTrajectoryBox();
00403 QGroupBox *createTrajectoryControlsBox();
00405 QGroupBox *createTrajectoryInfoBox();
00406
00407 void saveCurrentPlanningScene(bool copy);
00408
00409 virtual void planCallback(arm_navigation_msgs::ArmNavigationErrorCodes& errorCode);
00410 virtual void filterCallback(arm_navigation_msgs::ArmNavigationErrorCodes& errorCode);
00411
00412 virtual void attachObjectCallback(const std::string& name) {
00413 emit attachObjectSignal(name);
00414 }
00415
00417 virtual void selectedTrajectoryCurrentPointChanged( unsigned int new_current_point );
00418
00419 void setEnabledDisabledDisplay(const QString& qs1, const QString& qs2);
00420 void getEntryList(const std::string& s1,
00421 std::vector<std::string>& sv1);
00422 void addSpecialEntries(QListWidget* list_widget);
00423
00424 signals:
00426 void changeProgress(int progress);
00428 void updateTables();
00429
00430 void plannerFailure(int value);
00431 void filterFailure(int value);
00432
00433 void attachObjectSignal(const std::string& name);
00434
00435 void allScenesLoaded();
00436
00437 void selectedTrajectoryPointChanged( unsigned int new_point );
00438
00439 public slots:
00440
00441 void refreshPlanningSceneDialog();
00442
00443 void popupPlannerFailure(int value);
00444 void popupFilterFailure(int value);
00445
00447 void quit();
00449 void popupLoadPlanningScenes();
00451 void progressChanged(int progress)
00452 {
00453 load_scene_progress_->setValue(progress);
00454 }
00455 void planningSceneTableHeaderClicked(int col);
00456 void newButtonPressed();
00458 void loadButtonPressed();
00460 void refreshButtonPressed();
00461 void removePlanningSceneButtonPressed();
00463 void trajectoryTableSelection();
00465 void motionPlanTableSelection();
00467 void playButtonPressed();
00469 void filterButtonPressed();
00471 void trajectorySliderChanged(int nv);
00473 void replanButtonPressed();
00475 void trajectoryEditChanged();
00477 void createNewPlanningSceneSlot();
00479 void savePlanningSceneSlot();
00481 void copyPlanningSceneSlot();
00483 void createNewMotionPlanRequest(std::string group_name, std::string end_effector_name);
00485 void motionPlanStartColorButtonClicked();
00487 void motionPlanEndColorButtonClicked();
00489 void motionPlanStartVisibleButtonClicked(bool checked);
00491 void motionPlanEndVisibleButtonClicked(bool checked);
00493 void trajectoryColorButtonClicked();
00495 void trajectoryVisibleButtonClicked(bool checked);
00497 void createNewMotionPlanPressed();
00499 void createNewObjectPressed();
00501 void createObjectConfirmedPressed();
00503 void createMeshConfirmedPressed();
00505 void createNewMeshPressed();
00507 void createRequestPressed();
00509 void motionPlanCollisionVisibleButtonClicked(bool checked);
00511 void trajectoryCollisionsVisibleButtonClicked(bool checked);
00513 void motionPlanJointControlsActiveButtonClicked(bool checked);
00515 void selectMotionPlan(std::string ID);
00517 void selectTrajectory(std::string ID);
00519 void deleteSelectedMotionPlan();
00521 void deleteSelectedTrajectory();
00523 void updateStateTriggered();
00525 void executeButtonPressed();
00527 void refreshSceneButtonPressed();
00529 void viewOutcomesPressed();
00531 void alterLinkPaddingPressed();
00533 void alterAllowedCollisionPressed();
00535 void modelRenderTypeChanged(const QString& type);
00537 void trajectoryRenderTypeChanged(const int& type);
00539 void motionPlanRenderTypeChanged(const QString& type);
00541 void objectColorButtonPressed();
00542 void meshColorButtonPressed();
00543
00545 void alteredLinkPaddingValueChanged(double d);
00546
00547 void firstEntityListSelected();
00548 void secondEntityListSelected();
00549 void entityListsEdited();
00550 void disableCollisionClicked();
00551 void enableCollisionClicked();
00552 void resetAllowedCollisionClicked();
00553
00554 void meshFileSelected(const QString& s);
00555
00556 void attachObject(const std::string& name);
00557 void addTouchLinkClicked();
00558 void removeTouchLinkClicked();
00559
00560 void editRobotStatePressed();
00561 void editJointBoxChanged(const QString& joint);
00562 void jointStateSliderChanged(int nv);
00563
00564 void motionPlanHasPathConstraintsButtonClicked(bool checked);
00565 void setPathConstraintsButtonClicked();
00566
00567 void primaryPlannerTriggered();
00568 void secondaryPlannerTriggered();
00569 void primaryFilterTriggered();
00570 void secondaryFilterTriggered();
00571
00572 void onSelectedTrajectoryPointChanged( unsigned int new_point );
00573
00574 protected:
00575
00576 bool planning_scene_initialized_;
00577 QLabel* selected_trajectory_label_;
00578 QLabel* selected_trajectory_source_label_;
00579 QLabel* selected_trajectory_error_title_;
00580 QLabel* selected_trajectory_error_label_;
00581 QLabel* selected_request_label_;
00582 QLabel* selected_trajectory_stat_0_title_;
00583 QLabel* selected_trajectory_stat_0_label_;
00584 QLabel* selected_trajectory_stat_1_title_;
00585 QLabel* selected_trajectory_stat_1_label_;
00586 QLabel* selected_trajectory_stat_2_title_;
00587 QLabel* selected_trajectory_stat_2_label_;
00588 QLabel* selected_trajectory_stat_3_title_;
00589 QLabel* selected_trajectory_stat_3_label_;
00590 QLabel* selected_trajectory_stat_4_title_;
00591 QLabel* selected_trajectory_stat_4_label_;
00592 QLabel* selected_trajectory_stat_5_title_;
00593 QLabel* selected_trajectory_stat_5_label_;
00594
00595 QMenuBar* menu_bar_;
00596 QMenu* file_menu_;
00597 QMenu* planning_scene_menu_;
00598 QMenu* collision_object_menu_;
00599 QAction* new_object_action_;
00600 QAction* new_mesh_action_;
00601 QAction* refresh_action_;
00602 QAction* view_outcomes_action_;
00603
00604 QMenu* planner_configuration_menu_;
00605 QAction* set_primary_planner_action_;
00606 QAction* set_secondary_planner_action_;
00607 QAction* set_primary_filter_action_;
00608 QAction* set_secondary_filter_action_;
00609
00610 QAction* alter_link_padding_action_;
00611 QDialog* alter_link_padding_dialog_;
00612 QTableWidget* alter_link_padding_table_;
00613
00614 QAction* alter_allowed_collision_action_;
00615 QDialog* alter_allowed_collision_dialog_;
00616 QLineEdit* first_allowed_collision_line_edit_;
00617 QLineEdit* second_allowed_collision_line_edit_;
00618 QLineEdit* allowed_status_line_edit_;
00619 QListWidget* first_allowed_collision_list_;
00620 QListWidget* second_allowed_collision_list_;
00621
00622 QDialog* attach_object_dialog_;
00623 QComboBox* attach_link_box_;
00624 QListWidget* possible_touch_links_;
00625 QListWidget* added_touch_links_;
00626
00627 QAction* edit_robot_state_action_;
00628 QDialog* edit_robot_state_dialog_;
00629 QComboBox* edit_joint_box_;
00630 QSlider* joint_state_slider_;
00631 QLineEdit* lower_bound_edit_window_;
00632 QLineEdit* upper_bound_edit_window_;
00633 QLineEdit* current_value_window_;
00634
00635 QDialog* set_path_constraints_dialog_;
00636 QCheckBox* constrain_roll_check_box_;
00637 QCheckBox* constrain_pitch_check_box_;
00638 QCheckBox* constrain_yaw_check_box_;
00639 QDoubleSpinBox* constrain_roll_tolerance_;
00640 QDoubleSpinBox* constrain_pitch_tolerance_;
00641 QDoubleSpinBox* constrain_yaw_tolerance_;
00642
00643 QDialog* load_planning_scene_dialog_;
00644 QDialog* new_object_dialog_;
00645 QDialog* new_mesh_dialog_;
00646 QDialog* new_request_dialog_;
00647 QDialog* outcome_dialog_;
00648 QTableWidget* stage_outcome_table_;
00649 QTableWidget* trajectory_outcome_table_;
00650 QProgressBar* load_scene_progress_;
00651 QAction* new_planning_scene_action_;
00652 QAction* new_motion_plan_action_;
00653 QAction* load_planning_scene_action_;
00654 QAction* save_planning_scene_action_;
00655 QAction* copy_planning_scene_action_;
00656 QAction* quit_action_;
00657 QTableWidget* planning_scene_table_;
00658 QTreeWidget* motion_plan_tree_;
00659 QTreeWidget* trajectory_tree_;
00660 QSlider* trajectory_slider_;
00661 QPushButton* play_button_;
00662 QPushButton* filter_button_;
00663 QPushButton* replan_button_;
00664 QPushButton* execute_button_;
00665
00666 QPushButton* new_planning_scene_button_;
00667 QPushButton* load_planning_scene_button_;
00668 QPushButton* refresh_planning_scene_button_;
00669 QPushButton* remove_planning_scene_button_;
00670 QPushButton* object_color_button_;
00671 QComboBox* collision_display_box_;
00672
00673 QSpinBox* trajectory_point_edit_;
00674
00675 TableLoadThread* table_load_thread_;
00676
00677 QComboBox* collision_object_type_box_;
00678 QLineEdit* collision_object_name_;
00679 QComboBox* request_group_name_box_;
00680 QSpinBox* collision_object_scale_x_box_;
00681 QSpinBox* collision_object_scale_y_box_;
00682 QSpinBox* collision_object_scale_z_box_;
00683 QSpinBox* collision_object_pos_x_box_;
00684 QSpinBox* collision_object_pos_y_box_;
00685 QSpinBox* collision_object_pos_z_box_;
00686 QPushButton* make_object_button_;
00687
00688 QLineEdit* mesh_object_name_;
00689 QSpinBox* mesh_object_pos_x_box_;
00690 QSpinBox* mesh_object_pos_y_box_;
00691 QSpinBox* mesh_object_pos_z_box_;
00692 QDoubleSpinBox* mesh_object_scale_x_box_;
00693 QDoubleSpinBox* mesh_object_scale_y_box_;
00694 QDoubleSpinBox* mesh_object_scale_z_box_;
00695 QPushButton* mesh_color_button_;
00696 QPushButton* make_mesh_button_;
00697
00698 QCheckBox* load_motion_plan_requests_box_;
00699 QCheckBox* load_trajectories_box_;
00700 QCheckBox* create_request_from_robot_box_;
00701
00702 QFileDialog* file_selector_;
00703 QLineEdit* mesh_filename_field_;
00704
00705 QFormLayout* trajectory_info_box_layout_;
00706
00709 void setSelectedTrajectoryCheckboxVisible();
00710
00712 void setCommonTrajectoryInfo();
00714 void setPlannedTrajectoryInfo(bool success, planning_scene_utils::TrajectoryData& trajectory);
00716 void setFilteredTrajectoryInfo(bool success, planning_scene_utils::TrajectoryData& trajectory);
00718 void setExecutedTrajectoryInfo(bool success, planning_scene_utils::TrajectoryData& trajectory);
00720 void setOvershootTrajectoryInfo(bool success, planning_scene_utils::TrajectoryData& trajectory);
00721
00722
00723 std::string intToString(int val);
00724 std::string floatToString(double val);
00725
00726 };
00727 #endif