Show EOL distros: 

velodyne: velodyne_driver | velodyne_msgs | velodyne_pointcloud

Package Summary

ROS device driver for Velodyne HDL-64E, HDL-64E S2, and HDL-32 LIDARs.

velodyne: velodyne_driver | velodyne_msgs | velodyne_pointcloud

Package Summary

ROS device driver for Velodyne HDL-64E, HDL-64E S2, and HDL-32 LIDARs.

velodyne: velodyne_driver | velodyne_msgs | velodyne_pointcloud

Package Summary

ROS device driver for Velodyne HDL-64E, HDL-64E S2, and HDL-32 LIDARs.

velodyne: velodyne_driver | velodyne_msgs | velodyne_pointcloud

Package Summary

ROS device driver for Velodyne HDL-64E, and HDL-32 LIDARs.

velodyne: velodyne_driver | velodyne_laserscan | velodyne_msgs | velodyne_pointcloud

Package Summary

ROS device driver for Velodyne 3D LIDARs.

velodyne: velodyne_driver | velodyne_laserscan | velodyne_msgs | velodyne_pointcloud

Package Summary

ROS device driver for Velodyne 3D LIDARs.

velodyne: velodyne_driver | velodyne_laserscan | velodyne_msgs | velodyne_pointcloud

Package Summary

ROS device driver for Velodyne 3D LIDARs.

velodyne: velodyne_driver | velodyne_laserscan | velodyne_msgs | velodyne_pointcloud

Package Summary

ROS device driver for Velodyne 3D LIDARs.

velodyne: velodyne_driver | velodyne_laserscan | velodyne_msgs | velodyne_pointcloud

Package Summary

ROS device driver for Velodyne 3D LIDARs.

Overview

This package provides basic device handling for Velodyne 3D LIDARs. For a list of all supported models refer to the Supported Devices section.

The driver publishes device-dependent velodyne_msgs/VelodyneScan data. The velodyne_pointcloud package provides nodes and nodelets to convert those data into more-convenient sensor_msgs/PointCloud2 messages.

The API review describes the evolution of these interfaces.

Supported Devices

This driver supports all current Velodyne HDL-64E, HDL-32E, VLP-32C, and VLP-16 models. There is little difference in the way it handles those devices.

Different models publish packets at a different rate. Up through the ROS Groovy release, no distinction was made between the HDL-64E, HDL-64E S2, HDL-64E S2.1, and HDL-64E S3 variants. Unfortunately, the packet data rates for those devices are not all the same.

New in Hydro: the model parameter now expects an exact name: "VLP16", "32C", "32E", "64E", "64E_S2", "64E_S2.1", or "64E_S3", and generates the correct packet rates for them.
New in 1.3.0: The VLP-16 ("Puck") model is now supported.
New in 1.5.0: The VLP-32C ("Ultra Puck") model is now supported.
New in 1.5.2: The HDL-64E S3 model is now supported.

ROS Nodes

  • velodyne_node
    ROS node that captures Velodyne 3D LIDAR data and publishes it in raw form. This uses the same device driver class as velodyne_driver/DriverNodelet.

    • Publishes

      • velodyne_packets

        • type = velodyne_msgs/VelodyneScan
          Velodyne data packets (typically for one entire revolution of the device) in the /velodyne frame of reference.

      • diagnostics

        • type = diagnostic_msgs/DiagnosticStatus
          Diagnostic status information.

    • Parameters

      • frame_id

        • type = string
          default = velodyne
          Transform frame ID for the device (resolved using tf_prefix, if defined).

      • model

        • type = string
          default = "64E"
          Device model: "32E", "64E", "64E_S2" or "64E_S2.1", New in 1.3.0: "VLP16", New in 1.5.0: "32C", New in 1.5.2: "64E_S3"

      • npackets

        • type = int
          default = enough for a complete revolution
          Number of packets to publish per message.

      • pcap<<BR>

        • type = string
          default = use real device (empty)
          PCAP dump input file name.

      • rpm

        • type = double
          default = 600
          Device rotation speed in Revolutions per Minute. Note: This does not modify the device configuration, it is just a value that the driver uses for calculating the packets per rotation.

      • port

        • type = int
          default = 2368
          New in 1.3.0: UDP port to read.

      • device_ip

        • type = string
          default = use any device
          New in 1.3.0: dotted decimal IP address of device.

Examples

Read the Velodyne HDL-64E (default) input socket as fast as possible. Publish each complete revolution to velodyne_packets.

$ rosrun velodyne_driver velodyne_node

Read the Velodyne Velodyne HDL-32E input socket as fast as possible. Publish each complete revolution to velodyne_packets.

 $ rosrun velodyne_driver velodyne_node _model:=32E

Read previously captured Velodyne packets from dump.pcap file. Publish messages to velodyne_packets at approximately 10 Hz rate. Dump files can be grabbed by libpcap, Velodyne's DSR software, ethereal, wireshark, tcpdump, or the vdump command.

$ rosrun velodyne_driver velodyne_node _pcap:=dump.pcap

DriverNodelet

ROS nodelet that captures Velodyne 3D LIDAR data and publishes it in raw form. This uses the same device driver class as velodyne_node. All topics and parameters are identical.

Utility Commands

vdump

The vdump command dumps raw data from the Velodyne LIDAR in PCAP format. It is a shell script wrapper providing some obscure options for the powerful tcpdump command.

Other methods of acquiring PCAP data include using tcpdump directly, wireshark, Velodyne's DSR software, and programming with libpcap.

Usage

  rosrun velodyne_driver vdump <file_prefix> [ <interface> ]

        <file_prefix>   file name to dump (with 3-digit number suffix)
        <interface>     interface to read from (default: "eth0")

Examples

Dump Velodyne packets from the eth1 interface to a series of files named pcap-000, pcap-001, etc. Each file will be about 100MB. The time span that a single 100MB file covers depends on packet size and sampling rate of a particular model (for VLP-16 that is about 100 seconds worth of packets). Type ^C when finished.

$ rosrun velodyne_driver vdump pcap- eth1

Launch File Examples

Start a velodyne_nodelet_manager process running the driver nodelet. Other nodelets using the same nodelet manager process will have zero-copy access to the raw data messages the driver publishes.

 $ roslaunch velodyne_driver nodelet_manager.launch

Start a velodyne_nodelet_manager process for a Velodyne HDL-32E.

 $ roslaunch velodyne_driver nodelet_manager.launch model:=32E

Start a driver nodelet with input from tcpdump.pcap, in the current directory. The pwd provides a full path name, as required for roslaunch.

 $ roslaunch velodyne_driver nodelet_manager.launch pcap:=$(pwd)/tcpdump.pcap

Wiki: velodyne_driver (last edited 2019-01-28 18:52:55 by JoshuaWhitley)