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:

  1. Clone the github repository.
  2. Copy the cloned repository into the 'src' folder of your ROS workspace.
  3. 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.

Simulated 2D scanner (green points).

Usage example:

   1 roslaunch but_velodyne_proc laserscan_node.launch

Topics

points_in (sensor_msgs/PointCloud2)

  • input 3D cloud
scan_out (sensor_msgs/LaserScan)
  • simulated 2D scanner output

Parameters

~frame_id (string, default: "")

  • output frame_id (will be same as in input data if not specified)
~min_z (double, default: "")
  • points under this height will be discarded
~max_z (double, default: "")
  • points above this height will be discarded
~angular_res (double, default: "")
  • angular resolution (radians)
~min_range (double, default: "")
  • 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.

Resulting groundmap published as occupancy grid.

Topics

points_in (sensor_msgs/PointCloud2)

  • input 3D cloud
map2d_out (nav_msgs/OccupancyGrid)
  • 2D map of bumpiness

Parameters

~map2d_res (double, default: "0.001")

  • resolution of output 2D map
~map2d_width (double, default: "0")
  • width of output 2D map
~map2d_height (double, default: "0")
  • height of output 2D map
~max_range (double, default: "0")
  • points further than max_range will be skipped
~angular_res (double, default: "0.01")
  • angular resolution for internal processing
~radial_res (double, default: "0.01")
  • radial resolution for internal processing
~max_road_irregularity (double, default: "0")
  • tbd
~max_height_diff (double, default: "0")
  • tbd
~noise_filter (double, default: "true")
  • simple filtering of isolated occupied cells
~ground_prob (double, default: "")
  • tbd
~obstacle_prob (double, default: "")
  • tbd

Cloud Assembler Node

When a robot is moving, this node combines few historic clouds and the current one to produce denser cloud.

Original cloud.

Output cloud.

Topics

/velodyne_points (sensor_msgs/PointCloud2)

  • input 3D cloud
output (sensor_msgs/PointCloud2)
  • dense cloud

Wiki: but_velodyne_proc (last edited 2014-07-08 09:46:55 by ZdenekMaterna)