00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00030
00031
00032 #include <cstdio>
00033 #include <vector>
00034 #include <list>
00035 #include "ros/console.h"
00036 #include "std_msgs/String.h"
00037 #include "topic_tools/MuxSelect.h"
00038 #include "topic_tools/MuxAdd.h"
00039 #include "topic_tools/MuxList.h"
00040 #include "topic_tools/MuxDelete.h"
00041 #include "topic_tools/shape_shifter.h"
00042 #include "topic_tools/parse.h"
00043
00044 using std::string;
00045 using std::vector;
00046 using std::list;
00047 using namespace topic_tools;
00048
00049 const static string g_none_topic = "__none";
00050
00051 static ros::NodeHandle *g_node = NULL;
00052 static bool g_advertised = false;
00053 static string g_output_topic;
00054 static ros::Publisher g_pub;
00055 static ros::Publisher g_pub_selected;
00056
00057 struct sub_info_t
00058 {
00059 ros::Subscriber sub;
00060 ShapeShifter* msg;
00061 };
00062
00063 static list<struct sub_info_t> g_subs;
00064 static list<struct sub_info_t>::iterator g_selected = g_subs.end();
00065
00066 bool sel_srv_cb( topic_tools::MuxSelect::Request &req,
00067 topic_tools::MuxSelect::Response &res )
00068 {
00069 bool ret = false;
00070 if (g_selected != g_subs.end())
00071 res.prev_topic = g_selected->sub.getTopic();
00072 else
00073 res.prev_topic = string("");
00074
00075 if (req.topic == g_none_topic)
00076 {
00077 ROS_INFO("mux selected to no input.");
00078 g_selected = g_subs.end();
00079 ret = true;
00080 }
00081 else
00082 {
00083 ROS_INFO("trying to switch mux to %s", req.topic.c_str());
00084
00085 for (list<struct sub_info_t>::iterator it = g_subs.begin();
00086 it != g_subs.end();
00087 ++it)
00088 {
00089 if (ros::names::resolve(it->sub.getTopic()) == ros::names::resolve(req.topic))
00090 {
00091 g_selected = it;
00092 ROS_INFO("mux selected input: [%s]", it->sub.getTopic().c_str());
00093 ret = true;
00094 }
00095 }
00096 }
00097
00098 if(ret)
00099 {
00100 std_msgs::String t;
00101 t.data = req.topic;
00102 g_pub_selected.publish(t);
00103 }
00104
00105 return ret;
00106 }
00107
00108 bool sel_srv_cb_dep( topic_tools::MuxSelect::Request &req,
00109 topic_tools::MuxSelect::Response &res )
00110 {
00111 ROS_WARN("the <topic>_select service is deprecated; use mux/select instead");
00112 return sel_srv_cb(req,res);
00113 }
00114
00115
00116 void in_cb(const boost::shared_ptr<ShapeShifter const>& msg,
00117 ShapeShifter* s)
00118 {
00119 if (!g_advertised)
00120 {
00121 ROS_INFO("advertising");
00122 g_pub = msg->advertise(*g_node, g_output_topic, 10);
00123 g_advertised = true;
00124 }
00125 if (s == g_selected->msg)
00126 g_pub.publish(msg);
00127 }
00128
00129 bool list_topic_cb(topic_tools::MuxList::Request& req,
00130 topic_tools::MuxList::Response& res)
00131 {
00132 for (list<struct sub_info_t>::iterator it = g_subs.begin();
00133 it != g_subs.end();
00134 ++it)
00135 {
00136 res.topics.push_back(it->sub.getTopic());
00137 }
00138
00139 return true;
00140 }
00141
00142 bool add_topic_cb(topic_tools::MuxAdd::Request& req,
00143 topic_tools::MuxAdd::Response& res)
00144 {
00145
00146 ROS_INFO("trying to add %s to mux", req.topic.c_str());
00147
00148
00149 if(req.topic == g_none_topic)
00150 {
00151 ROS_WARN("failed to add topic %s to mux, because it's reserved for special use",
00152 req.topic.c_str());
00153 return false;
00154 }
00155
00156
00157 for (list<struct sub_info_t>::iterator it = g_subs.begin();
00158 it != g_subs.end();
00159 ++it)
00160 {
00161 if (ros::names::resolve(it->sub.getTopic()) == ros::names::resolve(req.topic))
00162 {
00163 ROS_WARN("tried to add a topic that mux was already listening to: [%s]",
00164 it->sub.getTopic().c_str());
00165 return false;
00166 }
00167 }
00168
00169 struct sub_info_t sub_info;
00170 sub_info.msg = new ShapeShifter;
00171 try
00172 {
00173 sub_info.sub = g_node->subscribe<ShapeShifter>(req.topic, 10, boost::bind(in_cb, _1, sub_info.msg));
00174 }
00175 catch(ros::InvalidNameException& e)
00176 {
00177 ROS_WARN("failed to add topic %s to mux, because it's an invalid name: %s",
00178 req.topic.c_str(), e.what());
00179 delete sub_info.msg;
00180 return false;
00181 }
00182 g_subs.push_back(sub_info);
00183
00184 ROS_INFO("added %s to mux", req.topic.c_str());
00185
00186 return true;
00187 }
00188
00189 bool del_topic_cb(topic_tools::MuxDelete::Request& req,
00190 topic_tools::MuxDelete::Response& res)
00191 {
00192
00193 ROS_INFO("trying to delete %s from mux", req.topic.c_str());
00194
00195 for (list<struct sub_info_t>::iterator it = g_subs.begin();
00196 it != g_subs.end();
00197 ++it)
00198 {
00199 if (ros::names::resolve(it->sub.getTopic()) == ros::names::resolve(req.topic))
00200 {
00201
00202 if(it == g_selected)
00203 {
00204 ROS_WARN("tried to delete currently selected topic %s from mux", req.topic.c_str());
00205 return false;
00206 }
00207 it->sub.shutdown();
00208 delete it->msg;
00209 g_subs.erase(it);
00210 ROS_INFO("deleted topic %s from mux", req.topic.c_str());
00211 return true;
00212 }
00213 }
00214
00215 ROS_WARN("tried to delete non-subscribed topic %s from mux", req.topic.c_str());
00216 return false;
00217 }
00218
00219 int main(int argc, char **argv)
00220 {
00221 vector<string> args;
00222 ros::removeROSArgs(argc, (const char**)argv, args);
00223
00224 if (args.size() < 3)
00225 {
00226 printf("\nusage: mux OUT_TOPIC IN_TOPIC1 [IN_TOPIC2 [...]]\n\n");
00227 return 1;
00228 }
00229 std::string topic_name;
00230 if(!getBaseName(args[1], topic_name))
00231 return 1;
00232 ros::init(argc, argv, topic_name + string("_mux"),
00233 ros::init_options::AnonymousName);
00234 vector<string> topics;
00235 for (unsigned int i = 2; i < args.size(); i++)
00236 topics.push_back(args[i]);
00237 ros::NodeHandle n;
00238 g_node = &n;
00239 g_output_topic = args[1];
00240
00241 ros::NodeHandle mux_nh("mux");
00242
00243 g_pub_selected = mux_nh.advertise<std_msgs::String>(string("selected"), 1, true);
00244
00245 ros::ServiceServer ss = n.advertiseService(g_output_topic + string("_select"), sel_srv_cb_dep);
00246
00247 ros::ServiceServer ss_select = mux_nh.advertiseService(string("select"), sel_srv_cb);
00248 ros::ServiceServer ss_add = mux_nh.advertiseService(string("add"), add_topic_cb);
00249 ros::ServiceServer ss_list = mux_nh.advertiseService(string("list"), list_topic_cb);
00250 ros::ServiceServer ss_del = mux_nh.advertiseService(string("delete"), del_topic_cb);
00251 for (size_t i = 0; i < topics.size(); i++)
00252 {
00253 struct sub_info_t sub_info;
00254 sub_info.msg = new ShapeShifter;
00255 sub_info.sub = n.subscribe<ShapeShifter>(topics[i], 10, boost::bind(in_cb, _1, sub_info.msg));
00256 g_subs.push_back(sub_info);
00257 }
00258 g_selected = g_subs.begin();
00259 std_msgs::String t;
00260 t.data = g_selected->sub.getTopic();
00261 g_pub_selected.publish(t);
00262 ros::spin();
00263 for (list<struct sub_info_t>::iterator it = g_subs.begin();
00264 it != g_subs.end();
00265 ++it)
00266 {
00267 it->sub.shutdown();
00268 delete it->msg;
00269 }
00270
00271 g_subs.clear();
00272 return 0;
00273 }
00274