11 #include <std_msgs/Empty.h>
12 #include <actionlib_msgs/GoalID.h>
25 QHBoxLayout* topic_layout =
new QHBoxLayout;
34 layout->addLayout( topic_layout );
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);
75 it->topic_name_->hide();
76 delete it->topic_name_;
78 it->remove_button_->hide();
79 delete it->remove_button_;
82 it->publisher_.shutdown();
106 tll.
id = lastTll.
id + 1;
113 tll.
topic_name_ =
new QLabel( topic_name.c_str() );
133 actionlib_msgs::GoalID
msg;
134 it->publisher_.publish(
msg);
158 int num_topics = topic_list_config.
listLength();
160 for(
int i = 0; i < num_topics; i++ ) {