record_action.h
Go to the documentation of this file.
00001 #ifndef RECORD_ACTION_H
00002 #define RECORD_ACTION_H
00003 
00004 #include <ros/ros.h>
00005 
00006 #include <rviz/panel.h>
00007 #include <QtGui>
00008 #include <jsk_rviz_plugins/RecordCommand.h>
00009 
00010 class QLineEdit;
00011 class QLabel;
00012 class QPushButton;
00013 
00014 namespace jsk_rviz_plugins
00015 {
00016   class RecordAction: public rviz::Panel
00017   {
00018     enum RecordState{
00019       IDLE = 0,
00020       RECORD = 1
00021     };
00022     Q_OBJECT
00023     public:
00024     RecordAction( QWidget* parent = 0 );
00025 
00026     virtual void load( const rviz::Config& config );
00027     virtual void save( rviz::Config config ) const;
00028 
00029   public Q_SLOTS:
00030 
00031     void setTopic( const QString& topic );
00032 
00033   protected Q_SLOTS:
00034 
00035     void updateTopic();
00036 
00037     void commandPlay();
00038     void recordClick();
00039 
00040     void addTopicList(std::string topic_name);
00041 
00042     void OnClickPlayButton(int id);
00043     void OnClickDeleteButton(int id);
00044 
00045   protected:
00046     QLineEdit* record_motion_name_editor_;
00047 
00048     QString output_topic_;
00049 
00050     QPushButton* record_interface_button_;
00051 
00052     QComboBox* add_topic_box_;
00053 
00054     QSignalMapper *m_delete_sigmap_;
00055     QSignalMapper *m_play_sigmap_;
00056 
00057     QVBoxLayout* layout;
00058 
00059     struct motionListLayout{
00060       int id;
00061       QHBoxLayout* layout_;
00062       QPushButton* play_button_;
00063       QPushButton* remove_button_;
00064       QLabel* target_name_;
00065     };
00066 
00067     std::vector<motionListLayout> motion_list_layouts_;
00068 
00069     ros::Publisher pub_;
00070     ros::NodeHandle nh_;
00071     RecordState rstate_;
00072   };
00073 
00074 }
00075 
00076 #endif


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Sun Sep 13 2015 22:29:03