34 #include "topic_tools/MuxSelect.h" 40 int main(
int argc,
char **argv)
42 ROS_WARN(
"topic_tools/switch_mux is deprecated; please use topic_tools/mux_select instead");
45 printf(
"usage: switch MUXED_TOPIC SELECT_TOPIC\n");
48 std::string topic_name;
51 ros::init(argc, argv, topic_name +
string(
"_switcher"));
53 string srv_name = string(argv[1]) +
"_select";
54 ROS_INFO(
"Waiting for service %s...\n", srv_name.c_str());
58 cmd.request.topic = argv[2];
61 ROS_INFO(
"muxed topic %s successfully switched from %s to %s",
62 argv[1], cmd.response.prev_topic.c_str(),
63 cmd.request.topic.c_str());
68 ROS_ERROR(
"failed to switch muxed topic %s to %s",
69 argv[1], cmd.request.topic.c_str());
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
int main(int argc, char **argv)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)