Note: This tutorial assumes that you have completed the previous tutorials: First Steps.
(!) 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 Camera as a Nodelet

Description: This tutorial explains you how to run a camera as a nodelet with a nodelet manager.

Tutorial Level: BEGINNER

Next Tutorial: Camera Frames with multiple Cameras

Introduction

Running a node as nodelet has several advantages. The biggest one being that messages no further have to be serialized but can be passed intraprocess with zero copy costs.

Using Nodelets

With regard to this package, running the nodes as nodelets allows us to run several Ensenso stereo cameras and/or mono cameras within the same NxLib instance. That for example makes it possible to generate textured point clouds, which is described in the TexturedPointCloud tutorial.

This package provides a nodelet implementation for both the ensenso_camera_mono_node and the ensenso_camera_node.

Launch File

In order to run a stereo camera node as a nodelet you can use the nodelet.launch file provided by this package. The following code shows the provided launch file.

   1 <!-- Open an Ensenso stereo camera in a nodelet. -->
   2 
   3 <launch>
   4   <arg name="serial" default=""
   5        doc="Serial of the stereo camera (default: first found camera)" />
   6   <arg name="settings" default=""
   7        doc="JSON file with camera parameters" />
   8   <arg name="camera_frame" default=""
   9        doc="The camera's tf frame (default: optical_frame_SERIAL)" />
  10   <arg name="link_frame" default=""
  11        doc="The camera's link tf frame (default: camera_frame)" />
  12   <arg name="target_frame" default=""
  13        doc="The tf frame the data will be returned in (default: camera_frame)" />
  14   <arg name="tcp_port" default="-1"
  15        doc="The TCP port to open on the NxLib (-1=off, 0=autoSelect, >0=portNumber)" />
  16   <arg name="threads" default="-1"
  17        doc="The number of threads used by the NxLib for this node (-1=autoDetect)" />
  18   <arg name="wait_for_camera" default="false"
  19        doc="Whether this node should wait for the camera to become available" />
  20 
  21   <node pkg="nodelet" type="nodelet" name="manager_" args="manager" output="screen" />
  22 
  23   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg serial)"
  24         args="load ensenso_camera/stereo_camera_nodelet /manager_" output="screen">
  25     <param name="serial" type="string" value="$(arg serial)" />
  26     <param name="settings" type="string" value="$(arg settings)" />
  27     <param name="camera_frame" type="string" value="$(arg camera_frame)" />
  28     <param name="link_frame" type="string" value="$(arg link_frame)" />
  29     <param name="target_frame" type="string" value="$(arg target_frame)" />
  30     <param name="tcp_port" type="int" value="$(arg tcp_port)" />
  31     <param name="threads" type="int" value="$(arg threads)" />
  32     <param name="wait_for_camera" type="bool" value="$(arg wait_for_camera)" />
  33   </node>
  34 </launch>

The launch file accepts all the arguments that the ensenso_camera_node accepts and has default values for each argument.

   4   <arg name="serial" default=""
   5        doc="Serial of the stereo camera (default: first found camera)" />
   6   <arg name="settings" default=""
   7        doc="JSON file with camera parameters" />
   8   <arg name="camera_frame" default=""
   9        doc="The camera's tf frame (default: optical_frame_SERIAL)" />
  10   <arg name="link_frame" default=""
  11        doc="The camera's link tf frame (default: camera_frame)" />
  12   <arg name="target_frame" default=""
  13        doc="The tf frame the data will be returned in (default: camera_frame)" />
  14   <arg name="tcp_port" default="-1"
  15        doc="The TCP port to open on the NxLib (-1=off, 0=autoSelect, >0=portNumber)" />
  16   <arg name="threads" default="-1"
  17        doc="The number of threads used by the NxLib for this node (-1=autoDetect)" />
  18   <arg name="wait_for_camera" default="false"
  19        doc="Whether this node should wait for the camera to become available" />

In order to get an overwiew of the requried and optional arguments you can always run:

roslaunch ensenso_camera nodelet.launch --ros-args

The output, however, is slightly wrong since all arguments are provided with a default value so that you can simply run the launch file without providing any arguments as shown at the end of this tutorial.

A nodelet is started in the same fashion as its corresponding node, however, with the slight difference that it requires a nodelet manager to be run in. This is why a nodelet is always run from within a launch file, in which a nodelet manager is started and then given to the nodelet. The crucial part is the manager's name, which has to be given to the nodelet via the load argument. That way the nodelet is handled by this specific nodelet manager.

  21   <node pkg="nodelet" type="nodelet" name="manager_" args="manager" output="screen" />
  22 
  23   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg serial)"
  24         args="load ensenso_camera/stereo_camera_nodelet /manager_" output="screen">

The last lines define the nodelet with its parameters. The parameters are mapped to the ones of the node, defined in ensenso_camera_node. The load argument of nodelet needs the nodelet class and the nodelet manager's name. If you want to start a nodelet for a supported mono camera, you need to use ensenso_camera/nodelet_mono instead of the ensenso_camera/nodelet class as it is also shown in the SeveralNodelets tutorial.

  23   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg serial)"
  24         args="load ensenso_camera/stereo_camera_nodelet /manager_" output="screen">
  25     <param name="serial" type="string" value="$(arg serial)" />
  26     <param name="settings" type="string" value="$(arg settings)" />
  27     <param name="camera_frame" type="string" value="$(arg camera_frame)" />
  28     <param name="link_frame" type="string" value="$(arg link_frame)" />
  29     <param name="target_frame" type="string" value="$(arg target_frame)" />
  30     <param name="tcp_port" type="int" value="$(arg tcp_port)" />
  31     <param name="threads" type="int" value="$(arg threads)" />
  32     <param name="wait_for_camera" type="bool" value="$(arg wait_for_camera)" />
  33   </node>

Since the launch is provided by this package and we do not need to specify any required arguments, we can simply call

roslaunch ensenso_camera nodelet.launch

without any arguments given. In this case, the wrapped ensenso_camera_node will select and open the first stereo camera it can find.

If you want to open a stereo camera with a specific serial you can run the following command with your camera serial replaced:

roslaunch ensenso_camera \
    nodelet.launch \
    serial:=<serial of Ensenso stereo camera>

This way you can provide any of the other listed arguments in order to change the node's behavior as described in the ensenso_camera_node documentation.

Wiki: ensenso_driver/Tutorials/Nodelet (last edited 2022-04-06 13:50:38 by BenjaminThiemann)