Only released in EOL distros:  

sick_visionary_t: sick_visionary_t_driver

Package Summary

Open source driver for the SICK Visionary-T 3D TOF camera.

  • Maintainer status: developed
  • Maintainer: Joshua Hampp <joshua.hampp AT ipa.fraunhofer DOT de>, Marco Dierschke <marco.dierschke AT sick DOT de>
  • Author: Joshua Hampp <joshua.hampp AT ipa.fraunhofer DOT de>
  • License: Apache License, Version 2.0 (http://www.apache.org/licenses/LICENSE-2.0)
  • Source: git https://github.com/SICKAG/sick_visionary_t.git (branch: indigo_release_candidate)
sick_visionary_t: sick_visionary_t_driver

Package Summary

Open source driver for the SICK Visionary-T 3D TOF camera.

  • Maintainer status: maintained
  • Maintainer: Joshua Hampp <joshua.hampp AT ipa.fraunhofer DOT de>, Marco Dierschke <marco.dierschke AT sick DOT de>
  • Author: Joshua Hampp <joshua.hampp AT ipa.fraunhofer DOT de>
  • License: Apache License, Version 2.0 (http://www.apache.org/licenses/LICENSE-2.0)
  • Source: git https://github.com/SICKAG/sick_visionary_t.git (branch: indigo_release_candidate)

Description

This is an open source driver for the SICK visionary-T. The visionary-T is a 3D camera based on the time-of- flight (TOF) principle. It provides real-time 3D data at up to 30 frame per second (fps).

The 3D camera is configured and its images visualized via the SOPAS ET software.

Once configured it runs in stand-alone operation mode and continuously streams 3D data via TCP/IP.

Please see the operation manual for further information and/or technical details.

Driver repository:

build status

Supported Hardware

This driver works with the following products

  • device name

    type

    part no.

    visionary-T CX

    V3S100-1AAAAAA

    1067189

    visionary-T CX without cooling fins

    V3S100-1AABAAB

    1075027

    visionary-T AG

    V3S110-1AAAAAA

    1075613

    visionary-T AG without cooling fins

    V3S110-1AABAAB

    1075614

API Stability

The 3D data streaming part of the ROS API is stable.

The digital i/o channel interface of this driver is considered unstable and not implemented yet.

Installation

In order to receive data, the IP address of the device has to be known. Using SOPAS ET the default IP address (192.168.1.10) can be verified, changed and stored permanently into the device.

In order to determine the IP address:

  1. first connect the camera device to a power source and the network interface to your computer, then
  2. start the SOPAS ET executable (Windows (r) based system required).

The device should be found, its IP address shown and automatically be added to the SOPAS project.

Make sure that the device is pingable to verify the correct network configuration.

The remote_device_ip parameter in the launch file needs to be set to the verified device IP address. This easiest way is to provide the parameter is in the launch file (launch/sick_visionary_t_driver.launch).

Operation

When the ROS driver is started, it sends a command that starts the data streaming of the visionary-T. When the driver is terminated, the data streaming is stopped at the device.

Attention
This means the device has to be power-cycled before it can be used with Sopas ET to view the 3D data.

ROS API

sick_visionary_t_driver_node

Open source driver for the SICK visionary-T 3d TOF camera.

Published Topics

Depth camera
Publishes depth, confidence and itensity data.
camera/camera_info (sensor_msgs/CameraInfo)
  • Camera calibration and metadata.
camera/depth (sensor_msgs/Image)
  • Raw image from device. Contains uint16 depths in mm.
camera/confidence (sensor_msgs/Image)
  • Raw image from device. Contains uint16 confidence values.
camera/intensity (sensor_msgs/Image)
  • Raw image from device. Contains uint16 intensity values.
Status and inputs/outputs
Publishes the status information and IO state of the sensor.
camera/ios (std_msgs/ByteMultiArray)
  • IO state of the camera.
/diagnostics (diagnostic_msgs/DiagnosticStatus)
  • Current state of the device including device variables.
Polar Scan
Publishes the response of the polar scan (uses 3D camera as laser scan, configuration by Sick software).
camera/scan (sensor_msgs/LaserScan)
  • Measurements reduced to a laser scan.
Height Map
Publishes the response of the height map (uses 3D camera to detect obstacles on the floor in front of the camera, configuration by Sick software).
camera/cartesian (sensor_msgs/PointCloud2)
  • Measurements reduced to a 2D grid.

Services

enable_depth_map (std_srvs/Trigger)
  • Stops height map and polar scan stream and starts stream of pointclouds.
enable_height_map (std_srvs/Trigger)
  • Stops depth map and polar scan stream and starts stream of the Cartesian warning zones.
enable_polar_scan (std_srvs/Trigger)
  • Stops height map and depth map stream and starts stream of polar scan which simulates a laser scan.

Parameters

~remote_device_ip (string, default: 192.168.1.10)
  • Specifies the address of the device to open (e. g. an ip address). The settings of the sensor (regarding calibration, resolution and so) are read from the device and used.
~frame_id (string, default: camera)
  • Specifies the frame id of the published messages.
~prevent_frame_skipping (bool, default: false)
  • Specifies whether the publishing and generation of ROS messages are skipped if the computer is too slow to handle all the data. Therefore only the most recent data from the sensor is published (if parameter is false).
~io_polling_interval (double, default: 0.1)
  • Specifies the time interval in seconds to poll the IOs of the device.
~channel (string, default: NO_CHANGE)
  • Specifies the initial selected streaming/channel (NO_CHANGE, DEPTHMAP, POLAR2D, CARTESIAN).
~user (string, default: SERVICE)
  • Specifies the default user level used to write parameters (RUN, AUTHORIZEDCLIENT, MAINTENANCE, SERVICE).

Wiki: sick_visionary_t_driver (last edited 2016-12-14 11:33:43 by josh)