!

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

Using Nodelets

Running a node as nodelet has several advantages. The biggest one being the messages not being serialized. Also, running nodelets within the same nodelet manager will make it possible to run several Ensenso stereo cameras within the same NxLib instance. That for example makes it possible to generate coloured point clouds, which is described in another tutorial in the end of this tutorial series.

Running the ensenso_camera_node or the ensenso_camera_mono_node as nodelets is farley easy. The ensenso_camera package therefore provides two kind of nodelets. One, named nodelet_mono for opening mono cameras and the other one, named nodelet, for opening the stereo cameras respectively.

In general you start the nodelets in the same fashion as the corresponding nodes. The only thing that differs, is that you run them within a launch file with a nodelet manager attached to them.

Simple Example

In the following example a stereo camera with serial "150580" is openened as nodelet. The following launch file shows how to run that stereo camera with a nodelet manager:

   1 <launch>
   2   <arg name="camera" value="150580" />
   3   <arg name="target_frame" value="Workspace" />
   4 
   5   <node pkg="nodelet" type="nodelet" name="manager_"  args="manager" output="screen" />
   6   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg camera)" args="load ensenso_camera/nodelet /manager_" output="screen">
   7     <param name="serial" type="string" value="$(arg camera)" />
   8     <param name="target_frame" type="string" value="$(arg target_frame)" />
   9   </node>
  10 </launch>

Step by step

The launch file is taking two arguments. The first, camera, is the camera's serial number 150580. Its value has to be changed to the camera you want to open. The second, target_frame, defines in which TF frame the resulting topics are going to be published.

   2   <arg name="camera" value="150580" />
   3   <arg name="target_frame" value="Workspace" />

The next line defines one nodelet manager. The crucial part is the manager's name, which has to be given to the nodelet as load argument. That way the nodelet is handled by this specific nodelet manager.

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

The last lines defines the nodelet itself 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 wanted to start a nodelet for supported mono cameras, you would have to use ensenso_camera/nodelet_mono instead of the ensenso_camera/nodelet class.

   6   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg camera)" args="load ensenso_camera/nodelet /manager_" output="screen">
   7     <param name="serial" type="string" value="$(arg camera)" />
   8     <param name="target_frame" type="string" value="$(arg target_frame)" />
   9   </node>

Running the nodelet

The above launch file is also defined in the ensenso_camera package and can be launched via:

$ roslaunch ensenso_camera nodelet.launch

Wiki: ensenso_driver/Tutorials/MultiCamera (last edited 2019-11-12 09:13:55 by YasinGuenduez)