Classes | Typedefs | Functions | Variables
velodyne_rawdata Namespace Reference

Classes

class  DataContainerBase
 
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. More...
 
typedef struct velodyne_rawdata::raw_packet raw_packet_t
 Raw Velodyne packet. More...
 

Functions

float SQR (float val)
 

Variables

static const int BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE)
 
static const int BLOCKS_PER_PACKET = 12
 
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 = 36000u
 
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 float VLP16_BLOCK_TDURATION = 110.592f
 
static const float VLP16_DSR_TOFFSET = 2.304f
 
static const float VLP16_FIRING_TOFFSET = 55.296f
 
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

Function Documentation

float velodyne_rawdata::SQR ( float  val)
inline

Definition at line 41 of file rawdata.cc.

Variable Documentation

const int velodyne_rawdata::BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE)
static

Definition at line 65 of file rawdata.h.

const int velodyne_rawdata::BLOCKS_PER_PACKET = 12
static

Definition at line 108 of file rawdata.h.

const uint16_t velodyne_rawdata::LOWER_BANK = 0xddff
static

Definition at line 72 of file rawdata.h.

const int velodyne_rawdata::PACKET_SIZE = 1206
static

Definition at line 107 of file rawdata.h.

const int velodyne_rawdata::PACKET_STATUS_SIZE = 4
static

Definition at line 109 of file rawdata.h.

const int velodyne_rawdata::RAW_SCAN_SIZE = 3
static

Definition at line 63 of file rawdata.h.

const uint16_t velodyne_rawdata::ROTATION_MAX_UNITS = 36000u
static

Definition at line 68 of file rawdata.h.

const float velodyne_rawdata::ROTATION_RESOLUTION = 0.01f
static

Definition at line 67 of file rawdata.h.

const int velodyne_rawdata::SCANS_PER_BLOCK = 32
static

Definition at line 64 of file rawdata.h.

const int velodyne_rawdata::SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET)
static

Definition at line 110 of file rawdata.h.

const int velodyne_rawdata::SIZE_BLOCK = 100
static

Raw Velodyne packet constants and structures.

Definition at line 62 of file rawdata.h.

const uint16_t velodyne_rawdata::UPPER_BANK = 0xeeff
static
Todo:
make this work for both big and little-endian machines

Definition at line 71 of file rawdata.h.

const float velodyne_rawdata::VLP16_BLOCK_TDURATION = 110.592f
static

Definition at line 77 of file rawdata.h.

const float velodyne_rawdata::VLP16_DSR_TOFFSET = 2.304f
static

Definition at line 78 of file rawdata.h.

const float velodyne_rawdata::VLP16_FIRING_TOFFSET = 55.296f
static

Definition at line 79 of file rawdata.h.

const int velodyne_rawdata::VLP16_FIRINGS_PER_BLOCK = 2
static

Special Defines for VLP16 support

Definition at line 75 of file rawdata.h.

const int velodyne_rawdata::VLP16_SCANS_PER_FIRING = 16
static

Definition at line 76 of file rawdata.h.



velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Sep 6 2020 03:25:30