cancel_action.h
Go to the documentation of this file.
00001 #ifndef CANCEL_ACTION_H
00002 #define CANCEL_ACTION_H
00003 
00004 #include <ros/ros.h>
00005 
00006 #include <rviz/panel.h>
00007 #include <QtGui>
00008 
00009 class QLineEdit;
00010 class QLabel;
00011 class QPushButton;
00012 //class QSignalMapper;
00013 
00014 namespace jsk_rviz_plugin
00015 {
00016   class CancelAction: public rviz::Panel
00017     {
00018       // This class uses Qt slots and is a subclass of QObject, so it needs
00019       // the Q_OBJECT macro.
00020 Q_OBJECT
00021   public:
00022       CancelAction( QWidget* parent = 0 );
00023 
00024       
00025       virtual void load( const rviz::Config& config );
00026       virtual void save( rviz::Config config ) const;
00027 
00028       public Q_SLOTS:
00029 
00030       void setTopic( const QString& topic );
00031 
00032       protected Q_SLOTS:
00033 
00034       void updateTopic();
00035 
00036       void sendTopic();
00037       void addTopic();
00038       void initComboBox();
00039 
00040       void addTopicList(std::string topic_name);
00041 
00042       void OnClickDeleteButton(int id);
00043 
00044     protected:
00045       QLineEdit* output_topic_editor_;
00046 
00047       QString output_topic_;
00048 
00049       QPushButton* add_topic_button_;
00050 
00051       QComboBox* add_topic_box_;
00052 
00053       QPushButton* send_topic_button_;
00054 
00055       QSignalMapper *m_sigmap;
00056 
00057       QVBoxLayout* layout;
00058 
00059       struct topicListLayout{
00060         int id;
00061         QHBoxLayout* layout_;
00062         QPushButton* remove_button_;
00063         QLabel* topic_name_;
00064         ros::Publisher publisher_;
00065       };
00066 
00067       std::vector<topicListLayout> topic_list_layouts_;
00068 
00069       // The ROS publisher for the command velocity.
00070       ros::Publisher velocity_publisher_;
00071 
00072       // The ROS node handle.
00073       ros::NodeHandle nh_;
00074 
00075     };
00076 
00077 }
00078 
00079 #endif // TELEOP_PANEL_H


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Oct 6 2014 01:18:44