Show EOL distros: 

common: actionlib | bfl | bond | bondcpp | bondpy | filters | nodelet | nodelet_topic_tools | pluginlib | smclib | tinyxml | xacro | yaml_cpp

Package Summary

This package contains common nodelet tools such as a mux and a demux nodelet.

Package Summary

This package contains common nodelet tools such as a mux and a demux nodelet.

nodelet_core: nodelet | nodelet_topic_tools

Package Summary

This package contains common nodelet tools such as a mux, demux and throttle.

nodelet_core: nodelet | nodelet_topic_tools

Package Summary

This package contains common nodelet tools such as a mux, demux and throttle.

nodelet_core: nodelet | nodelet_topic_tools

Package Summary

This package contains common nodelet tools such as a mux, demux and throttle.

nodelet_core: nodelet | nodelet_topic_tools

Package Summary

This package contains common nodelet tools such as a mux, demux and throttle.

nodelet_core: nodelet | nodelet_topic_tools

Package Summary

This package contains common nodelet tools such as a mux, demux and throttle.

nodelet_core: nodelet | nodelet_topic_tools

Package Summary

This package contains common nodelet tools such as a mux, demux and throttle.

nodelet_core: nodelet | nodelet_topic_tools

Package Summary

This package contains common nodelet tools such as a mux, demux and throttle.

nodelet_core: nodelet | nodelet_topic_tools

Package Summary

This package contains common nodelet tools such as a mux, demux and throttle.

nodelet_core: nodelet | nodelet_topic_tools

Package Summary

This package contains common nodelet tools such as a mux, demux and throttle.

Contents

  1. MUX
  2. DEMUX
  3. Throttle

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:

   1   <node pkg="nodelet" type="nodelet" name="pcl_manager" args="manager" output="screen" />
   2   <!-- MUX the data onto one topic -->
   3   <node pkg="nodelet" type="nodelet" name="data_mux" args="load pcl/NodeletMUX pcl_manager" output="screen">
   4     <rosparam>
   5       input_topics: [/passthrough/output, /normal_estimation/output]
   6     </rosparam>
   7   </node>

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:

   1 typedef nodelet::NodeletMUX<sensor_msgs::PointCloud2, message_filters::Subscriber<sensor_msgs::PointCloud2> > NodeletMUX;
   2 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:

   1   <node pkg="nodelet" type="nodelet" name="pcl_manager" args="manager" output="screen" />
   2   <!-- MUX the data onto one topic -->
   3   <node pkg="nodelet" type="nodelet" name="data_demux" args="load pcl/NodeletDEMUX pcl_manager" output="screen">
   4     <rosparam>
   5       output_topics: [/output1, /output2]
   6     </rosparam>
   7   </node>

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:

   1 typedef nodelet::NodeletDEMUX<sensor_msgs::PointCloud2> NodeletDEMUX;
   2 PLUGINLIB_DECLARE_CLASS (pcl, NodeletDEMUX, NodeletDEMUX, nodelet::Nodelet);

(replace sensor_msgs::PointCloud2 with the message type of choice).

Throttle

New in Fuerte

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:

   1   <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager" output="screen" />
   2 
   3   <node pkg="nodelet" type="nodelet" name="data_throttle" args="load my_pkg/NodeletThrottleImage nodelet_manager" output="screen">
   4     <remap from="topic_in"  to="camera/rgb/image_color"/>
   5     <remap from="topic_out" to="camera/rgb/image_color_throttle"/>
   6   </node>

To compile the NodeletThrottle nodelet in your library, add something like:

   1 #include <nodelet_topic_tools/nodelet_throttle.h>
   2 #include <sensor_msgs/Image.h>
   3 #include <pluginlib/class_list_macros.h>
   4 
   5 typedef nodelet_topic_tools::NodeletThrottle<sensor_msgs::Image> NodeletThrottleImage;
   6 PLUGINLIB_DECLARE_CLASS (my_pkg, NodeletThrottleImage, NodeletThrottleImage, nodelet::Nodelet);

(replace sensor_msgs::Image with the message type of choice).

Wiki: nodelet_topic_tools (last edited 2021-08-08 12:02:21 by Combinacijus)