cancel_action.cpp
Go to the documentation of this file.
1 #include <stdio.h>
2 
3 #include <QPainter>
4 #include <QLineEdit>
5 #include <QPushButton>
6 #include <QVBoxLayout>
7 #include <QHBoxLayout>
8 #include <QLabel>
9 #include <QTimer>
10 
11 #include <std_msgs/Empty.h>
12 #include <actionlib_msgs/GoalID.h>
13 
14 #include "cancel_action.h"
15 
16 namespace jsk_rviz_plugins
17 {
18 
19  CancelAction::CancelAction( QWidget* parent )
20  : rviz::Panel( parent )
21  {
22  layout = new QVBoxLayout;
23 
24  //Text Box and Add Button to add new topic
25  QHBoxLayout* topic_layout = new QHBoxLayout;
26 
27  add_topic_box_ = new QComboBox;
28  initComboBox();
29  topic_layout->addWidget( add_topic_box_ );
30 
31  QPushButton* add_topic_button_ = new QPushButton("Add Action");
32  topic_layout->addWidget( add_topic_button_ );
33 
34  layout->addLayout( topic_layout );
35  //End of Text Box and Add Button
36 
37  m_sigmap = new QSignalMapper(this);
38 
39  connect(m_sigmap, SIGNAL(mapped(int)),this, SLOT(OnClickDeleteButton(int)));
40 
41  //Button to send cancel topic
42  QPushButton* send_topic_button_ = new QPushButton("Cancel Action");
43  layout->addWidget( send_topic_button_ );
44 
45  setLayout( layout );
46 
47  connect( send_topic_button_, SIGNAL( clicked() ), this, SLOT( sendTopic ()));
48  connect( add_topic_button_, SIGNAL( clicked() ), this, SLOT( addTopic() ));
49  }
50 
52  add_topic_box_->addItem("");
54  ros::master::getTopics (topics);
55  ros::master::V_TopicInfo::iterator it = topics.begin();
56  while( it != topics.end()){
57  if(it->datatype == "actionlib_msgs/GoalID"){
58  std::string action_name = it->name;
59  std::string delete_string = "/cancel";
60  std::string::size_type index = action_name.find_last_of(delete_string);
61  if(index != std::string::npos){
62  action_name.erase(index - delete_string.length() + 1);
63  add_topic_box_->addItem(action_name.c_str());
64  }
65  }
66  it ++;
67  }
68  }
69 
70 
72  std::vector<topicListLayout>::iterator it = topic_list_layouts_.begin();
73  while( it != topic_list_layouts_.end()){
74  if(it->id == id){
75  it->topic_name_->hide();
76  delete it->topic_name_;
77 
78  it->remove_button_->hide();
79  delete it->remove_button_;
80 
81  delete it->layout_;
82  it->publisher_.shutdown();
83  it = topic_list_layouts_.erase( it );
84  Q_EMIT configChanged();
85  }else{
86  ++it;
87  }
88  }
89  }
90 
92  {
93  output_topic_ = add_topic_box_->currentText();
94  if( output_topic_ != "" ){
95  add_topic_box_->setCurrentIndex( 0 );
96  addTopicList(output_topic_.toStdString());
97  }
98  Q_EMIT configChanged();
99  }
100 
101  void CancelAction::addTopicList(std::string topic_name){
102  topicListLayout tll;
103 
104  if(!topic_list_layouts_.empty()){
105  topicListLayout lastTll = topic_list_layouts_.back();
106  tll.id = lastTll.id + 1;
107  }else{
108  tll.id = 0;
109  }
110 
111  tll.layout_ = new QHBoxLayout;
112 
113  tll.topic_name_ = new QLabel( topic_name.c_str() );
114  tll.layout_->addWidget( tll.topic_name_ );
115 
116  tll.remove_button_ = new QPushButton("Delete");
117  tll.layout_->addWidget( tll.remove_button_ );
118 
119  layout->addLayout(tll.layout_);
120 
121  tll.publisher_ = nh_.advertise<actionlib_msgs::GoalID>( topic_name + "/cancel", 1 );
122 
123  topic_list_layouts_.push_back(tll);
124 
125  connect(tll.remove_button_, SIGNAL(clicked()), m_sigmap, SLOT(map()));
126  m_sigmap->setMapping(tll.remove_button_, tll.id);
127 
128  }
129 
131  std::vector<topicListLayout>::iterator it = topic_list_layouts_.begin();
132  while( it != topic_list_layouts_.end()){
133  actionlib_msgs::GoalID msg;
134  it->publisher_.publish(msg);
135  it++;
136  }
137  }
138 
139  void CancelAction::save( rviz::Config config ) const
140  {
141  rviz::Panel::save( config );
142 
143  rviz::Config topic_list_config = config.mapMakeChild( "topics" );
144 
145  std::vector<topicListLayout>::const_iterator it = topic_list_layouts_.begin();
146  while( it != topic_list_layouts_.end()){
147  topic_list_config.listAppendNew().setValue( it->topic_name_->text() );
148  it ++;
149  }
150  config.mapSetValue( "Topic", output_topic_ );
151  }
152 
153  // Load all configuration data for this panel from the given Config object.
154  void CancelAction::load( const rviz::Config& config )
155  {
156  rviz::Panel::load( config );
157  rviz::Config topic_list_config = config.mapGetChild( "topics" );
158  int num_topics = topic_list_config.listLength();
159 
160  for( int i = 0; i < num_topics; i++ ) {
161  addTopicList(topic_list_config.listChildAt( i ).getValue().toString().toStdString());
162  }
163  }
164 
165 }
166 
msg
void setValue(const QVariant &value)
void addTopicList(std::string topic_name)
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
virtual void load(const rviz::Config &config)
int listLength() const
Config listChildAt(int i) const
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
void configChanged()
std::vector< TopicInfo > V_TopicInfo
void mapSetValue(const QString &key, QVariant value)
CancelAction(QWidget *parent=0)
std::vector< topicListLayout > topic_list_layouts_
Definition: cancel_action.h:71
QVariant getValue() const
virtual void save(rviz::Config config) const
Config mapMakeChild(const QString &key)
topics
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Config listAppendNew()
virtual void save(Config config) const
Config mapGetChild(const QString &key) const
virtual void load(const Config &config)


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Sat Mar 20 2021 03:03:18