ROS-based OMRON SENTECH Camera SDK

1. Overview

This omronsentech_camera package is provided by OMRON SENTECH, CO.,LTD. Any cameras supported by Linux-based SentechSDK are also supported by this package. This package provides generic access to the camera's GenICam GenApi nodes and functions through SentechSDK's transport layer module. Note that GenICam GenApi node is a different thing from the term node in ROS. Each GenICam GenApi node corresponds to the camera device's feature or register that can be accessed through a generic interface. The detail of the GenICam GenApi can be found in the GenICam GenApi documentation.

2. Installation

This package has been tested on ROS-Kinetic (Ubuntu 16.04 64bit) and ROS-Melodic (Ubuntu 18.04 64bit). Since this package basically wraps SentechSDK's transport layer module, SentechSDK must be installed prior to the installation of this package. The SentechSDK (USB3Vision and GigEVision) can be downloaded from the following URL: https://sentech.co.jp/products/USB/software.html.

Below are the list of ROS packages needed to build the package:

  1. camera_info_manager
  2. image_transport
  3. message_generation
  4. sensor_msgs
  5. std_msgs
  6. pluginlib
  7. nodelet
  8. roscpp
  9. roslaunch
  10. roslint
  11. rospy

For installation, either clone the omronsentech_camera.git or copy the content of this repository to your catkin workspace. Before building the package as a common ROS package using catkin_make, please ensure that the SentechSDK environment variable has been exported:

$ echo $STAPI_ROOT_PATH

In case that the environment variables has not been exported, if the SentechSDK installation folder is in /opt/sentech, you can export the environment variables used by SentechSDK by executing:

$ source /opt/sentech/.stprofile

The structure of the directory inside the omronsentech_camera is as follows:

/
|-./README.md
|-./README-ja.md
|-./CMakeLists.txt
|-./nodelet_plugins.xml
|-./package.xml
|-./rosdoc.yaml
|-./doc/
|      |-./html/
|      |-./manifest.yaml
|
|-./examples/
|      |-./cpp/grabber.cpp
|      |-./python/grabber.py
|
|-./include/
|      |-./omronsentech_camera/*.h
|                             
|-./launch/
|      |-./*.launch
|      |-./*.yaml
|
|-./msg/
|      |-./*.msg
|
|-./src/
|      |-./omronsentech_camera/*.cpp
|                             
|-./srv/
       |-./*.srv

To generate the documentation in the doc folder, execute the following command in the folder omronsentech_camera:

$ rosdoc_lite -o doc

Please note that doxygen and rosdoc_lite package are required to build the documentation.

3. Node stcamera_node

For easy usage, the stcamera_node provided in the package will automatically connect to either the first found camera, predefined camera, or any camera that it can find (depend on the camera_to_connect parameter) and continuously acquire images from the camera.

To run the stcamera_node, execute one of the following command:

or

If the node is run through stcamera_node.launch script, you can easily configure the parameters in stcamera_node.yaml to control which camera to connect. See the next section for the detail of parameter configuration.

3.1. Node Parameters

Parameters value are case sensitive. There are only three parameters to configure, as follows:

3.2. Camera Namespace

Once stcamera_node is connected to a camera, it will advertise topics and services correspond to the camera. To differentiate between the connected camera, each camera has its own namespace *{dev_CAMERA-NS}*. The namespace *{dev_CAMERA-NS}* is automatically generated by stcamera_node with the following rules:

The namespace *{dev_CAMERA-NS}* can also be retrieved from the value of device_namespace field returned by service call get_device_list or message from device_connection topic.

3.3. Published Topics

The topics published by the stcamera_node are as follows:

No. Topics Description
1 device_connection Published when connection or disconnection happened.
2 *{dev_CAMERA-NS}*/**camera_info** Based on the ROS image_transport.
3 *{dev_CAMERA-NS}*/**chunk** Published when chunk data is acquired.
4 *{dev_CAMERA-NS}*/**event** Published when camera event is registered and event data corresponds to the registered event is acquired.
5 *{dev_CAMERA-NS}*/**image_raw*** Published when image data is acquired, based on the ROS image_transport.

3.4. Services

The services advertised by the stcamera_node are as follows:

*(Please be aware that the GenICam node mentioned below is a completely different thing from the ROS node)*:

Attention:

3.5. Error codes

Codes Description
< 0 GenTL error codes. Please refer to GenICam GenTL documentation.
0 No error.
30000 GenICam GenericException occurred.
30001 Module name is invalid.
30002 (GenICam) Node is either invalid or inaccessible.
30003 Event already ON.
30004 Event already OFF.
30005 Image acquisition already ON.
30006 Image acquisition already OFF.
30007 Chunk is not supported.
30008 Chunk name is not valid.
30009 Trigger is not supported.
30010 Trigger name is not valid.
30011 Event is not supported.
30012 Event name is not valid.

4. Usage

4.1. Displaying acquired images with image_view and Changing Camera Gain:

For a simple viewing and operation, you can refer to the following steps:

4.2. Launch Script Examples and Termination

Examples of launch script and their parameters are included in the package. Please refer to the following procedure to use them:
  • stcamera_node.launch: This launch script will run stcamera_node. The node will attempt to connect to any detected cameras. You can directly launch this script without any modification or configure the calibration file (optional) in stcamera_node.yaml.
  • stcamera_nodelet_manager.launch: This launch script will run the nodelet version of stcamera_node. The node will attempt to connect to any detected cameras. You can directly launch this script without any modification or configure the calibration file (optional) in stcamera_nodelet_manager.yaml.
  • stcamera_node_imageproc.launch: This launch script will run two nodes: stcamera_node and image_view that displays streamed images from the connected camera. To launch this script, you have to modify the launch script and configuration file by specifying the CAMERA_ID or CAMERA_MODEL(SERIAL), the namespace dev_CAMERA-NS, and the calibration file (optional).
    • Change the argument camera_namespace in the launch file:
      <arg name="camera_namespace" default="dev_CAMERA-NS" />
    • Change the parameter of camera_to_connect in the yaml file:
      camera_to_connect: ["CAMERA_ID or CAMERA_MODEL(SERIAL)"]
    • Change the calibration path file either default_calibration_file or *{dev_CAMERA-NS}*/**calibration_file** (optional):
      default_calibration_file: file:///home/mydata/calibration.xml
