Note: This tutorial assumes that you have completed the previous tutorials: First Steps, Parameters, Workspace Calibration.
(!) 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.

Using the Ensenso URDF Files

Description: This tutorial introduces and shows how to use launch files, that generate the corresponding URDF files of the Ensenso cameras.

Tutorial Level: BEGINNER

Introduction

With Xacros you can define flexible URDF models for your robot. We offer some Xacro macros, which build up the corresponding model of the camera. Usually you build up an URDF file to check for collisions with either the model itself or external models.

Our Xacro/URDF files provide the camera's visual model and use a bounding box around the camera as collision model. By default this bounding box encloses the camera, the lenses and - if the camera has one - the projector. You can also increase the size of the bounding box in case you have e.g. a mono camera attached to your stereo camera. This can be done via the collision_margin argument (see below).

Currently we supply several Xacro files that build up the URDF file when running the launch file. The following models are supported and can be found in the ensenso_description package:

  • C-Series
  • N3x
  • N4x
  • S-Series
  • X-Series(xFA and normal)
  • XR-Series(xFA and normal)
  • XQ-Series

In case you have an XR-Series, please use the X-Series model since they have the same dimensions. Both X- and XR-Series are distinguished between the two different baselines

  • 200 millimeters and
  • 400 millimeters.

Our Xacros need a reference frame in order to built up the the URDF model. The reference frame itself is the frame where the camera is fastened. Depending on the model this is:

  • N35: The back of the camera, in the middle of the 4 screws.
  • X-Series: The bottom of the camera, in the middle of the model. Usually this is used for camera mounts.

X-Series Example

In the following example launch file the camera has been previously workspace calibrated. If you don't know how to perform a workspace calibration, please refer to the corresponding workspace calibration tutorial.

   1 <!-- Open a workspace calibrated Ensenso X-Series stereo camera and load the
   2 corresponding 3D model of the camera via Xacro and publish a tf transform from
   3 the camera_frame to the xaxro's reference frame. -->
   4 
   5 <launch>
   6   <!-- Camera parameters. -->
   7   <arg name="serial" default=""
   8        doc="Serial of the stereo camera (default: first found camera)" />
   9   <arg name="settings" default=""
  10        doc="JSON file with camera parameters" />
  11   <arg name="camera_frame" default=""
  12        doc="The camera's tf frame (default: optical_frame_SERIAL)" />
  13   <arg name="link_frame" default=""
  14        doc="The camera's link tf frame (default: camera_frame)" />
  15   <arg name="target_frame" default="Workspace"
  16        doc="The tf frame the data will be returned in" />
  17   <arg name="tcp_port" default="-1"
  18        doc="The TCP port to open on the NxLib (-1=off, 0=autoSelect, >0=portNumber)" />
  19   <arg name="threads" default="-1"
  20        doc="The number of threads used by the NxLib for this node (-1=autoDetect)" />
  21   <arg name="wait_for_camera" default="false"
  22        doc="Whether this node should wait for the camera to become available" />
  23 
  24   <!-- Xacro parameters. -->
  25   <!-- From that attachment frame the Xacro builds the camera frames. -->
  26   <arg name="xacro_reference_frame" default="xacro_ref" />
  27   <!-- Margin for the the collision model of the camera. -->
  28   <arg name="collision_margin" default="0.04" />
  29   <!-- Camera type, combination of baseline and mono camera type. -->
  30   <arg name="type" doc="Can be X200, X200_xFA, X400, X400_xFA" default="X200" />
  31 
  32   <!-- A static transform from the optical_frame_<serial> (left lens) to the
  33   Xacro reference frame (camera mount). Switch between baselines (200mm or 400mm
  34   in the models). The first argument of (x-Value) differs between the different
  35   baselines -->
  36   <node pkg="tf2_ros" type="static_transform_publisher"
  37         name="camera_to_model_broadcaster"
  38         args="0.1 0.036 0.033 0.7071068 0 0 0.7071068
  39               optical_frame_$(arg serial) $(arg xacro_reference_frame)"
  40         if="$(eval type == 'X200' or type == 'X200_xFA')"/>
  41 
  42   <node pkg="tf2_ros" type="static_transform_publisher"
  43         name="camera_to_model_broadcaster"
  44         args="0.2 0.036 0.033 0.7071068 0 0 0.7071068
  45               optical_frame_$(arg serial) $(arg xacro_reference_frame)"
  46         if="$(eval type == 'X400' or type == 'X400_xFA')"/>
  47 
  48   <!-- Use the Xacro and surpass parameters. -->
  49   <param name="ensenso_description"
  50          command="xacro '$(find ensenso_description)/ensenso_$(arg type)_Series.xacro'
  51                   corresponding_frame_name:=$(arg xacro_reference_frame)
  52                   camera:=$(arg serial)
  53                   margin:=$(arg collision_margin) "/>
  54 
  55   <!-- Publish the transforms between the defined frames in the Xacro above. -->
  56   <node pkg="robot_state_publisher" type="robot_state_publisher"
  57         name="camera_state_publisher" >
  58     <remap from="robot_description" to="ensenso_description" />
  59   </node>
  60 
  61   <!-- Start the Ensenso camera as nodelet. -->
  62   <node pkg="nodelet" type="nodelet" name="manager_" args="manager" output="screen" />
  63 
  64   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg serial)"
  65         args="load ensenso_camera/stereo_camera_nodelet /manager_" output="screen">
  66     <param name="serial" type="string" value="$(arg serial)" />
  67     <param name="settings" type="string" value="$(arg settings)" />
  68     <param name="camera_frame" type="string" value="$(arg camera_frame)" />
  69     <param name="link_frame" type="string" value="$(arg link_frame)" />
  70     <param name="target_frame" type="string" value="$(arg target_frame)" />
  71     <param name="tcp_port" type="int" value="$(arg tcp_port)" />
  72     <param name="threads" type="int" value="$(arg threads)" />
  73     <param name="wait_for_camera" type="bool" value="$(arg wait_for_camera)" />
  74   </node>
  75 </launch>

