cancel_action.cpp
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 #include <actionlib_msgs/GoalID.h>
00013 
00014 #include "cancel_action.h"
00015 
00016 namespace jsk_rviz_plugins
00017 {
00018 
00019   CancelAction::CancelAction( QWidget* parent )
00020     : rviz::Panel( parent )
00021   {
00022     layout = new QVBoxLayout;
00023 
00024     //Text Box and Add Button to add new topic
00025     QHBoxLayout* topic_layout = new QHBoxLayout;
00026 
00027     add_topic_box_ = new QComboBox;
00028     initComboBox();
00029     topic_layout->addWidget( add_topic_box_ );
00030 
00031     QPushButton* add_topic_button_ = new QPushButton("Add Action");
00032     topic_layout->addWidget( add_topic_button_ );
00033 
00034     layout->addLayout( topic_layout );
00035     //End of Text Box and Add Button
00036 
00037     m_sigmap = new QSignalMapper(this);
00038 
00039     connect(m_sigmap, SIGNAL(mapped(int)),this, SLOT(OnClickDeleteButton(int)));
00040 
00041     //Button to send cancel topic
00042     QPushButton* send_topic_button_ = new QPushButton("Cancel Action");
00043     layout->addWidget( send_topic_button_ );
00044 
00045     setLayout( layout );
00046 
00047     connect( send_topic_button_, SIGNAL( clicked() ), this, SLOT( sendTopic ()));
00048     connect( add_topic_button_, SIGNAL( clicked() ), this, SLOT( addTopic() ));
00049   }
00050 
00051   void CancelAction::initComboBox(){
00052     add_topic_box_->addItem("");
00053     ros::master::V_TopicInfo topics;
00054     ros::master::getTopics (topics);
00055     ros::master::V_TopicInfo::iterator it = topics.begin();
00056     while( it != topics.end()){
00057       if(it->datatype == "actionlib_msgs/GoalID"){
00058         std::string action_name = it->name;
00059         std::string delete_string = "/cancel";
00060         std::string::size_type index = action_name.find_last_of(delete_string);
00061         if(index != std::string::npos){
00062           action_name.erase(index - delete_string.length() + 1);
00063           add_topic_box_->addItem(action_name.c_str());
00064         }
00065       }
00066       it ++;
00067     }
00068   }
00069 
00070 
00071   void CancelAction::OnClickDeleteButton(int id){
00072     std::vector<topicListLayout>::iterator it = topic_list_layouts_.begin();
00073     while( it != topic_list_layouts_.end()){
00074       if(it->id == id){
00075         it->topic_name_->hide();
00076         delete it->topic_name_;
00077 
00078         it->remove_button_->hide();
00079         delete it->remove_button_;
00080 
00081         delete it->layout_;
00082         it->publisher_.shutdown();
00083         it = topic_list_layouts_.erase( it );
00084         Q_EMIT configChanged();
00085       }else{
00086         ++it;
00087       }
00088     }
00089   }
00090 
00091   void CancelAction::addTopic()
00092   {
00093     output_topic_ = add_topic_box_->currentText();
00094     if( output_topic_ != "" ){
00095       add_topic_box_->setCurrentIndex( 0 );
00096       addTopicList(output_topic_.toStdString());
00097     }
00098     Q_EMIT configChanged();
00099   }
00100 
00101   void CancelAction::addTopicList(std::string topic_name){
00102     topicListLayout tll;
00103 
00104     if(!topic_list_layouts_.empty()){
00105       topicListLayout lastTll = topic_list_layouts_.back();
00106       tll.id = lastTll.id + 1;
00107     }else{
00108       tll.id = 0;
00109     }
00110 
00111     tll.layout_ = new QHBoxLayout;
00112 
00113     tll.topic_name_ = new QLabel( topic_name.c_str() );
00114     tll.layout_->addWidget( tll.topic_name_ );
00115 
00116     tll.remove_button_ = new QPushButton("Delete");
00117     tll.layout_->addWidget( tll.remove_button_ );
00118 
00119     layout->addLayout(tll.layout_);
00120 
00121     tll.publisher_ = nh_.advertise<actionlib_msgs::GoalID>( topic_name + "/cancel", 1 );
00122     
00123     topic_list_layouts_.push_back(tll);
00124 
00125     connect(tll.remove_button_, SIGNAL(clicked()), m_sigmap, SLOT(map()));
00126     m_sigmap->setMapping(tll.remove_button_, tll.id);
00127 
00128   }
00129 
00130   void CancelAction::sendTopic(){
00131     std::vector<topicListLayout>::iterator it = topic_list_layouts_.begin();
00132     while( it != topic_list_layouts_.end()){
00133       actionlib_msgs::GoalID msg;
00134       it->publisher_.publish(msg);
00135       it++;
00136     }
00137   }
00138 
00139   void CancelAction::save( rviz::Config config ) const
00140   {
00141     rviz::Panel::save( config );
00142 
00143     rviz::Config topic_list_config = config.mapMakeChild( "topics" );
00144 
00145     std::vector<topicListLayout>::const_iterator it = topic_list_layouts_.begin();
00146     while( it != topic_list_layouts_.end()){
00147       topic_list_config.listAppendNew().setValue( it->topic_name_->text() );
00148       it ++;
00149     }
00150     config.mapSetValue( "Topic", output_topic_ );
00151   }
00152 
00153   // Load all configuration data for this panel from the given Config object.
00154   void CancelAction::load( const rviz::Config& config )
00155   {
00156     rviz::Panel::load( config );
00157     rviz::Config topic_list_config = config.mapGetChild( "topics" );
00158     int num_topics = topic_list_config.listLength();
00159 
00160     for( int i = 0; i < num_topics; i++ ) {
00161       addTopicList(topic_list_config.listChildAt( i ).getValue().toString().toStdString());
00162     }
00163   }
00164 
00165 }
00166 
00167 #include <pluginlib/class_list_macros.h>
00168 PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::CancelAction, rviz::Panel )


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