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 <outopic> <intopic1> [intopic2...] [standard ROS arguments]

  • Subscribe to <intopic1>...N and publish currently selected topic to outopic. mux will start with <intopic1> 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 <topic>

  • Select output from <topic>.

mux_add MUX_NAME <topic>

  • Add new input <topic>.

mux_delete MUX_NAME <topic>

  • Delete input <topic>.

switch_mux <outtopic> <intopic> 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

mux

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.

Subscribed Topics

<intopicN> (any/any)
  • The Nth input topic that mux is subscribed to (specified on the command-line, or added via the mux/add service)

Published Topics

<outtopic> (any/any)
  • Messages from the selected input go here (specified on command-line)
mux/selected (new in ROS 0.11) (std_msgs/String)
  • Which topic is currently selected, or __none

Services

mux/select (new in ROS 0.11) (topic_tools/MuxSelect)
  • Select an input topic to output, or __none to turn off output
mux/add (new in 0.11) (topic_tools/MuxAdd)
  • Add a new input topic
mux/delete (new in ROS 0.11) (topic_tools/MuxDelete)
  • Delete an input topic
<outtopic>_select (DEPRECATED since ROS 0.11) (topic_tools/MuxSelect)
  • Select an input topic to output, or __none to turn off output

Parameters

~lazy (bool, default: False)
  • If True, don't subscribe to input topic unless there is at least one subscriber on the output topic. New in Electric
~initial_topic (str)
  • Input topic to select on startup. If __none, start with no input topic. If unset, default to first topic in arguments New in Lunar

Wiki: topic_tools/mux (last edited 2018-07-04 00:11:32 by IsaacSaito)