$search
00001 /* 00002 * Copyright (c) 2011, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the <ORGANIZATION> nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 // Author: Matthew Klingensmith, E. Gil Jones 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 00048 #include <qt4/QtGui/qwidget.h> 00049 #include <qt4/QtGui/qmenubar.h> 00050 #include <qt4/QtGui/qmenu.h> 00051 #include <qt4/QtGui/qprogressbar.h> 00052 #include <qt4/QtGui/qdialog.h> 00053 #include <qt4/QtGui/qtablewidget.h> 00054 #include <qt4/QtGui/qlayout.h> 00055 #include <qt4/QtGui/qpushbutton.h> 00056 #include <qt4/Qt/qthread.h> 00057 #include <qt4/QtGui/qslider.h> 00058 #include <qt4/QtGui/qspinbox.h> 00059 #include <qt4/QtGui/qlabel.h> 00060 #include <qt4/QtGui/qgroupbox.h> 00061 #include <qt4/QtGui/qcombobox.h> 00062 #include <qt4/QtGui/qcheckbox.h> 00063 #include <qt4/QtGui/qcolordialog.h> 00064 #include <qt4/QtGui/qtreewidget.h> 00065 #include <qt4/QtGui/qpalette.h> 00066 #include <qt4/QtGui/qformlayout.h> 00067 #include <qt4/QtGui/qlineedit.h> 00068 #include <qt4/QtGui/qfiledialog.h> 00069 #include <qt4/QtGui/qmessagebox.h> 00070 #include <qt4/QtGui/qmainwindow.h> 00071 #include <qt4/QtGui/qlistwidget.h> 00072 #include <QDateTime> 00073 00074 static const std::string VIS_TOPIC_NAME = "planning_scene_visualizer_markers"; 00075 00076 //in 100 hz ticks 00077 static const unsigned int CONTROL_SPEED = 5; 00078 static const std::string EXECUTE_RIGHT_TRAJECTORY = "/r_arm_controller/follow_joint_trajectory"; 00079 static const std::string EXECUTE_LEFT_TRAJECTORY = "/l_arm_controller/follow_joint_trajectory"; 00080 static const std::string LEFT_IK_NAME = "/pr2_left_arm_kinematics/get_constraint_aware_ik"; 00081 static const std::string RIGHT_IK_NAME = "/pr2_right_arm_kinematics/get_constraint_aware_ik"; 00082 static const std::string NON_COLL_LEFT_IK_NAME = "/pr2_left_arm_kinematics/get_ik"; 00083 static const std::string NON_COLL_RIGHT_IK_NAME = "/pr2_right_arm_kinematics/get_ik"; 00084 static const std::string RIGHT_ARM_GROUP = "right_arm"; 00085 static const std::string LEFT_ARM_GROUP = "left_arm"; 00086 static const std::string RIGHT_ARM_REDUNDANCY = "r_upper_arm_roll_joint"; 00087 static const std::string LEFT_ARM_REDUNDANCY = "l_upper_arm_roll_joint"; 00088 static const std::string LEFT_IK_LINK = "l_wrist_roll_link"; 00089 static const std::string RIGHT_IK_LINK = "r_wrist_roll_link"; 00090 static const std::string PLANNER_SERVICE_NAME = "/ompl_planning/plan_kinematic_path"; 00091 static const std::string LEFT_INTERPOLATE_SERVICE_NAME = "/l_interpolated_ik_motion_plan"; 00092 static const std::string RIGHT_INTERPOLATE_SERVICE_NAME = "/r_interpolated_ik_motion_plan"; 00093 static const std::string TRAJECTORY_FILTER_SERVICE_NAME = "/trajectory_filter/filter_trajectory_with_constraints"; 00094 static const std::string PROXIMITY_SPACE_SERVICE_NAME = "/collision_proximity_server_test/get_distance_aware_plan"; 00095 static const std::string PROXIMITY_SPACE_VALIDITY_NAME = "/collision_proximity_server_test/get_state_validity"; 00096 static const std::string PROXIMITY_SPACE_PLANNER_NAME = "/collision_proximity_planner/plan"; 00097 static const std::string LIST_CONTROLLERS_SERVICE = "/pr2_controller_manager/list_controllers"; 00098 static const std::string LOAD_CONTROLLERS_SERVICE = "/pr2_controller_manager/load_controller"; 00099 static const std::string UNLOAD_CONTROLLERS_SERVICE = "/pr2_controller_manager/unload_controller"; 00100 static const std::string SWITCH_CONTROLLERS_SERVICE = "/pr2_controller_manager/switch_controller"; 00101 static const std::string GAZEBO_ROBOT_MODEL = "pr2"; 00102 static const std::string ROBOT_DESCRIPTION_PARAM = "robot_description"; 00103 static const ros::Duration PLANNING_DURATION = ros::Duration(5.0); 00104 static const std::string SET_PLANNING_SCENE_DIFF_NAME = "environment_server/set_planning_scene_diff"; 00105 00109 class ParameterDialog: public QDialog 00110 { 00111 public: 00112 planning_scene_utils::PlanningSceneParameters params_; 00113 ParameterDialog(planning_scene_utils::PlanningSceneParameters params, QWidget* parent = NULL) : 00114 QDialog(parent) 00115 { 00116 params_ = params; 00117 setMinimumWidth(640); 00118 setup(); 00119 } 00120 00124 void setup() 00125 { 00126 QGroupBox* groupBox = new QGroupBox(this); 00127 groupBox->setTitle("Planning Scene Editor Parameters"); 00128 QVBoxLayout* boxLayout = new QVBoxLayout(this); 00129 00130 layout = new QFormLayout(groupBox); 00131 left_ik_name_ = new QLineEdit(groupBox); 00132 layout->addRow("Left IK Service", left_ik_name_); 00133 left_ik_name_->setText(QString::fromStdString(params_.left_ik_name_)); 00134 00135 right_ik_name_ = new QLineEdit(groupBox); 00136 layout->addRow("Right IK Service", right_ik_name_); 00137 right_ik_name_->setText(QString::fromStdString(params_.right_ik_name_)); 00138 00139 non_coll_left_ik_name_ = new QLineEdit(groupBox); 00140 layout->addRow("Non Collision-Aware Left IK Service", non_coll_left_ik_name_); 00141 non_coll_left_ik_name_->setText(QString::fromStdString(params_.non_coll_left_ik_name_)); 00142 00143 non_coll_right_ik_name_ = new QLineEdit(groupBox); 00144 layout->addRow("Non Collision-Aware Right IK Service", non_coll_right_ik_name_); 00145 non_coll_right_ik_name_->setText(QString::fromStdString(params_.non_coll_right_ik_name_)); 00146 00147 right_arm_group_ = new QLineEdit(groupBox); 00148 layout->addRow("Right Arm Group", right_arm_group_); 00149 right_arm_group_->setText(QString::fromStdString(params_.right_arm_group_)); 00150 00151 left_arm_group_ = new QLineEdit(groupBox); 00152 layout->addRow("Left Arm Group", left_arm_group_); 00153 left_arm_group_->setText(QString::fromStdString(params_.left_arm_group_)); 00154 00155 right_arm_redundancy_ = new QLineEdit(groupBox); 00156 layout->addRow("Right Arm Redundancy DOF", right_arm_redundancy_); 00157 right_arm_redundancy_->setText(QString::fromStdString(params_.right_redundancy_)); 00158 00159 left_arm_redundancy_ = new QLineEdit(groupBox); 00160 layout->addRow("Left Arm Redundancy DOF", left_arm_redundancy_); 00161 left_arm_redundancy_->setText(QString::fromStdString(params_.left_redundancy_)); 00162 00163 left_ik_link_ = new QLineEdit(groupBox); 00164 layout->addRow("Left IK Link", left_ik_link_); 00165 left_ik_link_ ->setText(QString::fromStdString(params_.left_ik_link_)); 00166 00167 right_ik_link_ = new QLineEdit(groupBox); 00168 layout->addRow("Right IK Link", right_ik_link_); 00169 right_ik_link_->setText(QString::fromStdString(params_.right_ik_link_)); 00170 00171 planner_service_name_ = new QLineEdit(groupBox); 00172 layout->addRow("Planner Service", planner_service_name_); 00173 planner_service_name_->setText(QString::fromStdString(params_.planner_service_name_)); 00174 00175 left_interpolate_service_name_ = new QLineEdit(groupBox); 00176 layout->addRow("Left Interpolation Service", left_interpolate_service_name_); 00177 left_interpolate_service_name_->setText(QString::fromStdString(params_.left_interpolate_service_name_)); 00178 00179 right_interpolate_service_name_ = new QLineEdit(groupBox); 00180 layout->addRow("Right Interpolation Service", right_interpolate_service_name_); 00181 right_interpolate_service_name_->setText(QString::fromStdString(params_.right_interpolate_service_name_)); 00182 00183 trajectory_filter_service_name_ = new QLineEdit(groupBox); 00184 layout->addRow("Trajectory Filter Service", trajectory_filter_service_name_); 00185 trajectory_filter_service_name_ ->setText(QString::fromStdString(params_.trajectory_filter_service_name_)); 00186 00187 proximity_space_service_name_ = new QLineEdit(groupBox); 00188 layout->addRow("Proximity Space Service", proximity_space_service_name_); 00189 proximity_space_service_name_ ->setText(QString::fromStdString(params_.proximity_space_service_name_)); 00190 00191 proximity_space_validity_name_ = new QLineEdit(groupBox); 00192 layout->addRow("Proximity Space Validity Service", proximity_space_validity_name_); 00193 proximity_space_validity_name_ ->setText(QString::fromStdString(params_.proximity_space_validity_name_)); 00194 00195 proximity_space_planner_name_ = new QLineEdit(groupBox); 00196 layout->addRow("Proximity Space Planner", proximity_space_planner_name_); 00197 proximity_space_planner_name_ ->setText(QString::fromStdString(params_.proximity_space_planner_name_)); 00198 00199 execute_left_trajectory_ = new QLineEdit(groupBox); 00200 layout->addRow("Execute Left Trajectory", execute_left_trajectory_); 00201 execute_left_trajectory_ ->setText(QString::fromStdString(params_.execute_left_trajectory_)); 00202 00203 execute_right_trajectory_ = new QLineEdit(groupBox); 00204 layout->addRow("Execute Right Trajectory", execute_right_trajectory_); 00205 execute_right_trajectory_ ->setText(QString::fromStdString(params_.execute_right_trajectory_)); 00206 00207 use_robot_data_ = new QCheckBox(groupBox); 00208 use_robot_data_->setText("Use Robot Data"); 00209 use_robot_data_->setChecked(params_.use_robot_data_); 00210 layout->addRow("Use Data From Simulated/Real Robot?", use_robot_data_); 00211 use_robot_data_->setToolTip("When this is checked, a robot state publisher will not be created. Instead, TF data\n\ 00212 will be taken from the robot's actual state."); 00213 sync_with_gazebo_ = new QCheckBox(groupBox); 00214 sync_with_gazebo_->setText("Sync With Gazebo"); 00215 sync_with_gazebo_->setChecked(false); 00216 sync_with_gazebo_->setToolTip("When this is checked, the warehouse viewer will attempt to set the robot state\n\ 00217 to the start state of any motion plan requests played."); 00218 layout->addRow("Synchronize Robot State With Gazebo?", sync_with_gazebo_); 00219 00220 QPushButton* button = new QPushButton(groupBox); 00221 button->setText("Accept"); 00222 button->setSizePolicy(QSizePolicy::Maximum, QSizePolicy::Maximum); 00223 connect(button, SIGNAL(clicked()), this, SLOT(accept())); 00224 00225 boxLayout->addWidget(groupBox); 00226 boxLayout->addWidget(button); 00227 groupBox->setLayout(layout); 00228 setLayout(boxLayout); 00229 00230 } 00231 00235 void updateParams() 00236 { 00237 params_.left_ik_name_ = left_ik_name_->text().toStdString(); 00238 params_.right_ik_name_ = right_ik_name_->text().toStdString(); 00239 params_.non_coll_left_ik_name_ = non_coll_left_ik_name_ ->text().toStdString(); 00240 params_.non_coll_right_ik_name_ = non_coll_right_ik_name_ ->text().toStdString(); 00241 params_.right_arm_group_ = right_arm_group_->text().toStdString(); 00242 params_.left_arm_group_ = left_arm_group_ ->text().toStdString(); 00243 params_.right_redundancy_ = right_arm_redundancy_->text().toStdString(); 00244 params_.left_redundancy_ = left_arm_redundancy_->text().toStdString(); 00245 params_.left_ik_link_ = left_ik_link_->text().toStdString(); 00246 params_.right_ik_link_ = right_ik_link_->text().toStdString(); 00247 params_.planner_service_name_ = planner_service_name_->text().toStdString(); 00248 params_.left_interpolate_service_name_ = left_interpolate_service_name_->text().toStdString(); 00249 params_.right_interpolate_service_name_ = right_interpolate_service_name_->text().toStdString(); 00250 params_.trajectory_filter_service_name_ = trajectory_filter_service_name_->text().toStdString(); 00251 params_.proximity_space_service_name_ = proximity_space_service_name_->text().toStdString(); 00252 params_.proximity_space_validity_name_ = proximity_space_validity_name_->text().toStdString(); 00253 params_.proximity_space_planner_name_ = proximity_space_planner_name_->text().toStdString(); 00254 params_.execute_left_trajectory_ = execute_left_trajectory_->text().toStdString(); 00255 params_.execute_right_trajectory_ = execute_right_trajectory_->text().toStdString(); 00256 params_.use_robot_data_ = use_robot_data_->isChecked(); 00257 params_.sync_robot_state_with_gazebo_ = sync_with_gazebo_->isChecked(); 00258 } 00259 00260 private: 00261 QFormLayout* layout; 00262 QLineEdit* left_ik_name_; 00263 QLineEdit* right_ik_name_; 00264 QLineEdit* non_coll_left_ik_name_; 00265 QLineEdit* non_coll_right_ik_name_; 00266 QLineEdit* right_arm_group_; 00267 QLineEdit* left_arm_group_; 00268 QLineEdit* right_arm_redundancy_; 00269 QLineEdit* left_arm_redundancy_; 00270 QLineEdit* left_ik_link_; 00271 QLineEdit* right_ik_link_; 00272 QLineEdit* planner_service_name_; 00273 QLineEdit* left_interpolate_service_name_; 00274 QLineEdit* right_interpolate_service_name_; 00275 QLineEdit* trajectory_filter_service_name_; 00276 QLineEdit* proximity_space_service_name_; 00277 QLineEdit* proximity_space_validity_name_; 00278 QLineEdit* proximity_space_planner_name_; 00279 QLineEdit* execute_left_trajectory_; 00280 QLineEdit* execute_right_trajectory_; 00281 QCheckBox* use_robot_data_; 00282 QCheckBox* sync_with_gazebo_; 00283 00284 }; 00285 00289 class WarehouseViewer: public QMainWindow, public planning_scene_utils::PlanningSceneEditor 00290 { 00291 Q_OBJECT 00292 public: 00294 bool quit_threads_; 00295 00299 class TableLoadThread: public QThread 00300 { 00301 public: 00302 WarehouseViewer* visualizer_; 00303 TableLoadThread(WarehouseViewer* visualizer) : 00304 QThread(visualizer), visualizer_(visualizer) 00305 { 00306 } 00307 00308 void run() 00309 { 00310 visualizer_->createPlanningSceneTable(); 00311 } 00312 }; 00313 00314 WarehouseViewer(QWidget* parent, planning_scene_utils::PlanningSceneParameters& params); 00315 ~WarehouseViewer(); 00316 00318 void initQtWidgets(); 00320 void setupPlanningSceneDialog(); 00322 void createPlanningSceneTable(); 00324 void createTrajectoryTable(); 00326 void createMotionPlanTable(); 00328 void createNewObjectDialog(); 00330 void createNewMeshDialog(); 00332 void createRequestDialog(); 00333 00335 void updateState(); 00337 void onPlanningSceneLoaded(int scene, int numScenes); 00338 void createOutcomeDialog(); 00339 void createAlterLinkPaddingDialog(); 00340 void createAlterAllowedCollisionDialog(); 00341 void createAttachObjectDialog(const std::string& name); 00342 bool createNewPlanningSceneConfirm(); 00343 void createRobotStateEditor(); 00344 00345 void saveCurrentPlanningScene(bool copy); 00346 00347 virtual void planCallback(arm_navigation_msgs::ArmNavigationErrorCodes& errorCode); 00348 virtual void filterCallback(arm_navigation_msgs::ArmNavigationErrorCodes& errorCode); 00349 00350 virtual void attachObjectCallback(const std::string& name) { 00351 emit attachObjectSignal(name); 00352 } 00353 00354 void setEnabledDisabledDisplay(const QString& qs1, const QString& qs2); 00355 void getEntryList(const std::string& s1, 00356 std::vector<std::string>& sv1); 00357 void addSpecialEntries(QListWidget* list_widget); 00358 00359 signals: 00361 void changeProgress(int progress); 00363 void updateTables(); 00364 00365 void plannerFailure(int value); 00366 void filterFailure(int value); 00367 00368 void attachObjectSignal(const std::string& name); 00369 00370 void allScenesLoaded(); 00371 00372 public slots: 00373 00374 void refreshPlanningSceneDialog(); 00375 00376 void popupPlannerFailure(int value); 00377 void popupFilterFailure(int value); 00378 00380 void quit(); 00382 void popupLoadPlanningScenes(); 00384 void progressChanged(int progress) 00385 { 00386 load_scene_progress_->setValue(progress); 00387 } 00388 void planningSceneTableHeaderClicked(int col); 00389 void newButtonPressed(); 00391 void loadButtonPressed(); 00393 void refreshButtonPressed(); 00394 void removePlanningSceneButtonPressed(); 00396 void trajectoryTableSelection(); 00398 void motionPlanTableSelection(); 00400 void playButtonPressed(); 00402 void filterButtonPressed(); 00404 void sliderDragged(int nv); 00406 void replanButtonPressed(); 00408 void trajectoryEditChanged(); 00410 void createNewPlanningSceneSlot(); 00412 void savePlanningSceneSlot(); 00414 void copyPlanningSceneSlot(); 00416 void createNewMotionPlanRequest(std::string group_name, std::string end_effector_name); 00418 void motionPlanStartColorButtonClicked(); 00420 void motionPlanEndColorButtonClicked(); 00422 void motionPlanStartVisibleButtonClicked(bool checked); 00424 void motionPlanEndVisibleButtonClicked(bool checked); 00426 void trajectoryColorButtonClicked(); 00428 void trajectoryVisibleButtonClicked(bool checked); 00430 void createNewMotionPlanPressed(); 00432 void createNewObjectPressed(); 00434 void createObjectConfirmedPressed(); 00436 void createMeshConfirmedPressed(); 00438 void createNewMeshPressed(); 00440 void createRequestPressed(); 00442 void motionPlanCollisionVisibleButtonClicked(bool checked); 00444 void trajectoryCollisionsVisibleButtonClicked(bool checked); 00446 void motionPlanJointControlsActiveButtonClicked(bool checked); 00448 void selectMotionPlan(std::string ID); 00450 void selectTrajectory(std::string ID); 00452 void deleteSelectedMotionPlan(); 00454 void deleteSelectedTrajectory(); 00456 void updateStateTriggered(); 00458 void executeButtonPressed(); 00460 void refreshSceneButtonPressed(); 00462 void viewOutcomesPressed(); 00464 void alterLinkPaddingPressed(); 00466 void alterAllowedCollisionPressed(); 00468 void trajectoryRenderTypeChanged(const QString& type); 00470 void motionPlanRenderTypeChanged(const QString& type); 00472 void objectColorButtonPressed(); 00473 void meshColorButtonPressed(); 00474 00476 void alteredLinkPaddingValueChanged(double d); 00477 00478 void firstEntityListSelected(); 00479 void secondEntityListSelected(); 00480 void entityListsEdited(); 00481 void disableCollisionClicked(); 00482 void enableCollisionClicked(); 00483 void resetAllowedCollisionClicked(); 00484 00485 void meshFileSelected(const QString& s); 00486 00487 void attachObject(const std::string& name); 00488 void addTouchLinkClicked(); 00489 void removeTouchLinkClicked(); 00490 00491 void editRobotStatePressed(); 00492 void editJointBoxChanged(const QString& joint); 00493 void jointStateSliderChanged(int nv); 00494 00495 void primaryPlannerTriggered(); 00496 void secondaryPlannerTriggered(); 00497 00498 protected: 00499 00500 bool planning_scene_initialized_; 00501 QLabel* selected_trajectory_label_; 00502 QLabel* selected_request_label_; 00503 QMenuBar* menu_bar_; 00504 QMenu* file_menu_; 00505 QMenu* planning_scene_menu_; 00506 QMenu* collision_object_menu_; 00507 QAction* new_object_action_; 00508 QAction* new_mesh_action_; 00509 QAction* refresh_action_; 00510 QAction* view_outcomes_action_; 00511 00512 QMenu* planner_configuration_menu_; 00513 QAction* set_primary_planner_action_; 00514 QAction* set_secondary_planner_action_; 00515 00516 QAction* alter_link_padding_action_; 00517 QDialog* alter_link_padding_dialog_; 00518 QTableWidget* alter_link_padding_table_; 00519 00520 QAction* alter_allowed_collision_action_; 00521 QDialog* alter_allowed_collision_dialog_; 00522 QLineEdit* first_allowed_collision_line_edit_; 00523 QLineEdit* second_allowed_collision_line_edit_; 00524 QLineEdit* allowed_status_line_edit_; 00525 QListWidget* first_allowed_collision_list_; 00526 QListWidget* second_allowed_collision_list_; 00527 00528 QDialog* attach_object_dialog_; 00529 QComboBox* attach_link_box_; 00530 QListWidget* possible_touch_links_; 00531 QListWidget* added_touch_links_; 00532 00533 QAction* edit_robot_state_action_; 00534 QDialog* edit_robot_state_dialog_; 00535 QComboBox* edit_joint_box_; 00536 QSlider* joint_state_slider_; 00537 QLineEdit* lower_bound_edit_window_; 00538 QLineEdit* upper_bound_edit_window_; 00539 QLineEdit* current_value_window_; 00540 00541 QDialog* load_planning_scene_dialog_; 00542 QDialog* new_object_dialog_; 00543 QDialog* new_mesh_dialog_; 00544 QDialog* new_request_dialog_; 00545 QDialog* outcome_dialog_; 00546 QTableWidget* stage_outcome_table_; 00547 QTableWidget* trajectory_outcome_table_; 00548 QProgressBar* load_scene_progress_; 00549 QAction* new_planning_scene_action_; 00550 QAction* new_motion_plan_action_; 00551 QAction* load_planning_scene_action_; 00552 QAction* save_planning_scene_action_; 00553 QAction* copy_planning_scene_action_; 00554 QAction* quit_action_; 00555 QTableWidget* planning_scene_table_; 00556 QTreeWidget* motion_plan_tree_; 00557 QTreeWidget* trajectory_tree_; 00558 QSlider* trajectory_slider_; 00559 QPushButton* play_button_; 00560 QPushButton* filter_button_; 00561 QPushButton* replan_button_; 00562 QPushButton* execute_button_; 00563 00564 QPushButton* new_planning_scene_button_; 00565 QPushButton* load_planning_scene_button_; 00566 QPushButton* refresh_planning_scene_button_; 00567 QPushButton* remove_planning_scene_button_; 00568 QPushButton* object_color_button_; 00569 QComboBox* collision_display_box_; 00570 00571 QSpinBox* trajectory_point_edit_; 00572 00573 TableLoadThread* table_load_thread_; 00574 00575 QComboBox* collision_object_type_box_; 00576 QLineEdit* collision_object_name_; 00577 QComboBox* request_group_name_box_; 00578 QSpinBox* collision_object_scale_x_box_; 00579 QSpinBox* collision_object_scale_y_box_; 00580 QSpinBox* collision_object_scale_z_box_; 00581 QSpinBox* collision_object_pos_x_box_; 00582 QSpinBox* collision_object_pos_y_box_; 00583 QSpinBox* collision_object_pos_z_box_; 00584 QPushButton* make_object_button_; 00585 00586 QLineEdit* mesh_object_name_; 00587 QSpinBox* mesh_object_pos_x_box_; 00588 QSpinBox* mesh_object_pos_y_box_; 00589 QSpinBox* mesh_object_pos_z_box_; 00590 QDoubleSpinBox* mesh_object_scale_x_box_; 00591 QDoubleSpinBox* mesh_object_scale_y_box_; 00592 QDoubleSpinBox* mesh_object_scale_z_box_; 00593 QPushButton* mesh_color_button_; 00594 QPushButton* make_mesh_button_; 00595 00596 QCheckBox* load_motion_plan_requests_box_; 00597 QCheckBox* load_trajectories_box_; 00598 QCheckBox* create_request_from_robot_box_; 00599 00600 QFileDialog* file_selector_; 00601 QLineEdit* mesh_filename_field_; 00602 00603 }; 00604 #endif