common: actionlib | bfl | filters | nodelet | nodelet_topic_tools | nodelet_tutorial_math | pluginlib | tinyxml | xacro | yaml_cpp
Package Summary
The nodelet package is designed to provide a way to run multiple algorithms in the same process with zero copy transport between algorithms. This package provides both the nodelet base class needed for implementing a nodelet, as well as the NodeletLoader class used for instantiating nodelets.
- Author: Tully Foote, Radu Bogdan Rusu
- License: BSD
- Repository: ros-pkg (https://code.ros.org/svn/ros-pkg)
Contents
New in C Turtle
High Level
Provide a way to run multiple algorithms on a single machine, in a single process, without incurring copy costs. roscpp has optimizations to do zero copy pointer passing between publish and subscribe calls within the same node. To do this nodelets allow dynamic loading of classes into the same node, however they provide simple seperate namespaces such that the nodelet acts like a seperate node, despite being in the same process. This has been extended further in that it is dynamically loadable at runtime using pluginlib.
Applications
- high throughput data flows can be composed of many nodelets and then loaded into the same process to avoid copying and network traffic.
Specific Goals
- use the existing C++ ROS interfaces.
- allow zero copy passing of data between nodelets
- dynamically load as plugins to break build time dependencies
- location transparent except for performance improvements
- writing code in a node or a nodelet will be minimally different.
Technique
- Define a base class nodelet::Nodelet which will be used for dynamic loading. All nodelets will inherit from this base class, and be dynamically loadable using pluginlib.
- It will provide the namespace, remapping arguments and parameters automatically, like they were a first class node.
- There will be a nodelet_manager process into which one or more nodelets can be loaded. Any communications between them can use the zero copy roscpp publish call with a boost shared pointer.
Basic Usage
- Launch a nodelet manager such as the following:
rosrun nodelet nodelet manager __name:=nodelet_manager
The loader is just a class and can be embedded into any any roscpp node. It provides service calls to load and unload nodelets.
- Load a nodelet using the loader script
rosrun nodelet nodelet TYPE nodelet_manager __name:=nodelet1
This script will pass through all topic remappings and parameters into the namespace of the nodelet.
Loader script usage:
Usage: nodelet command [args] Commands: load pkg/NodeletType manager - loads a nodelet of type pkg/NodeletType on a remote manager unload manager - unload a nodelet from a remote manager manager - Load a nodelet manager standalone pkg/NodeletType - Run the nodelet in a local manager w/o the abilty to add another nodelet, useful for debugging
Example launch file
<launch>
<node pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager"/>
<node pkg="nodelet" type="nodelet" name="Plus"
args="load nodelet_tutorial_math/Plus standalone_nodelet">
<remap from="/Plus/out" to="remapped_output"/>
</node>
<rosparam param="Plus2" file="$(find nodelet_tutorial_math)/plus_default.yaml"/>
<node pkg="nodelet" type="nodelet" name="Plus2" args="load nodelet_tutorial_math/Plus standalone_nodelet">
<rosparam file="$(find nodelet_tutorial_math)/plus_default.yaml"/>
</node>
<node pkg="nodelet" type="nodelet" name="Plus3" args="standalone nodelet_tutorial_math/Plus">
<param name="value" type="double" value="2.5"/>
<remap from="Plus3/in" to="Plus2/out"/>
</node>
</launch>
API
Nodelet Base Class:
Public methods:
1 Nodelet() //Default constructor used when dynamically loaded
2 void init (const std::string& name, const ros::M_string& remapping_args, const std::vector<std::string>& my_argv); // This method is how a nodelet should be started. The arguments are what is required from the manager to start the nodelet. This will initialize the nodelet base class and then call the subclass's onInit() method.
Protected members and methods for use in subclass:
1 std::string getName() //Get the name of the nodelet
2 ros::NodeHandle& getNodeHandle () // Get the node handle (provides this nodelets custom remappings and name)
3 ros::NodeHandle& getPrivateNodeHandle () // Get the private node handle (provides this nodelets custom remappings in it's private namespace)
4 ros::NodeHandle& getMTNodeHandle () // Get the node handle with the Multi Threaded callback queue. (provides this nodelets custom remappings and name)
5 ros::NodeHandle& getMTPrivateNodeHandle () // Get the private node handle with the Multi Threaded callback queue. (provides this nodelets custom remappings in it's private namespace)
6 ros::CallbackQueue& getMTCallbackQueue () // Get the callback queue (threadpool available from the manager)
7 std::vector<std::string> getMyArgv() // Get command line arguments to the nodelet stripped of ROS and nodelet specific args.
Initialization method used to start ROS API in subclass:
1 virtual void onInit () = 0 //Virtual and must be overridden by subclass. All initialization of the ROS infrastructure must be put into this function.
NODELET ROSCONSOLE MACROS
These macros will only compile inside nodelet methods.
These are wrappers on rosconsole macros. They include verbosity levels DEBUG, INFO, WARN, ERROR, and FATAL.
1 #include "nodelet/nodelet.h"
2
3 //... inside a nodelet method
4 NODELET_DEBUG("My debug statement")
5 NODELET_DEBUG_STREAM("my debug statement " << (double) 1.0)
6 NODELET_DEBUG_COND( 1 == 1, "my debug_statement")
7 NODELET_DEBUG_STREAM_COND( 1 == 1, "my debug statement " << (double) 1.0)






