Show EOL distros: 

sick_tim

Package Summary

A ROS driver for the SICK TiM series of laser scanners. Currently, the package supports several types of TiM310 and TiM551 scanners.

Package Summary

A ROS driver for the SICK TiM series of laser scanners. Currently, the pacakge supports serveral types of TiM310 and TiM551 scanners.

Package Summary

A ROS driver for the SICK TiM and the SICK MRS 1000 laser scanners.

Package Summary

A ROS driver for the SICK TiM series of laser scanners.

Package Summary

A ROS driver for the SICK TiM and the SICK MRS 1000 laser scanners.

Package Summary

A ROS driver for the SICK TiM and the SICK MRS 1000 laser scanners.

Package Summary

A ROS driver for the SICK TiM and the SICK MRS 1000 laser scanners.

Package Summary

A ROS driver for the SICK TiM and the SICK MRS 1000 laser scanners.

Choosing the right branch

Choose the branch named according to your ROS version (e.g. melodic, noetic...).

Supported scanner types

This package provides one node for each supported type of scanner (all nodes provide the same features, regarding the Sick Tim). The model name and part no. can be found on the side of the scanner. Since all scanners of the TIM line look alike, this is the only reliable way of identifying your device. Additionally, this driver supports the Sick MRS1000 scanner.

If your TIM scanner is not listed below, just try out whether one of the nodes works for you. If it does, drop us a mail, so we can add that model to the list. If it doesn't, open a Github issue, and we'll try to add support.

Node: sick_tim310s01

Model Name: TIM310-1030000S01

Part No.: 1056791

Web site: link

This is the "special edition" of the TIM3xx line. It was developed on request and officially supports ranging (i.e., there is a specification of the datagram format).

Frequency: 15 Hz, range: 4m. Range + intensities.

  • This node also works with the TIM510-9950000S01 (see issue).

Node: sick_tim310

Model Name: TIM310-1030000

Part No.: 1052627

Web site: link.

This is the standard edition of the TIM310. It does not support ranging (only detection). There was a firmware bug in versions prior to V2.50 that allowed ranging output, and this node works with those firmware versions. All newer firmware versions will not work.

Frequency: 1.875 Hz, range: 4m. Range + intensities. (This is a little strange, because according to the specs, frequency should be 15 Hz).

Node: sick_tim310_1130000m01

Model Name: TIM310-1130000M01

Part No.: 1062563

Web site: none

Only available as a sample device (?). Angular resolution: 3°, no intensities. Will probably be rebranded as TIM-510.

Frequency: 15 Hz, range: 4m. Only range, no intensities.

Node: sick_tim551_2050001

Model Name: TIM551-2050001

Part No.: 1060445

Web site: link

Frequency: 15 Hz, angular resolution: 1°, range: 10m. Range + intensities.

Other devices tested to work with this node (both TCP and USB, where available):

  • TIM351-2134001 only works with firmware revisions prior to V2.50 (cf. Issue)

  • TIM561-2050101

  • TIM571-2050101 (P/N 1075091); frequency: 15 Hz, angular resolution: 0.333°, range: 25m; see sick_tim571_2050101.launch

Node: sick_mrs1000

Model Name: MRS1104C-111011

Part No.: 1081208

Web site: link

Frequency: 4 x 12.5 Hz Angular resolution: 0.25° Aperture angle: Horizontal: 275°; Vertical 7.5° (Over 4 measurement layer) Range: 0.2m to 64m Systematic error: ± 60 mm Statistical error: ≤ 30 mm Connection: LAN, TCP

ROS API

sick_tim*

Published Topics

scan (sensor_msgs/LaserScan)
  • The published laser scans.
datagram (std_msgs/String)
  • The datagrams as received from the scanner (for debug purposes). Is only enabled when the publish_datagram param is set.

Parameters

Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~min_ang (double, default: -2.35619449019)
  • The angle of the first range measurement [rad]. Range: -2.35619449019 to 2.35619449019
~max_ang (double, default: 2.35619449019)
  • The angle of the last range measurement [rad]. Range: -2.35619449019 to 2.35619449019
~intensity (bool, default: True)
  • Whether or not to return intensity values. RSSI output must be enabled on scanner (see "Enabling intensity (RSSI) output").
~skip (int, default: 0)
  • The number of scans to skip between each measured scan. Range: 0 to 9
~frame_id (str, default: laser)
  • The TF frame in which laser scans will be returned.
~time_offset (double, default: -0.001)
  • An offset to add to the time stamp before publication of a scan [s]. Range: -0.25 to 0.25
~auto_reboot (bool, default: True)
  • Whether or not to reboot laser if it reports an error
Not Dynamically Reconfigurable Parameters
~hostname (string, default: None)
  • Enables TCP (Ethernet) instead of USB connection; hostname is the host name or IP address of the laser scanner (only valid for TiM551)
~port (string, default: "2112")
  • TCP port used (only evaluated if hostname is set).
~publish_datagram (bool, default: False)
  • Only for debug purposes: enables publishing messages on the /datagram topic (see above).
~subscribe_datagram (bool, default: false)
  • Only for debug purposes: If set to true, enables subscribing to the /datagram topic (instead of reading from the physical device). Useful to debug datagrams from a rosbag that was previously recorded using the publish_datagram param.

Before starting

See the udev/README file in the package directory.

USB vs. TCP (Ethernet) connection

By default the node will try to use the USB connection. To use the ethernet connection instead (for those scanners that have one), you have to set the parameter "hostname" to the scanner hostname or IP (see commented out part in the respective sick_tim/launch/sick*.launch files).

The scanner IP can be changed using the SICK SOPAS-ET configuration software.

In case of problems, make sure your PC is on the same network as the scanner and that you can ping the scanner from your PC.

Enabling intensity (RSSI) output and high angular resolution

To reduce data rates, some scanners (e.g., the TiM 571) don't send RSSI data by default. It must first be enabled in the configuration software by downloading SOPAS-ET 3.2.0, connecting to the sensor using USB or Ethernet, logging in (UID: Authorized Client, PWD: client), and clicking the checkbox shown below:

sopas-enable-rssi.png

Also, to get a high angular resolution, you may have to configure a higher baud rate. For example, the TIM510-9950000S01 will output the measurements at 460,800 bit/s with an angular resolution of 1° or at 115,200 bit/s with an angular resolution of 3°, so make sure to select a baud rate of 460,800 bit/s.

Quick start

roslaunch sick_tim sick_tim551_2050001.launch

Now you can visualize the /scan topic using rviz. Enjoy! :-)

sick_tim3xx.png

Report a Bug

Use GitHub to report bugs or submit feature requests. [View active issues]

  • Enable publish_datagram in the launch file, by moving it out of the xml comments (<!-- ... -->) and setting it to true: <param name="publish_datagram" type="bool" value="true" />.

  • roslaunch sick_tim sick_timXXX.launch
  • (in a new terminal:) rosbag record --limit=50 --bz2 /scan /datagram /diagnostics
  • Attach the resulting bag file to the bug report.

Wiki: sick_tim (last edited 2022-04-05 15:52:27 by MartinGuenther)