Go to the documentation of this file.00001 #include <stdio.h>
00002 
00003 #include <QPainter>
00004 #include <QLineEdit>
00005 #include <QPushButton>
00006 #include <QVBoxLayout>
00007 #include <QHBoxLayout>
00008 #include <QLabel>
00009 #include <QTimer>
00010 
00011 #include <std_msgs/Empty.h>
00012 
00013 #include "publish_topic.h"
00014 
00015 namespace jsk_rviz_plugins
00016 {
00017   PublishTopic::PublishTopic( QWidget* parent )
00018     : rviz::Panel( parent )
00019   {
00020     QHBoxLayout* topic_layout = new QHBoxLayout;
00021     topic_layout->addWidget( new QLabel( "Topic:" ));
00022     output_topic_editor_ = new QLineEdit;
00023     topic_layout->addWidget( output_topic_editor_ );
00024 
00025 
00026     
00027     QVBoxLayout* layout = new QVBoxLayout;
00028     layout->addLayout( topic_layout );
00029 
00030     QPushButton* send_topic_button_ = new QPushButton("Send Topic");
00031     layout->addWidget( send_topic_button_ );
00032     setLayout( layout );
00033 
00034 
00035     connect( send_topic_button_, SIGNAL( clicked() ), this, SLOT( sendTopic ()));
00036     connect( output_topic_editor_, SIGNAL( editingFinished() ), this, SLOT( updateTopic() ));
00037 
00038   }
00039 
00040   void PublishTopic::updateTopic()
00041   {
00042     setTopic( output_topic_editor_->text() );
00043   }
00044 
00045   
00046   void PublishTopic::setTopic( const QString& new_topic )
00047   {
00048     
00049     if( new_topic != output_topic_ )
00050       {
00051         output_topic_ = new_topic;
00052         
00053         if( output_topic_ == "" )
00054           {
00055             velocity_publisher_.shutdown();
00056           }
00057         else
00058           {
00059             velocity_publisher_ = nh_.advertise<std_msgs::Empty>( output_topic_.toStdString(), 1 );
00060           }
00061 
00062         Q_EMIT configChanged();
00063       }
00064   }
00065   
00066   void PublishTopic::sendTopic(){
00067     std_msgs::Empty msg;
00068     velocity_publisher_.publish(msg);
00069   }
00070 
00071 
00072   void PublishTopic::save( rviz::Config config ) const
00073   {
00074     rviz::Panel::save( config );
00075     config.mapSetValue( "Topic", output_topic_ );
00076   }
00077 
00078   
00079   void PublishTopic::load( const rviz::Config& config )
00080   {
00081     rviz::Panel::load( config );
00082     QString topic;
00083     if( config.mapGetString( "Topic", &topic ))
00084       {
00085         output_topic_editor_->setText( topic );
00086         updateTopic();
00087       }
00088   }
00089 
00090 }
00091 
00092 #include <pluginlib/class_list_macros.h>
00093 PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PublishTopic, rviz::Panel )
00094