Only released in EOL distros:
Package Summary
Package laserscan_kinect converts depth image from Microsoft Kinect sensor to 2D laser scanner format. Conversion algorithm allows to remove ground from depth image and compensate sensor mount tilt angle relative to the ground.
- Maintainer status: developed
- Maintainer: Michal Drwiega <drwiega.michal AT gmail DOT com>
- Author: Michal Drwiega
- License: BSD
- Source: git https://github.com/mdrwiega/depth_nav_tools.git (branch: indigo-devel)
Package Summary
Package laserscan_kinect converts depth image from the depth sensor to a 2D laser scanner format. The conversion algorithm allows to remove a ground from the depth image and compensate the sensor mount tilt angle relative to the ground.
- Maintainer status: developed
- Maintainer: Michal Drwiega <drwiega.michal AT gmail DOT com>
- Author: Michal Drwiega (http://www.mdrwiega.com)
- License: BSD
- Source: git https://github.com/mdrwiega/depth_nav_tools.git (branch: kinetic-devel)
Contents
Overview
The package laserscan_kinect converts depth image to laser scan (sensor_msgs/LaserScan). It allows to use RGB-D sensor (for example Microsoft Kinect) for navigation purposes. Package laserscan_kinect finds the smallest value of distance in each column of the depth image and converts it to polar coordinates.
Moreover, the package provides features like a ground removing from the scan and a sensor tilt compensation in distance values, but it is necessary to know a height of sensor optical center and a tilt angle in the frame of ground.
Example
The picture shows a comparison between the laser scan based on converted depth image from Microsoft Kinect (blue points) and a laser scan from the scanner Hokuyo URG-04LX-UG01 (black points). Moreover, the picture contains the RBG image and the depth image.
Tuning
During the tuning process additional debug image can be used. It contains lines that represent the lower and upper bounds of the detection area. Also, closest points in each image column are visible.
Usage
The file /config/params.yaml contains example parameters values. To start the node laserscan_kinect it can be used a following file /launch/laserscan.launch .
Node
laserscan_kinect
Subscribed Topics
image (sensor_msgs/Image)- Depth image which will be converted to laserscan.
- Additional information about the depth sensor.
Published Topics
/scan (sensor_msgs/LaserScan)- Converted depthimage. It contains information about the robot surrounding in a planar scan.
- Debug image used during the tuning process.
Parameters
~output_frame_id (str, default: camera_depth_frame)- Frame id for the output laserscan message.
- Minimum sensor range (in meters). Pixels in the depth image with values smaller than this parameter are ignored during the processing.
- Maximum sensor range (in meters). Pixels in the depth image with values greater than this parameter are ignored during the processing.
- Row step in the depth image processing. By increasing this parameter the computational complexity of the algorithm is decreased but some of data are losted.
- Height of used part of the depth image (in pixels).
- Determines if continuously camera model data update is necessary. If it's true, then camera model (sensor_msgs/CameraInfo) from topic camera_info is updated with each new depth image message. Otherwise, the camera model and parameters associated with it are updated only at the beginning of the node or when the node parameter is changed by dynamic_reconfigure.
- Determines if a ground removal from the output scan feature is enabled. The ground removal method to work needs correctly defined values of parameters like a sensor_tilt_angle and sensor_mount_height.
- Height of the depth sensor optical center mount (in meters). Parameter is necessary for the ground removal feature. It should be measured from the ground to the optical center of the depth sensor.
- Depth sensor tilt angle (in degrees). If the sensor is leaning towards the ground the tilt angle should be positive. Otherwise, the value of the angle should be negative.
- Margin in the ground removal feature (in meters).
- Parameter determines if sensor tilt angle compensation is enabled.
- Publish a debug image that can be used during the parameters tuning process.
Report a Bug
Use GitHub to report bugs or submit feature requests. [View active issues]