## repository: https://code.ros.org/svn/ros-pkg <> <> The `nodelet_topic_tools` package contains a MUX (`NodeletMUX`) and a DEMUX (`NodeletDEMUX`) nodelet. == MUX == `NodeletMUX` represent a mux nodelet for topics: it takes N (<=8) input topics, and publishes all of them on one output topic. One implementation of `NodeletMUX` can be found in [[pcl_ros]]. Usage example: {{{#!xml block=launch input_topics: [/passthrough/output, /normal_estimation/output] }}} The above accepts data from `/passthrough/output` and `/normal_estimation/output`, and republishes it on `/data_mux/output`. To compile the `NodeletMUX` nodelet in your library, add something like: {{{#!cplusplus typedef nodelet::NodeletMUX > NodeletMUX; PLUGINLIB_DECLARE_CLASS (pcl, NodeletMUX, NodeletMUX, nodelet::Nodelet); }}} (replace `sensor_msgs::PointCloud2` with the message type of choice). == DEMUX == `NodeletDEMUX` represent a demux nodelet for topics: it takes 1 input topic, and publishes on N (<=8) output topics. One implementation of `NodeletDEMUX` can be found in [[pcl_ros]]. Usage example: {{{#!xml block=launch output_topics: [/output1, /output2] }}} The above accepts data from `/data_demux/input`, and republishes it on `/data_demux/output1` and `/data_demux/output2`. To compile the `NodeletDEMUX` nodelet in your library, add something like: {{{#!cplusplus typedef nodelet::NodeletDEMUX NodeletDEMUX; PLUGINLIB_DECLARE_CLASS (pcl, NodeletDEMUX, NodeletDEMUX, nodelet::Nodelet); }}} (replace `sensor_msgs::PointCloud2` with the message type of choice). == Throttle == <> `NodeletThrottle` can throttle a topic in a nodelet to a specified rate. Note that this tool is in the `nodelet_topic_tools` namespace. Usage example: {{{#!xml block=launch }}} To compile the `NodeletThrottle` nodelet in your library, add something like: {{{#!cplusplus #include #include #include typedef nodelet_topic_tools::NodeletThrottle NodeletThrottleImage; PLUGINLIB_DECLARE_CLASS (my_pkg, NodeletThrottleImage, NodeletThrottleImage, nodelet::Nodelet); }}} (replace `sensor_msgs::Image` with the message type of choice). ## AUTOGENERATED DON'T DELETE ## CategoryPackage