Classes | Typedefs | Variables
velodyne_rawdata Namespace Reference

Classes

struct  raw_block
 Raw Velodyne data block. More...
struct  raw_packet
 Raw Velodyne packet. More...
class  RawData
 Velodyne data conversion class. More...
union  two_bytes

Typedefs

typedef struct
velodyne_rawdata::raw_block 
raw_block_t
 Raw Velodyne data block.
typedef struct
velodyne_rawdata::raw_packet 
raw_packet_t
 Raw Velodyne packet.
typedef
velodyne_pointcloud::PointXYZIR 
VPoint
typedef pcl::PointCloud< VPointVPointCloud

Variables

static const int BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE)
static const int BLOCKS_PER_PACKET = 12
static const float DISTANCE_MAX = 130.0f
static const float DISTANCE_MAX_UNITS
static const float DISTANCE_RESOLUTION = 0.002f
static const uint16_t LOWER_BANK = 0xddff
static const int PACKET_SIZE = 1206
static const int PACKET_STATUS_SIZE = 4
static const int RAW_SCAN_SIZE = 3
static const uint16_t ROTATION_MAX_UNITS = 36000
static const float ROTATION_RESOLUTION = 0.01f
static const int SCANS_PER_BLOCK = 32
static const int SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET)
static const int SIZE_BLOCK = 100
static const uint16_t UPPER_BANK = 0xeeff
static const int VLP16_BLOCK_TDURATION = 110.592
static const int VLP16_DSR_TOFFSET = 2.304
static const int VLP16_FIRING_TOFFSET = 55.296
static const int VLP16_FIRINGS_PER_BLOCK = 2
static const int VLP16_SCANS_PER_FIRING = 16

Typedef Documentation

Raw Velodyne data block.

Each block contains data from either the upper or lower laser bank. The device returns three times as many upper bank blocks.

use stdint.h types, so things work with both 64 and 32-bit machines

Raw Velodyne packet.

revolution is described in the device manual as incrementing (mod 65536) for each physical turn of the device. Our device seems to alternate between two different values every third packet. One value increases, the other decreases.

Todo:
figure out if revolution is only present for one of the two types of status fields

status has either a temperature encoding or the microcode level

Definition at line 38 of file rawdata.h.

Definition at line 39 of file rawdata.h.


Variable Documentation

Definition at line 47 of file rawdata.h.

const int velodyne_rawdata::BLOCKS_PER_PACKET = 12 [static]

Definition at line 96 of file rawdata.h.

const float velodyne_rawdata::DISTANCE_MAX = 130.0f [static]

According to Bruce Hall DISTANCE_MAX is 65.0, but we noticed valid packets with readings up to 130.0. meters

Definition at line 54 of file rawdata.h.

Initial value:

Definition at line 56 of file rawdata.h.

const float velodyne_rawdata::DISTANCE_RESOLUTION = 0.002f [static]

meters

Definition at line 55 of file rawdata.h.

const uint16_t velodyne_rawdata::LOWER_BANK = 0xddff [static]

Definition at line 59 of file rawdata.h.

const int velodyne_rawdata::PACKET_SIZE = 1206 [static]

Definition at line 95 of file rawdata.h.

const int velodyne_rawdata::PACKET_STATUS_SIZE = 4 [static]

Definition at line 97 of file rawdata.h.

const int velodyne_rawdata::RAW_SCAN_SIZE = 3 [static]

Definition at line 45 of file rawdata.h.

const uint16_t velodyne_rawdata::ROTATION_MAX_UNITS = 36000 [static]

hundredths of degrees

Definition at line 50 of file rawdata.h.

const float velodyne_rawdata::ROTATION_RESOLUTION = 0.01f [static]

degrees

Definition at line 49 of file rawdata.h.

const int velodyne_rawdata::SCANS_PER_BLOCK = 32 [static]

Definition at line 46 of file rawdata.h.

Definition at line 98 of file rawdata.h.

const int velodyne_rawdata::SIZE_BLOCK = 100 [static]

Raw Velodyne packet constants and structures.

Definition at line 44 of file rawdata.h.

const uint16_t velodyne_rawdata::UPPER_BANK = 0xeeff [static]

Definition at line 58 of file rawdata.h.

const int velodyne_rawdata::VLP16_BLOCK_TDURATION = 110.592 [static]

Definition at line 65 of file rawdata.h.

const int velodyne_rawdata::VLP16_DSR_TOFFSET = 2.304 [static]

Definition at line 66 of file rawdata.h.

const int velodyne_rawdata::VLP16_FIRING_TOFFSET = 55.296 [static]

Definition at line 67 of file rawdata.h.

Special Defines for VLP16 support

Definition at line 63 of file rawdata.h.

Definition at line 64 of file rawdata.h.



velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera
autogenerated on Thu Aug 27 2015 15:37:05