00001 00012 #ifndef RAIL_PICK_AND_PLACE_MODEL_GENERATION_PANEL_H_ 00013 #define RAIL_PICK_AND_PLACE_MODEL_GENERATION_PANEL_H_ 00014 00015 // ROS 00016 #include <actionlib/client/simple_action_client.h> 00017 #include <graspdb/graspdb.h> 00018 #include <rail_pick_and_place_msgs/GenerateModelsAction.h> 00019 #include <rail_pick_and_place_msgs/RetrieveGraspDemonstrationAction.h> 00020 #include <rail_pick_and_place_msgs/RetrieveGraspModelAction.h> 00021 #include <ros/ros.h> 00022 #include <rviz/panel.h> 00023 00024 // Qt 00025 #include <QComboBox> 00026 #include <QLabel> 00027 #include <QListWidget> 00028 #include <QPushButton> 00029 #include <QSpinBox> 00030 00031 namespace rail 00032 { 00033 namespace pick_and_place 00034 { 00035 00042 class ModelGenerationPanel : public rviz::Panel 00043 { 00044 00045 // this class uses Qt slots and is a subclass of QObject, so it needs the Q_OBJECT macro 00046 Q_OBJECT 00047 00048 public: 00056 ModelGenerationPanel(QWidget *parent = NULL); 00057 00063 virtual ~ModelGenerationPanel(); 00064 00072 virtual void load(const rviz::Config &config); 00073 00081 virtual void save(rviz::Config config) const; 00082 00083 private: 00092 void doneCallback(const actionlib::SimpleClientGoalState &state, 00093 const rail_pick_and_place_msgs::GenerateModelsResultConstPtr &result); 00094 00102 void feedbackCallback(const rail_pick_and_place_msgs::GenerateModelsFeedbackConstPtr &feedback); 00103 00105 graspdb::Client *graspdb_; 00106 00108 ros::NodeHandle node_; 00110 actionlib::SimpleActionClient<rail_pick_and_place_msgs::GenerateModelsAction> generate_models_ac_; 00112 actionlib::SimpleActionClient<rail_pick_and_place_msgs::RetrieveGraspDemonstrationAction> retrieve_grasp_ac_; 00114 actionlib::SimpleActionClient<rail_pick_and_place_msgs::RetrieveGraspModelAction> retrieve_grasp_model_ac_; 00115 00117 QLabel *model_generation_status_; 00119 QComboBox *object_list_; 00121 QListWidget *models_list_; 00123 QSpinBox *model_size_spin_box_; 00125 QPushButton *refresh_button_, *select_all_button_, *deselect_all_button_, *generate_models_button_, *delete_button_; 00126 00127 // used as UI callbacks 00128 private 00129 Q_SLOTS: 00130 00136 void executeGenerateModels(); 00137 00143 void deleteModel(); 00144 00150 void selectAll(); 00151 00157 void deselectAll(); 00158 00164 void populateModelsList(const QString &text); 00165 00171 void modelSelectionChanged(); 00172 00178 void refresh(); 00179 }; 00180 00181 } 00182 } 00183 00184 #endif