MetricTrainingPanel.h
Go to the documentation of this file.
00001 
00011 #ifndef RAIL_PICK_AND_PLACE_METRIC_TRAINING_PANEL_H_
00012 #define RAIL_PICK_AND_PLACE_METRIC_TRAINING_PANEL_H_
00013 
00014 // ROS
00015 #include <actionlib/client/simple_action_client.h>
00016 #include <actionlib/server/simple_action_server.h>
00017 #include <graspdb/graspdb.h>
00018 #include <rail_pick_and_place_msgs/GetYesNoFeedbackAction.h>
00019 #include <rail_pick_and_place_msgs/TrainMetricsAction.h>
00020 #include <ros/ros.h>
00021 #include <rviz/panel.h>
00022 
00023 // Boost
00024 #include <boost/thread/mutex.hpp>
00025 
00026 // Qt
00027 #include <QComboBox>
00028 #include <QLabel>
00029 #include <QPushButton>
00030 
00031 namespace rail
00032 {
00033 namespace pick_and_place
00034 {
00035 
00042 class MetricTrainingPanel : 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   MetricTrainingPanel(QWidget *parent = NULL);
00057 
00063   virtual ~MetricTrainingPanel();
00064 
00072   virtual void load(const rviz::Config &config);
00073 
00081   virtual void save(rviz::Config config) const;
00082 
00083 private:
00091   void getYesNoFeedbackCallback(const rail_pick_and_place_msgs::GetYesNoFeedbackGoalConstPtr &goal);
00092 
00101   void doneCallback(const actionlib::SimpleClientGoalState &state,
00102       const rail_pick_and_place_msgs::TrainMetricsResultConstPtr &result);
00103 
00111   void feedbackCallback(const rail_pick_and_place_msgs::TrainMetricsFeedbackConstPtr &feedback);
00112 
00114   graspdb::Client *graspdb_;
00116   bool responded_, yes_;
00117 
00119   boost::mutex mutex_;
00120 
00122   ros::NodeHandle node_;
00124   ros::ServiceServer get_yes_no_feedback_srv_;
00126   actionlib::SimpleActionServer<rail_pick_and_place_msgs::GetYesNoFeedbackAction> as_;
00128   actionlib::SimpleActionClient<rail_pick_and_place_msgs::TrainMetricsAction> train_metrics_ac_;
00129 
00131   QComboBox *object_list_;
00133   QPushButton *train_metrics_button_, *refresh_button_, *yes_button_, *no_button_;
00135   QLabel *train_metrics_status_;
00136 
00137 // used as UI callbacks
00138 private Q_SLOTS:
00139 
00145   void executeTrainMetrics();
00146 
00152   void refresh();
00153 
00159   void setYesFeedback();
00160 
00166   void setNoFeedback();
00167 };
00168 
00169 }
00170 }
00171 
00172 #endif


rail_pick_and_place_tools
Author(s): Russell Toris , David Kent
autogenerated on Sun Mar 6 2016 11:39:08