mux_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
36 #include <std_msgs/String.h>
38 
39 namespace jsk_topic_tools
40 {
41 
42  const static std::string g_none_topic = "__none";
43 
44  void MUX::onInit()
45  {
46  advertised_ = false;
48  readVectorParameter(pnh_, "topics", topics_);
49  if (topics_.size() < 1) {
50  NODELET_FATAL("need to specify at least one topic in ~topics");
51  return;
52  }
53  pub_selected_ = pnh_.advertise<std_msgs::String>("selected", 1, true);
54  // in original mux node, it subscribes all the topics first, however
55  // in our version, we never subscribe topic which are not selected.
56  // ros::SubscriberStatusCallback connect_cb
57  // = boost::bind( &Mux::connectCb, this);
60  // service advertise: _select, select, add, list, delete
63  ss_list_ = pnh_.advertiseService("list_topics", &MUX::listTopicCallback, this);
65 
66  }
67 
69  {
70  // new subscriber come or
71  if (pub_.getNumSubscribers() > 0) {
72  // subscribe topic again
73  if (!subscribing_) {
74  //NODELET_INFO("subscribe");
75  sub_.reset(new ros::Subscriber(
77  selected_topic_, 10,
78  &MUX::inputCallback, this, th_)));
79  subscribing_ = true;
80  }
81  }
82  else {
83  if (subscribing_) {
84  //NODELET_INFO("unsubscribe");
85  sub_->shutdown();
86  subscribing_ = false;
87  }
88  }
89  }
90 
91 
92 
93  bool MUX::selectTopicCallback(topic_tools::MuxSelect::Request &req,
94  topic_tools::MuxSelect::Response &res)
95  {
96  res.prev_topic = selected_topic_;
97  if (selected_topic_ != g_none_topic) {
98  //NODELET_INFO("unsubscribe");
99  sub_->shutdown(); // unsubscribe first
100  }
101 
102  if (req.topic == g_none_topic) { // same topic
104  return true;
105  }
106  for (size_t i = 0; i < topics_.size(); i++) {
107  if (pnh_.resolveName(topics_[i]) == pnh_.resolveName(req.topic)) {
108  // subscribe the topic
111  return true;
112  }
113  }
114 
115  NODELET_WARN("%s is not provided in topic list", req.topic.c_str());
116  return false;
117  }
118 
119  bool MUX::addTopicCallback(topic_tools::MuxAdd::Request& req,
120  topic_tools::MuxAdd::Response& res)
121  {
122  NODELET_INFO("trying to add %s to mux", req.topic.c_str());
123  if (req.topic == g_none_topic) {
124  NODELET_WARN("failed to add topic %s to mux, because it's reserved for special use",
125  req.topic.c_str());
126  return false;
127  }
128 
129  for (size_t i = 0; i < topics_.size(); i++) {
130  if (pnh_.resolveName(topics_[i]) == pnh_.resolveName(req.topic)) {
131  NODELET_WARN("tried to add a topic that mux was already listening to: [%s]",
132  topics_[i].c_str());
133  return false;
134  }
135  }
136 
137  // in original mux, it subscribes the topic immediately after adds topic.
138  // in this version, we postpone the subscription until selected.
139 
140  topics_.push_back(ros::names::resolve(req.topic));
141  return true;
142  }
143 
144  bool MUX::deleteTopicCallback(topic_tools::MuxDelete::Request& req,
145  topic_tools::MuxDelete::Response& res)
146  {
147  // cannot delete the topic now selected
148  for (size_t i = 0; i < topics_.size(); i++) {
149  if (pnh_.resolveName(topics_[i]) == pnh_.resolveName(req.topic)) {
150  if (pnh_.resolveName(req.topic) == pnh_.resolveName(selected_topic_)) {
151  NODELET_WARN("tried to delete currently selected topic %s from mux",
152  req.topic.c_str());
153  return false;
154  }
155  topics_.erase(topics_.begin() + i);
156  return true;
157  }
158  }
159  NODELET_WARN("cannot find the topics %s in the list of mux",
160  req.topic.c_str());
161  return false;
162  }
163 
164  bool MUX::listTopicCallback(topic_tools::MuxList::Request& req,
165  topic_tools::MuxList::Response& res)
166  {
167  for (size_t i = 0; i < topics_.size(); i++) {
168  res.topics.push_back(pnh_.resolveName(topics_[i]));
169  }
170  return true;
171  }
172 
174  {
175  // subscribe topic in order to "advertise"
176  advertised_ = false;
177  subscribing_ = false;
178  // assume that selected_topic_ is already set correctly
179  if (selected_topic_ == g_none_topic) {
180  NODELET_WARN("none topic is selected");
181  return;
182  }
183  //NODELET_INFO("subscribe");
184  sub_.reset(new ros::Subscriber(
186  selected_topic_, 10,
187  &MUX::inputCallback, this, th_)));
188  std_msgs::String msg;
189  msg.data = selected_topic_;
190  pub_selected_.publish(msg);
191  }
192 
194  {
195  if (!advertised_) { // first time
197  = boost::bind(&MUX::connectCb, this, _1);
198  ros::AdvertiseOptions opts("output", 1,
199  msg->getMD5Sum(),
200  msg->getDataType(),
201  msg->getMessageDefinition(),
202  connect_cb,
203  connect_cb);
204  pub_ = pnh_.advertise(opts);
205  advertised_ = true;
206  sub_->shutdown();
207  //NODELET_INFO("unsubscribe");
208  }
209  pub_.publish(msg);
210  }
211 
212 }
213 
216 
msg
boost::shared_ptr< ros::Subscriber > sub_
Definition: mux_nodelet.h:69
virtual void inputCallback(const boost::shared_ptr< topic_tools::ShapeShifter const > &msg)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
std::vector< std::string > topics_
Definition: mux_nodelet.h:67
ros::Publisher pub_
Definition: mux_nodelet.h:71
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::ServiceServer ss_del_
Definition: mux_nodelet.h:74
std::string resolveName(const std::string &name, bool remap=true) const
ros::Publisher pub_selected_
Definition: mux_nodelet.h:70
PLUGINLIB_EXPORT_CLASS(jsk_topic_tools::Snapshot, nodelet::Nodelet)
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::ServiceServer ss_add_
Definition: mux_nodelet.h:74
ros::NodeHandle & getPrivateNodeHandle() const
virtual bool selectTopicCallback(topic_tools::MuxSelect::Request &req, topic_tools::MuxSelect::Response &res)
Definition: mux_nodelet.cpp:93
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
ros::NodeHandle pnh_
Definition: mux_nodelet.h:72
virtual void subscribeSelectedTopic()
virtual void connectCb(const ros::SingleSubscriberPublisher &pub)
Definition: mux_nodelet.cpp:68
std::string selected_topic_
Definition: mux_nodelet.h:68
virtual void onInit()
Definition: mux_nodelet.cpp:44
ros::ServiceServer ss_list_
Definition: mux_nodelet.h:74
static const std::string g_none_topic
Definition: mux_nodelet.cpp:42
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
jsk_topic_tools::MUX MUX
ros::ServiceServer ss_select_
Definition: mux_nodelet.h:74
virtual bool deleteTopicCallback(topic_tools::MuxDelete::Request &req, topic_tools::MuxDelete::Response &res)
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
virtual bool listTopicCallback(topic_tools::MuxList::Request &req, topic_tools::MuxList::Response &res)
#define NODELET_FATAL(...)
virtual bool addTopicCallback(topic_tools::MuxAdd::Request &req, topic_tools::MuxAdd::Response &res)
ros::TransportHints th_
Definition: mux_nodelet.h:73


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Tue Feb 6 2018 03:45:19