Only released in EOL distros:
Package Summary
ROS package for HLDS(Hitachi-LG Data Storage,Inc.) HLS-LFOM 3D LiDAR(TOF)
- Maintainer status: maintained
- Maintainer: Jeehoon Yang <jhyang AT hlds.co DOT kr>
- Author: Jeehoon Yang <jhyang AT hlds.co DOT kr>, Wayne Rust <wayne.rust AT educatedrobot DOT com>
- License: BSD
- Bug / feature tracker: https://github.com/HLDS-GIT/hls_lfom_tof_driver/issues
- Source: git https://github.com/HLDS-GIT/hls_lfom_tof_driver.git (branch: master)
Contents
Manufacturer of the TOF: Hitachi-LG Data Storage, Inc.
Product Webpage: HLDS 3D LiDAR(TOF)
Overview
* Object distance measurement with high accuracy in realtime
* Easy to install with Ethernet (POE+) connection
* Multiple use cases can be accommondated with the SDK
Product Specification
Installation
Download HLS-LFOM SDK
Download latest version(v2.1.0 or later) for Ubuntu 16.04 LTS (x64) and extract it(http://hlds.co.jp/product-eng/tofsdk)
Install SDK
$ sudo dpkg -i libtof-dev_<version_number>ubuntu16_amd64.deb
Build HLS-LFOM 3D LiDAR(TOF) driver
$ cd ~/catkin_ws/src $ git clone https://github.com/HLDS-GIT/hls_lfom_tof_driver.git $ cd ~/catkin_ws $ catkin_make
If using SDK older than v2.3, please use CMakeLists_old.txt.
Setting IP address
Modify IP address of tof.ini file in launch folder. It should be the same as the IP address of the TOF sensor you are trying to connect. (Default is 192.168.0.105)
If you want to change IP address, please refer to Setup TOF sensor of API Reference Manual in SDK
Running Node
Run hlds_3dtof_node
roslaunch hls_lfom_tof_driver hlds_tof_driver.launch
Run hlds_3dtof_node with RViz
roslaunch hls_lfom_tof_driver view_hlds_tof_driver.launch
Nodes
hlds_3dtof_node
hlds_3dtof_node is a driver for HLS-LFOM 3D LiDAR(TOF). It reads raw sensor data using HLS-LFOM's SDK and convert to ROS message.Published Topics
cloud (sensor_msgs/PointCloud2)- XYZ point cloud
- point.z data with TYPE_32FC1 encoding type
- 3channel depths data with RGB8 encoding type
- IR image with MONO8 encoding type
Services
set_distance_mode_srv (hls_lfom_tof_driver/DistanceMode)- Set TOF distance mode (dm_2_0x, dm_1_5x, dm_1_0x, dm_0_5x)
- Set to 'true' enable and 'false' to disable edge signal cutoff.
- Set value (0.0~1.0)
- Set value (0~4095)
Parameters
camera_mode (string, default: CameraModeDepth)- set camera mode : CameraModeDepth, CameraModeIr, Depth_Ir(TOFv2 only)
- X-axis rotation angle(0 to 359 degree)
- Y-axis rotation angle(0 to 359 degree)
- Z-axis rotation angle(0 to 359 degree)
- Edge noise reduction mode
- Signal level to cutoff(0 to 4095)
- Distance rate far from TOF(rate:0.0~1.0)
- Pixel size of TOF sensor image. Refer to CameraPixel type of API reference manual in SDK
- Exposure sensitivity for IR(1 to 15)
- Distance mode of TOF sensor. Refer to DistanceMode type of API reference manual in SDK
- Frame rate of TOF sensor. Refer to FrameRate type of API reference manual in SDK
Use Case
3D SLAM
3D occupancy grid mapping and hector slam with HLS-LFOM1
Package Installation
// Install pointcloud to laserscan $ sudo apt-get install ros-kinetic-pointcloud-to-laserscan //Install hector slam $ sudo apt-get install ros-kinetic-hector-slam //Install octomap $ sudo apt-get install ros-kinetic-octomap-server
Example
Depth image processing
Combine depth image and IR image into XYZRGB point cloud
Package Installation
Example
Depth image processing launch file
OpenPose
OpenPose with IR image
Package Installation
Example
Related Links
HLDS 2D LiDAR: HLS-LFCD2 HLS-LFCD3