The launch file accepts all the camera parameters that the ensenso_camera_node accepts and has default values for each parameter.

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

After these parameters, the Xacro parameters for the X-Series are defined:

  • xacro_reference_frame: This is needed for the Xacro in order to build its own joints and links.

  • collision_margin: The default margin creates a bounding box that encloses the camera, the lenses and the projector. Increase the margin in order to enlarge the bounding box.

  • type: The combination of baseline and mono camera type.

  24   <!-- Xacro parameters. -->
  25   <!-- From that attachment frame the Xacro builds the camera frames. -->
  26   <arg name="xacro_reference_frame" default="xacro_ref" />
  27   <!-- Margin for the the collision model of the camera. -->
  28   <arg name="collision_margin" default="0.04" />
  29   <!-- Camera type, combination of baseline and mono camera type. -->
  30   <arg name="type" doc="Can be X200, X200_xFA, X400, X400_xFA" default="X200" />

The next thing we need is a static transform publisher that defines where the camera mount frame (xacro_reference_frame) is. Therefore we use the camera's optical frame, which the camera publishes as camera_frame and define the mounting frame relative to the optical frame. Depending on the baseline of the model, different x values for the transform have to be used, hence the conditionals in line 40 and 46.

  32   <!-- A static transform from the optical_frame_<serial> (left lens) to the
  33   Xacro reference frame (camera mount). Switch between baselines (200mm or 400mm
  34   in the models). The first argument of (x-Value) differs between the different
  35   baselines -->
  36   <node pkg="tf2_ros" type="static_transform_publisher"
  37         name="camera_to_model_broadcaster"
  38         args="0.1 0.036 0.033 0.7071068 0 0 0.7071068
  39               optical_frame_$(arg serial) $(arg xacro_reference_frame)"
  40         if="$(eval type == 'X200' or type == 'X200_xFA')"/>
  41 
  42   <node pkg="tf2_ros" type="static_transform_publisher"
  43         name="camera_to_model_broadcaster"
  44         args="0.2 0.036 0.033 0.7071068 0 0 0.7071068
  45               optical_frame_$(arg serial) $(arg xacro_reference_frame)"
  46         if="$(eval type == 'X400' or type == 'X400_xFA')"/>

In the next lines we load the ensenso description onto the parameter server with the command argument. Also, we hand the parameters given above to the Xacro macros. The macros will then build up our URDF files.

  48   <!-- Use the Xacro and surpass parameters. -->
  49   <param name="ensenso_description"
  50          command="xacro '$(find ensenso_description)/ensenso_$(arg type)_Series.xacro'
  51                   corresponding_frame_name:=$(arg xacro_reference_frame)
  52                   camera:=$(arg serial)
  53                   margin:=$(arg collision_margin) "/>

In order to get the joints of the generated URDF published, we need a robot state publisher. It will publish the joints and links defined in the Xacros, as tf transforms and frames.

  55   <!-- Publish the transforms between the defined frames in the Xacro above. -->
  56   <node pkg="robot_state_publisher" type="robot_state_publisher"
  57         name="camera_state_publisher" >
  58     <remap from="robot_description" to="ensenso_description" />
  59   </node>

In the last lines of the launch file, we start the ensenso camera as nodelet. It will publish its camera_frame, which is needed by the generated URDF.

  61   <!-- Start the Ensenso camera as nodelet. -->
  62   <node pkg="nodelet" type="nodelet" name="manager_" args="manager" output="screen" />
  63 
  64   <node pkg="nodelet" type="nodelet" name="Ensenso_$(arg serial)"
  65         args="load ensenso_camera/stereo_camera_nodelet /manager_" output="screen">
  66     <param name="serial" type="string" value="$(arg serial)" />
  67     <param name="settings" type="string" value="$(arg settings)" />
  68     <param name="camera_frame" type="string" value="$(arg camera_frame)" />
  69     <param name="link_frame" type="string" value="$(arg link_frame)" />
  70     <param name="target_frame" type="string" value="$(arg target_frame)" />
  71     <param name="tcp_port" type="int" value="$(arg tcp_port)" />
  72     <param name="threads" type="int" value="$(arg threads)" />
  73     <param name="wait_for_camera" type="bool" value="$(arg wait_for_camera)" />
  74   </node>

Running X-Series Xacro

If your camera is workspace calibrated, you can run the following command with your camera serial replaced for an X-Series camera:

roslaunch ensenso_camera \
    ensenso_X_with_xacro.launch \
    type:=X200_xFA \
    serial:=<serial of Ensenso stereo camera>

In order to see other currently supported models, you can exchange type with:

  • X200
  • X400
  • X400_xFA

If you used the X200_xFA model, you should see something similar below in Rviz.

Screenshot of RViz showing the X200_xFA Model URDF

Running N-Series Xacro

Because the N-Series differs in the reference frame of the Xacros, there is a separate example launch file. For N-Series you can run the following command with your camera serial replaced:

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

Wiki: ensenso_driver/Tutorials/EnsensoUrdf (last edited 2023-12-08 12:54:02 by BenjaminThiemann)