== mux == <> `mux` is a ROS node that subscribes to a set of incoming topics and republishes incoming data from one of them to another topic, i.e., it's a multiplexer that switches an output among 1 of N inputs. Services are offered to switch among input topics, and to add and delete input topics. At startup, the first input topic on the command line is selected. `mux` is part of the [[topic_tools]] package. === mux Usage === `mux [intopic2...] [standard ROS arguments]` Subscribe to `...N` and publish currently selected topic to `outopic`. `mux` will start with `` selected. * `outtopic`: Outgoing topic to publish on * `intopicN`: Incoming topic to subscribe to e.g. mux two command streams (`auto_cmdvel` and `joystick_cmdvel`) into one (`sel_cmdvel`): {{{ rosrun topic_tools mux sel_cmdvel auto_cmdvel joystick_cmdvel mux:=mux_cmdvel }}} '''IMPORTANT''': To avoid conflicting with other instances of `mux`, you should always remap the `mux`'s node name to something descriptive, using the `mux:=foo` syntax on the command line. <> === Associated mux tools (mux_select, mux_add, mux_delete) === For convenience, `topic_tools` provides some command-line tools for interacting with a `mux`. Assuming that the `mux` is called `MUX_NAME` (via remapping `mux:=MUX_NAME` on startup), you can use: `mux_select MUX_NAME ` Select output from ``. `mux_add MUX_NAME ` Add new input ``. `mux_delete MUX_NAME ` Delete input ``. `switch_mux ` '''DEPRECATED since ROS 0.11''' Use `mux_select` instead. ==== Examples ==== Setting up the `sel_cmdvel` topic to switch between `auto_cmdvel` and `joystick_cmdvel`: {{{ rosrun topic_tools mux sel_cmdvel auto_cmdvel joystick_cmdvel mux:=mux_cmdvel & }}} Then using `mux_select` to select `joystick_cmdvel`: {{{ rosrun topic_tools mux_select mux_cmdvel joystick_cmdvel }}} You can instead use [[rosservice]]: {{{ rosservice call mux_cmdvel/select joystick_cmdvel }}} == ROS API == {{{ #!clearsilver CS/NodeAPI node.0 { name=mux desc=`mux` is a node that can subscribe to a set of incoming topics and republish incoming data from one of them to another topic, i.e., it's a multiplexer that switches an output among 1 of N inputs. Services are offered to switch among input topics, and to add and delete input topics. At startup, the first input topic on the command line is selected. sub{ 0.name= 0.type=any/any 0.desc=The Nth input topic that mux is subscribed to (specified on the command-line, or added via the `mux/add` service) } pub{ 0.name= 0.type=any/any 0.desc=Messages from the selected input go here (specified on command-line) 1.name=mux/selected (new in ROS 0.11) 1.type=std_msgs/String 1.desc=Which topic is currently selected, or `__none` } srv{ 0.name=mux/select (new in ROS 0.11) 0.type=topic_tools/MuxSelect 0.desc=Select an input topic to output, or `__none` to turn off output 1.name=mux/add (new in 0.11) 1.type=topic_tools/MuxAdd 1.desc=Add a new input topic 2.name=mux/delete (new in ROS 0.11) 2.type=topic_tools/MuxDelete 2.desc=Delete an input topic 3.name=_select (DEPRECATED since ROS 0.11) 3.type=topic_tools/MuxSelect 3.desc=Select an input topic to output, or `__none` to turn off output } param { 1.name= ~lazy 1.default=False 1.type= bool 1.desc= If True, don't subscribe to input topic unless there is at least one subscriber on the output topic. <> 2.name = ~initial_topic 2.type= str 2.desc= Input topic to select on startup. If ```__none```, start with no input topic. If unset, default to first topic in arguments <> } }}}