Note: This tutorial assumes that you have completed the previous tutorials: pluginlib/Tutorials/Writing and Using a Simple Plugin.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Running a nodelet

Description: This will show you how to run a nodelet already in the system.

Tutorial Level: BEGINNER

Next Tutorial: nodelet/Tutorials/Porting nodes to nodelets

Setup

We will assume that nodelet_tutorial_math has been installed (ros-$ROS_DISTRO-nodelet-tutorial-math) and a roscore is running.

roscore

Bring up a manager

A nodelet will be run inside a NodeletManager. A nodelet manager is a c++ program which is setup to listen to ROS services and will be the executable in which the nodelet is dynamically loaded. In this case we will run a standalone manager, but in many cases these managers will be embedded within running nodes.

rosrun nodelet nodelet manager __name:=nodelet_manager

We have renamed this node to nodelet_manager for clarity.

Launching the nodelet

Nodelets are launched remotely by using the nodelet executable as well.

What this code does: The nodelet executable, called here, will contact the nodelet_manager and ask it to instantiate an instance of the nodelet_tutorial_math/Plus nodelet. It will pass through the name, nodelet1, and also any remappings if applied to the code inside the nodelet. And parameters appear in the right namespace too.

rosrun nodelet nodelet load nodelet_tutorial_math/Plus nodelet_manager __name:=nodelet1 nodelet1/in:=foo _value:=1.1

If you do a rostopic list you will see:

/foo
/nodelet1/out

If you look at the output of rosnode list you will see:

/nodelet1
/nodelet_manager

Testing Operation

In separate terminals run:

rostopic pub /foo std_msgs/Float64 5.0 -r 10

rostopic echo /nodelet1/out

Will show: 6.1 which is 5.0 + 1.1 .

Using within roslaunch files

Here is an example launch file (available in nodelet_tutorial_math pkg) with multiple nodelets running on the same standalone manager:

<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>

Wiki: nodelet/Tutorials/Running a nodelet (last edited 2017-05-11 22:32:25 by DirkThomas)