Note: This tutorial assumes that you have completed the previous tutorials: Running a Camera as Nodelet, Camera Frames with multiple Cameras.
(!) 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 several Ensenso Nodelets

Description: This tutorial shows how to run several cameras as nodelets within the same nodelet manager.

Tutorial Level: BEGINNER

Next Tutorial: Textured Point Cloud

Introduction

If the cameras are run as nodelets in the same manager, they are run within one process, opening up additional functionality with the Ensenso SDK. For example, an RGB mono and a stereo camera can be opened in a joint process to create a colored point cloud, which is described in the next tutorial.

The following tutorial will show you briefly how you can start several nodelets together with one nodelet manager.

Launch file

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

   1 <!-- Open both an Ensenso stereo camera and a mono camera within the same
   2 nodelet manager. -->
   3 
   4 <launch>
   5   <arg name="serial_stereo" default=""
   6        doc="Serial of the stereo camera (default: first found stereo camera)" />
   7   <arg name="serial_mono" default=""
   8        doc="Serial of the mono mamera (default: first found mono camera)" />
   9   <arg name="settings_stereo" default=""
  10        doc="JSON file with stereo camera parameters" />
  11   <arg name="settings_mono" default=""
  12        doc="JSON file with mono camera parameters" />
  13   <arg name="stereo_ns" default="stereo"
  14        doc="Namespace of the stereo camera" />
  15   <arg name="mono_ns" default="mono"
  16        doc="Namespace of the mono camera" />
  17   <arg name="camera_frame" default=""
  18        doc="The stereo camera's tf frame (default: optical_frame_SERIAL_STEREO)" />
  19   <arg name="link_frame" default=""
  20        doc="The stereo camera's link tf frame (default: camera_frame)" />
  21   <arg name="target_frame" default=""
  22        doc="The tf frame the data will be returned in (default: camera_frame)" />
  23   <arg name="tcp_port" default="-1"
  24        doc="The TCP port to open on the NxLib (-1=off, 0=autoSelect, >0=portNumber)" />
  25   <arg name="threads" default="-1"
  26        doc="The number of threads used by the NxLib for this node (-1=autoDetect)" />
  27   <arg name="wait_for_camera" default="false"
  28        doc="Whether this node should wait for the camera to become available" />
  29 
  30   <node pkg="nodelet" type="nodelet" name="manager_" args="manager" output="screen" />
  31 
  32   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg serial_stereo)"
  33         ns="$(arg stereo_ns)"
  34         args="load ensenso_camera/stereo_camera_nodelet /manager_" output="screen">
  35     <param name="serial" type="string" value="$(arg serial_stereo)" />
  36     <param name="settings" type="string" value="$(arg settings_stereo)" />
  37     <param name="camera_frame" type="string" value="$(arg camera_frame)" />
  38     <param name="link_frame" type="string" value="$(arg link_frame)" />
  39     <param name="target_frame" type="string" value="$(arg target_frame)" />
  40     <param name="tcp_port" type="int" value="$(arg tcp_port)" />
  41     <param name="threads" type="int" value="$(arg threads)" />
  42     <param name="wait_for_camera" type="bool" value="$(arg wait_for_camera)" />
  43   </node>
  44 
  45   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg serial_mono)"
  46         ns="$(arg mono_ns)"
  47         args="load ensenso_camera/mono_camera_nodelet /manager_" output="screen">
  48     <param name="serial" type="string" value="$(arg serial_mono)" />
  49     <param name="settings" type="string" value="$(arg settings_mono)" />
  50     <param name="link_frame" type="string" value="$(arg link_frame)" />
  51     <param name="wait_for_camera" type="bool" value="$(arg wait_for_camera)" />
  52   </node>
  53 </launch>

As in the previous tutorial on Nodelets, the launch file accepts all the arguments that the ensenso_camera_node accepts and has default values for each argument.

The crucial arguments are the namespaces of the cameras. Because the topics and actions are defined with a default NodeHandle, the topics would overwrite themselves in the global namespace /. Therefore each nodelet has to be given its own namespace in the following lines:

  13   <arg name="stereo_ns" default="stereo"
  14        doc="Namespace of the stereo camera" />
  15   <arg name="mono_ns" default="mono"
  16        doc="Namespace of the mono camera" />

In the next lines the nodelet manager with the name manager_ is defined. Its name has to be used in the load argument of all nodelets you want to have handled by this nodelet manager.

  30   <node pkg="nodelet" type="nodelet" name="manager_" args="manager" output="screen" />

The next block starts the nodelet for the stereo camera (ensenso_camera/nodelet). Note the nodelet manager name in the load argument. The last lines of the block map the parameters to the ones of the node, defined in ensenso_camera_node.

  32   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg serial_stereo)"
  33         ns="$(arg stereo_ns)"
  34         args="load ensenso_camera/stereo_camera_nodelet /manager_" output="screen">
  35     <param name="serial" type="string" value="$(arg serial_stereo)" />
  36     <param name="settings" type="string" value="$(arg settings_stereo)" />
  37     <param name="camera_frame" type="string" value="$(arg camera_frame)" />
  38     <param name="link_frame" type="string" value="$(arg link_frame)" />
  39     <param name="target_frame" type="string" value="$(arg target_frame)" />
  40     <param name="tcp_port" type="int" value="$(arg tcp_port)" />
  41     <param name="threads" type="int" value="$(arg threads)" />
  42     <param name="wait_for_camera" type="bool" value="$(arg wait_for_camera)" />
  43   </node>

The last lines start the nodelet for mono camera (ensenso_camera/nodelet_mono). Again, note the nodelet manager name in the load argument. The last lines of the block map the parameters to the ones of the node, defined in ensenso_camera_mono_node.

  45   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg serial_mono)"
  46         ns="$(arg mono_ns)"
  47         args="load ensenso_camera/mono_camera_nodelet /manager_" output="screen">
  48     <param name="serial" type="string" value="$(arg serial_mono)" />
  49     <param name="settings" type="string" value="$(arg settings_mono)" />
  50     <param name="link_frame" type="string" value="$(arg link_frame)" />
  51     <param name="wait_for_camera" type="bool" value="$(arg wait_for_camera)" />
  52   </node>

In order to run the launch file, which does already exists in the ensenso_camera package, run the following command in a terminal and fill in your camera serials:

roslaunch ensenso_camera \
    mono_stereo_nodelets.launch \
    serial_stereo:=<serial of Ensenso stereo camera> \
    serial_mono:=<serial of mono camera>

Wiki: ensenso_driver/Tutorials/SeveralNodelets (last edited 2022-04-06 13:52:18 by BenjaminThiemann)