Skip to main content

Decoder for raw Velodyne packet data

Project description

velodyne_decoder PyPI Build

Python package and C++ library for Velodyne packet decoding. Intended as a light-weight substitute for velodyne_driver in ROS with minimal external dependencies.

The resulting decoded data is provided as a structured NumPy array in Python and an array of structs in C++.

array([(8.327308, -2.161341, 0.3599853, 85., 17, -0.04960084),
       (8.323784, -2.9578836, 0.27016047, 102., 15, -0.04959854),
       (8.184404, -2.845847, -0.8741639, 39., 2, -0.04959623), ...,
       (8.369528, -2.8161895, 2.307987, 17., 31, 0.00064051),
       (8.377898, -3.2570598, 1.7714221, 104., 30, 0.00064282),
       (8.358282, -2.8030438, 0.31229734, 104., 16, 0.00064282)],
      dtype={'names': ['x', 'y', 'z', 'intensity', 'ring', 'time'],
             'formats': ['<f4', '<f4', '<f4', '<f4', '<u2', '<f4'], 'offsets': [0, 4, 8, 16, 20, 24], 'itemsize': 32})

The layout of the structs and the array is identical to the PointXYZIRT point clouds output by the ROS driver.

Installation

Wheels are available from PyPI for Linux, MacOS and Windows. Python versions 2.7 and 3.6+ are supported.

pip install velodyne-decoder

Alternatively, you can build and install the development version from source.

sudo apt-get install cmake build-essential python3-dev
pip install git+https://github.com/valgur/velodyne_decoder.git

Usage

Decoding Velodyne data from a ROS bag

from rosbag import Bag
import velodyne_decoder as vd

config = vd.Config()
config.model = '32C'
config.calibration_file = '/opt/ros/noetic/share/velodyne_pointcloud/params/VeloView-VLP-32C.yaml'
config.min_range = 0.3
config.max_range = 130
decoder = vd.ScanDecoder(config)

bagfile = 'xyz.bag'
lidar_topics = ['/velodyne_packets']
cloud_arrays = []
with Bag(bagfile) as bag:
    for topic, scan_msg, ros_time in bag.read_messages(lidar_topics):
        cloud_arrays.append(decoder.decode_message(scan_msg))

config.model and config.calibration_file are required. For a list of supported model IDs see

>> > velodyne_decoder.Config.SUPPORTED_MODELS
['VLP16', '32C', '32E', 'VLS128']

For the calibration file you can use the one provided with the velodyne driver matching your model.

Additional optional config parameters are min_range and max_range in meters and min_angle and max_angle in degrees.

Authors

  • Martin Valgur (@valgur) – this library.

The core functionality has been adapted from the ROS velodyne driver.

License

BSD 3-Clause License

Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distribution

velodyne-decoder-1.0.1.tar.gz (5.4 kB view hashes)

Uploaded Source

Built Distributions

velodyne_decoder-1.0.1-cp39-cp39-win_amd64.whl (174.6 kB view hashes)

Uploaded CPython 3.9 Windows x86-64

velodyne_decoder-1.0.1-cp39-cp39-manylinux2010_x86_64.whl (339.5 kB view hashes)

Uploaded CPython 3.9 manylinux: glibc 2.12+ x86-64

velodyne_decoder-1.0.1-cp39-cp39-macosx_10_9_x86_64.whl (219.9 kB view hashes)

Uploaded CPython 3.9 macOS 10.9+ x86-64

velodyne_decoder-1.0.1-cp38-cp38-win_amd64.whl (177.2 kB view hashes)

Uploaded CPython 3.8 Windows x86-64

velodyne_decoder-1.0.1-cp38-cp38-manylinux2010_x86_64.whl (339.2 kB view hashes)

Uploaded CPython 3.8 manylinux: glibc 2.12+ x86-64

velodyne_decoder-1.0.1-cp38-cp38-macosx_10_9_x86_64.whl (219.9 kB view hashes)

Uploaded CPython 3.8 macOS 10.9+ x86-64

velodyne_decoder-1.0.1-cp37-cp37m-win_amd64.whl (177.8 kB view hashes)

Uploaded CPython 3.7m Windows x86-64

velodyne_decoder-1.0.1-cp37-cp37m-manylinux2010_x86_64.whl (341.4 kB view hashes)

Uploaded CPython 3.7m manylinux: glibc 2.12+ x86-64

velodyne_decoder-1.0.1-cp37-cp37m-macosx_10_9_x86_64.whl (218.5 kB view hashes)

Uploaded CPython 3.7m macOS 10.9+ x86-64

velodyne_decoder-1.0.1-cp36-cp36m-win_amd64.whl (177.8 kB view hashes)

Uploaded CPython 3.6m Windows x86-64

velodyne_decoder-1.0.1-cp36-cp36m-manylinux2010_x86_64.whl (341.4 kB view hashes)

Uploaded CPython 3.6m manylinux: glibc 2.12+ x86-64

velodyne_decoder-1.0.1-cp36-cp36m-macosx_10_9_x86_64.whl (218.5 kB view hashes)

Uploaded CPython 3.6m macOS 10.9+ x86-64

velodyne_decoder-1.0.1-cp35-cp35m-win_amd64.whl (177.8 kB view hashes)

Uploaded CPython 3.5m Windows x86-64

velodyne_decoder-1.0.1-cp35-cp35m-manylinux2010_x86_64.whl (341.3 kB view hashes)

Uploaded CPython 3.5m manylinux: glibc 2.12+ x86-64

velodyne_decoder-1.0.1-cp35-cp35m-macosx_10_9_x86_64.whl (218.5 kB view hashes)

Uploaded CPython 3.5m macOS 10.9+ x86-64

velodyne_decoder-1.0.1-cp27-cp27mu-manylinux2010_x86_64.whl (342.3 kB view hashes)

Uploaded CPython 2.7mu manylinux: glibc 2.12+ x86-64

velodyne_decoder-1.0.1-cp27-cp27m-win_amd64.whl (178.7 kB view hashes)

Uploaded CPython 2.7m Windows x86-64

velodyne_decoder-1.0.1-cp27-cp27m-manylinux2010_x86_64.whl (342.2 kB view hashes)

Uploaded CPython 2.7m manylinux: glibc 2.12+ x86-64

velodyne_decoder-1.0.1-cp27-cp27m-macosx_10_9_x86_64.whl (219.1 kB view hashes)

Uploaded CPython 2.7m macOS 10.9+ x86-64

Supported by

AWS AWS Cloud computing and Security Sponsor Datadog Datadog Monitoring Fastly Fastly CDN Google Google Download Analytics Microsoft Microsoft PSF Sponsor Pingdom Pingdom Monitoring Sentry Sentry Error logging StatusPage StatusPage Status page