Wiki

  Show EOL distros: 

Package Summary

Driver node for Scarlet and SceneScan stereo vision sensors by Nerian Vision GmbH

  • Maintainer status: developed
  • Maintainer: Konstantin Schauwecker <konstantin.schauwecker AT nerian DOT com>
  • Author: Nerian Vision Technologies <service AT nerian DOT com>
  • License: MIT
  • Source: git https://github.com/nerian-vision/nerian_stereo.git (branch: master)

Package Summary

Driver node for SceneScan and SP1 stereo vision sensors by Nerian Vision GmbH

  • Maintainer status: developed
  • Maintainer: Konstantin Schauwecker <konstantin.schauwecker AT nerian DOT com>
  • Author: Nerian Vision Technologies <service AT nerian DOT com>
  • License: MIT
  • Source: git https://github.com/nerian-vision/nerian_stereo.git (branch: master)

Package Summary

Driver node for Scarlet and SceneScan stereo vision sensors by Nerian Vision GmbH

  • Maintainer status: developed
  • Maintainer: Konstantin Schauwecker <konstantin.schauwecker AT nerian DOT com>
  • Author: Nerian Vision Technologies <service AT nerian DOT com>
  • License: MIT
  • Source: git https://github.com/nerian-vision/nerian_stereo.git (branch: master)

Package Summary

Driver node for Scarlet and SceneScan stereo vision sensors by Nerian Vision GmbH

  • Maintainer status: developed
  • Maintainer: Konstantin Schauwecker <konstantin.schauwecker AT nerian DOT com>
  • Author: Nerian Vision Technologies <service AT nerian DOT com>
  • License: MIT
  • Source: git https://github.com/nerian-vision/nerian_stereo.git (branch: master)

Introduction

https://nerian.com/nerian-images/scarlet-ros-wiki.jpg

Nerian's Scarlet and SceneScan product lines are stereo vision based 3D imaging systems for real-time 3d sensing. While Scarlet is a fully integrated unit with image sensors and image processing in one device, SceneScan connects to two industrial USB cameras that provide input image data. Both devices correlate the images of both cameras / sensors and produce a disparity map, which is transmitted through gigabit Ethernet. The disparity map describes a mapping of image points from the left camera image to corresponding image points in the right camera image. With this information it is possible to reconstruct the 3D location of every observed scene points.


Please note: since version 3.0.0 this node is no longer compatible to SP1 – the predecessor of SceneScan. Please use an older version with SP1 or the now discontinued nerian_sp1 node


Installation on ROS1 and ROS2

On Ubuntu Linux, please use the following commands to install the official package for your current ROS version.

sudo apt-get update
sudo apt-get install ros-`rosversion -d`-nerian-stereo

These commands work for both, ROS1 and ROS2 distributions.

Should there not be an appropriate package for your system and ROS version, please checkout the git repository and compile the code using catkin/colcon.

ROS Node

The data delivered by Scarlet / SceneScan can be received using the available open source API. Using the API directly is recommended for high performance applications with ROS1. Alternatively the nerian_stereo ROS node can be used for publishing the received data as ROS messages. A Nodelet version is also provided for ROS1.

https://nerian.com/nerian-images/ros-rviz.png

Published Topics

The node can publish the received data through three different topics:

/nerian_stereo/point_cloud (sensor_msgs/PointCloud2)

/nerian_stereo/disparity_map (sensor_msgs/Image) /nerian_stereo/left_image (sensor_msgs/Image) /nerian_stereo/right_image (sensor_msgs/Image) /nerian_stereo/stereo_camera_info (nerian_stereo/StereoCameraInfo)

Launching and parameters

Example launch files are included for the ROS1 node and nodelet and for ROS2. You can run several nodes in parallel if you use more than one device, specifying the respective device address and a desired ROS node name in case of ROS1:

# For ROS1:
roslaunch nerian_stereo nerian_stereo.launch device_address:=192.168.10.10 node_name:=nerian_stereo_01

# For ROS2:
ros2 launch nerian_stereo nerian_stereo.launch.py

The behaviour of the node can be configured through various parameters. An example parameterization can be found in the included launch file nerian_stereo.launch. The following parameters are supported:

~point_cloud_intensity_channel (string, default: "mono8")

~ros_coordinate_system (bool, default: "true") ~ros_timestamps (bool, default: "true") ~color_code_disparity_map (string, default: "none") ~color_code_legend (bool, default: "true") ~frame (string, default: "world") ~remote_host (string, default: "0.0.0.0") ~remote_port (string, default: "7681") ~use_tcp (bool, default: "false") ~calibration_file (string, default: "") ~delay_execution (double, default: 0) ~max_depth (double, default: -1)

Testing

The topics published by the nerian_stereo node can be viewed with rviz. The disparity map can also be visualized with the image_view node in ROS1 or showimage from ROS2. To do so, use can use one of the following commands:

# For ROS1:
rosrun image_view image_view image:=/nerian_stereo/disparity_map

# For ROS2:
ros2 run image_tools showimage image:=/nerian_stereo/disparity_map

In this case color coding should be activated such that the disparity map can be displayed on a screen.

https://nerian.com/nerian-images/image_view.jpg

For displaying the left camera image, please run the image_view node with the following command line:

#For ROS1:
rosrun image_view image_view image:=/nerian_stereo/left_image

#For ROS2:
ros2 run image_tools showimage image:=/nerian_stereo/left_image

Dynamic reconfiguration in ROS1

At launch time, the ROS1 node (and nodelet) publishes the current configuration reported by the respective device to the ROS parameter server, and can be reconfigured at run time using ROS dynamic_reconfigure, for example using the GUI:

rosrun rqt_reconfigure rqt_reconfigure

Further Information

http://c.statcounter.com/10599048/0/906ae443/1/

Wiki: nerian_stereo (last edited 2021-04-14 10:51:01 by Konstantin Schauwecker)