class mrpt::hwdrivers::CVelodyneScanner

A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Linux and Windows.

(Using this class requires WinPCap as a run-time dependency in Windows). It can receive data from real devices via an Ethernet connection or parse a WireShark PCAP file for offline processing. The choice of online vs. offline operation is taken upon calling initialize() : if a PCAP input file has been defined, offline operation takes place and network is not listened for incomming packets.

Parsing dual return scans requires a VLP-16 with firmware version 3.0.23 or newer. While converting the scan into a point cloud in mrpt::obs::CObservationVelodyneScan you can select whether to keep the strongest, the last or both laser returns.

XML calibration files are not mandatory for VLP-16 and HDL-32, but they are for HDL-64.

Grabbing live data (as a user)

Grabbing live data (programmatically)

See the source code of the example application [MRPT]/apps/velodyne-view (velodyne-view web page) for more details.

Playing back a PCAP file:

It is common to save Velodyne datasets as Wireshark’s PCAP files. These files can be played back with tools like bittwist, which emit all UDP packets in the PCAP log. Then, use this class to receive the packets as if they come from the real sensor.

Alternatively, if MRPT is linked against libpcap, this class can directly parse a PCAP file to simulate reading from a device offline. See method setPCAPInputFile() and config file parameter ``

To compile with PCAP support: In Debian/Ubuntu, install libpcap-dev. In Windows, install WinPCap developer packages + the regular WinPCap driver.

Configuration and usage:

Data is returned as observations of type:

Configuration includes setting the device IP (optional) and sensor model (mandatory only if a calibration file is not provided). These parameters can be set programmatically (see methods of this class), or via a configuration file with CGenericSensor::loadConfig() (see example config file section below).

About timestamps:

Each gathered observation of type mrpt::obs::CObservationVelodyneScan is populated with two timestamps, one for the local PC timestamp and, if available, another one for the GPS-stamped timestamp. Refer to the observation docs for details.

Format of parameters for loading from a .ini file

 PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS:
-------------------------------------------------------
  [supplied_section_name]
  # ---- Sensor description ----
  #calibration_file         = PUT_HERE_FULL_PATH_TO_CALIB_FILE.xml      //
Optional but recommended: put here your vendor-provided calibration file
  model                    = VLP16      // Can be any of: `VLP16`, `HDL32`,
`HDL64`  (It is used to load default calibration file. Parameter not required
if `calibration_file` is provided.
  #pos_packets_min_period  = 0.5        // (Default=0.5 seconds) Minimum
period to leave between reporting position packets. Used to decimate the
large number of packets of this type.
  # How long to wait, after loss of GPS signal, to report timestamps as "not
based on satellite time". 30 secs, with typical velodyne clock drifts, means
a ~1.7 ms typical drift.
  #pos_packets_timing_timeout = 30      // (Default=30 seconds)
  # ---- Online operation ----

  # IP address of the device. UDP packets from other IPs will be ignored.
Leave commented or blank
  # if only one scanner is present (no IP filtering)
  #device_ip       = XXX.XXX.XXX.XXX

  #rpm             = 600        // Sensor RPM (Default: unchanged). Requires
setting `device_ip`
  #return_type     = STRONGEST  // Any of: 'STRONGEST', 'LAST', 'DUAL'
(Default: unchanged). Requires setting `device_ip`

  # ---- Offline operation ----
  # If uncommented, this class will read from the PCAP instead of connecting
and listeling
  # for online network packets.
  # pcap_input     = PUT_FULL_PATH_TO_PCAP_LOG_FILE.pcap
  # pcap_read_once = false   // Do not loop
  # pcap_read_fast = false    // fast forward skipping non-velodyne packets
  # pcap_read_full_scan_delay_ms = 100 // Used to simulate a reasonable
number of full scans / second
  # pcap_repeat_delay = 0.0   // seconds

  # ---- Save to PCAP file ----
  # If uncommented, a PCAP file named
`[pcap_output_prefix]_[DATE_TIME].pcap` will be
  # written simultaneously to the normal operation of this class.
  # pcap_output     = velodyne_log

  # 3D position of the sensor on the vehicle:
  pose_x     = 0    // 3D position (meters)
  pose_y     = 0
  pose_z     = 0
  pose_yaw   = 0    // 3D orientation (degrees)
  pose_pitch = 0
  pose_roll  = 0