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


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Wed May 1 2019 02:40:22