36 #include "std_msgs/String.h"
37 #include "topic_tools/MuxSelect.h"
38 #include "topic_tools/MuxAdd.h"
39 #include "topic_tools/MuxList.h"
40 #include "topic_tools/MuxDelete.h"
70 static list<struct sub_info_t>
g_subs;
85 topic_tools::MuxSelect::Response &res )
93 ROS_DEBUG(
"Unsubscribing to %s, lazy", res.prev_topic.c_str());
101 res.prev_topic = string(
"");
106 ROS_INFO(
"mux selected to no input.");
113 ROS_INFO(
"trying to switch mux to %s", req.topic.c_str());
115 for (list<struct sub_info_t>::iterator it =
g_subs.begin();
122 ROS_INFO(
"mux selected input: [%s]", it->topic_name.c_str());
143 topic_tools::MuxSelect::Response &res )
145 ROS_WARN(
"the <topic>_select service is deprecated; use mux/select instead");
166 for (
static list<struct sub_info_t>::iterator it =
g_subs.begin(); it !=
g_subs.end(); ++it) {
168 ROS_INFO(
"Unregistering from %s", it->topic_name.c_str());
183 ROS_INFO(
"lazy mode; unsubscribing");
193 topic_tools::MuxList::Response& res)
196 for (list<struct sub_info_t>::iterator it =
g_subs.begin();
200 res.topics.push_back(it->topic_name);
207 topic_tools::MuxAdd::Response& res)
211 ROS_INFO(
"trying to add %s to mux", req.topic.c_str());
216 ROS_WARN(
"failed to add topic %s to mux, because it's reserved for special use",
222 for (list<struct sub_info_t>::iterator it =
g_subs.begin();
228 ROS_WARN(
"tried to add a topic that mux was already listening to: [%s]",
229 it->topic_name.c_str());
246 ROS_WARN(
"failed to add topic %s to mux, because it's an invalid name: %s",
247 req.topic.c_str(), e.what());
251 g_subs.push_back(sub_info);
253 ROS_INFO(
"added %s to mux", req.topic.c_str());
259 topic_tools::MuxDelete::Response& res)
263 ROS_INFO(
"trying to delete %s from mux", req.topic.c_str());
265 for (list<struct sub_info_t>::iterator it =
g_subs.begin();
274 ROS_WARN(
"tried to delete currently selected topic %s from mux", req.topic.c_str());
282 ROS_INFO(
"deleted topic %s from mux", req.topic.c_str());
287 ROS_WARN(
"tried to delete non-subscribed topic %s from mux", req.topic.c_str());
291 int main(
int argc,
char **argv)
298 printf(
"\nusage: mux OUT_TOPIC IN_TOPIC1 [IN_TOPIC2 [...]]\n\n");
306 vector<string> topics;
307 for (
unsigned int i = 2; i <
args.size(); i++)
308 topics.push_back(
args[i]);
318 g_pub_selected = mux_nh.advertise<std_msgs::String>(string(
"selected"), 1,
true);
320 for (
size_t i = 0; i < topics.size(); i++)
327 g_subs.push_back(sub_info);
331 std::string initial_topic;
332 pnh.
getParam(
"initial_topic", initial_topic);
334 if (initial_topic.empty())
341 ROS_INFO(
"mux selected to no input.");
347 ROS_INFO(
"trying to switch mux to %s", initial_topic.c_str());
349 for (list<struct sub_info_t>::iterator it =
g_subs.begin();
356 t.data = initial_topic;
357 ROS_INFO(
"mux selected input: [%s]", it->topic_name.c_str());
382 for (list<struct sub_info_t>::iterator it =
g_subs.begin();