To terminate the stcamera_node, use the following ROS command:
$ rosnode kill /stcamera_node

4.3. Node Client Examples

In the examples folder, node "grabber" is provided as a straightforward node client of stcamera_node. The grabber (provided in C++ and Python) does the following:
  1. Display the SentechSDK and GenTL information by calling get_sdk_info.
  2. Search for a connected camera and get the camera namespace by calling get_device_list.
  3. Read and write the camera's Gain by calling get_genicam_node_info and write_node_float respectively.
  4. Subscribe to image_raw topic and grab up to 10 images. The image sizes and encoding information are printed on screen.
  5. Set trigger mode to ON (trigger selector is set to FrameStart and the source is set to Software) by calling enable_trigger), then grab up to 10 images with interval 1 seconds in between by sending software trigger through send_soft_trigger.
If you are using GigEVision camera, please ensure that the camera has a valid IP address. The IP address can be checked by calling either get_device_list or get_gige_ip. A static IP address can be assigned by using set_gige_ip service call. For example: 
$ rosservice call /stcamera_node/get_gige_ip "00:11:1c:xx:xx:xx" to display the current IP address of GigEVision camera with MAC 00:11:1c:xx:xx:xx, and
$ rosservice call /stcamera_node/set_gige_ip "00:11:1c:xx:xx:xx" 192.168.y.z 255.255.255.0 0.0.0.0 to assign a static IP address to GigEVision camera with MAC 00:11:1c:xx:xx:xx.

5. Customization

The stcamera_node provides generic functionality to control the OMRON SENTECH camera. If customization is needed to accommodate a specific camera, you can extend StCameraInterface class and either create a new ROS node or modify the existing stcamera_node (StCameraNode class) to support the specific camera. If you prefer the latter, you will need to modify the initialization process of the camera interface in StCameraNode class which can be found in function initializeCamera(). Please refer to the doxygen documentation for the structure of the StCameraInterface and the StCameraNode classes.

6. API Documentation

You can also find the code API and Msg/Srv API documentation at the following URL: https://wiki.ros.org/omronsentech_camera.

7. Questions/Feedbacks and Bug Reports

If you have any questions/feedbacks or found any bugs, please contact support-ros AT sentech.co DOT jp.


omronsentech_camera
Author(s): OSE ROS Support
autogenerated on Tue Jul 2 2019 19:44:14