Contents
Overview
This package contains tools for Velodyne 3D laser scanner (tested with Velodyne HDL-32E). There are three main nodes:
Laserscan Node - simulates conventional 2D scanner by using data from 3D LiDAR.
Groundmap Node - estimates "safe ground" (i.e. not too rough, without high steps and other obstacles) around the robot.
Cloud Assembler Node - combines several consecutive point clouds into a more dense cloud.
Each node has it's nodelet counterpart with same ROS API.
Use GitHub to report bugs or submit feature requests. [View active issues]
Installation
From source:
- Clone the github repository.
- Copy the cloned repository into the 'src' folder of your ROS workspace.
- Recompile your ROS workspace: $ catkin_make.
Laserscan Node
Uses 3D data to simulate conventional 2D scanner. This way, Velodyne might be used with move_base.
Usage example:
1 roslaunch but_velodyne_proc laserscan_node.launch
Topics
points_in (sensor_msgs/PointCloud2)
- input 3D cloud
- simulated 2D scanner output
Parameters
~frame_id (string, default: "")
- output frame_id (will be same as in input data if not specified)
- points under this height will be discarded
- points above this height will be discarded
- angular resolution (radians)
- points closer to the sensor than this will be discarded
Groundmap Node
Estimates frame-to-frame bumpiness of robot's surrounding and publishes it as an occupancy grid. This might be used by autonomous rovers supposed to navigate on a rough terrain.
Topics
points_in (sensor_msgs/PointCloud2)
- input 3D cloud
- 2D map of bumpiness
Parameters
~map2d_res (double, default: "0.001")
- resolution of output 2D map
- width of output 2D map
- height of output 2D map
- points further than max_range will be skipped
- angular resolution for internal processing
- radial resolution for internal processing
- tbd
- tbd
- simple filtering of isolated occupied cells
- tbd
- tbd
Cloud Assembler Node
When a robot is moving, this node combines few historic clouds and the current one to produce denser cloud.
Topics
/velodyne_points (sensor_msgs/PointCloud2)
- input 3D cloud
- dense cloud