velodyne Namespace Reference

Classes

struct  correction_angles
 Correction angles for a specific HDL-64E device. More...
class  Data
 Base Velodyne data class -- not used directly. More...
class  DataScans
 Convert Velodyne raw input to laserscans format. More...
class  DataXYZ
 Convert Velodyne raw input to XYZ format. More...
class  Input
class  InputPCAP
 Velodyne input from PCAP dump file. More...
class  InputSocket
 Live Velodyne input from socket. More...
struct  laserscan
 A single laser scan in Velodyne's frame of reference. More...
struct  laserscan_xyz
 a single laser scan in XYZ format More...
struct  raw_block
 Raw Velodyne data block. More...
struct  raw_packet
 Raw Velodyne packet. More...
union  two_bytes

Typedefs

typedef struct velodyne::laserscan laserscan_t
 A single laser scan in Velodyne's frame of reference.
typedef struct
velodyne::laserscan_xyz 
laserscan_xyz_t
 a single laser scan in XYZ format
typedef struct velodyne::raw_block raw_block_t
 Raw Velodyne data block.
typedef void(* raw_callback_t )(const raw_packet_t *raw, size_t npackets)
 type of callback function to receive raw data for one revolution.
typedef struct velodyne::raw_packet raw_packet_t
 Raw Velodyne packet.
typedef boost::function< void(const
std::vector< laserscan_t > &)> 
scanCallback
typedef void(* scans_callback_t )(const std::vector< laserscan_t > &scan)
 type of callback function to receive laser scans
typedef void(* xyz_callback_t )(const std::vector< laserscan_xyz_t > &scan)
 type of callback function to receive XYZ laser scans
typedef boost::function< void(const
std::vector< laserscan_xyz_t > &)> 
xyzCallback

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
const int LASER_RING [N_LASERS]
 convert laser number to ring sequence (inverse of LASER_SEQUENCE)
const int LASER_SEQUENCE [N_LASERS]
 ring sequence for device laser numbers
static const uint16_t LOWER_BANK = 0xddff
const int N_LASERS = 64
 number of lasers
static const int PACKET_SIZE = 1206
static const int PACKET_STATUS_SIZE = 4
static const int PACKETS_PER_REV = 260
static const int RAW_SCAN_SIZE = 3
static const float 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 SCANS_PER_REV = (SCANS_PER_PACKET * PACKETS_PER_REV)
static const int SIZE_BLOCK = 100
static uint16_t UDP_PORT_NUMBER = 2368
static const uint16_t UPPER_BANK = 0xeeff

Typedef Documentation

A single laser scan in Velodyne's frame of reference.

pitch is relative to the plane of the unit (in its frame of reference): positive is above, negative is below

heading is relative to the front of the unit (the outlet is the back): positive is clockwise (yaw)

a single laser scan in XYZ format

Data are in the Velodyne's frame of reference.

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

typedef void(* velodyne::raw_callback_t)(const raw_packet_t *raw, size_t npackets)

type of callback function to receive raw data for one revolution.

Parameters:
raw -> buffer containing raw packet contents
npackets number of packets in the buffer

Use getMsgHeader() to access the ROS message header containing time stamp, sequence number, and frame ID.

Definition at line 135 of file data.h.

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

typedef boost::function<void(const std::vector<laserscan_t> &)> velodyne::scanCallback

Definition at line 317 of file data.h.

typedef void(* velodyne::scans_callback_t)(const std::vector< laserscan_t > &scan)

type of callback function to receive laser scans

Parameters:
scan -> vector containing the laser scans for a complete revolution in Velodyne frame of reference.

Use getMsgHeader() to access the ROS message header containing time stamp, sequence number, and frame ID.

Definition at line 316 of file data.h.

typedef void(* velodyne::xyz_callback_t)(const std::vector< laserscan_xyz_t > &scan)

type of callback function to receive XYZ laser scans

Parameters:
scan -> vector containing the laser scans for a complete revolution in XYZ format using Velodyne frame of reference.

Use getMsgHeader() to access the ROS message header containing time stamp, sequence number, and frame ID.

Definition at line 403 of file data.h.

typedef boost::function<void(const std::vector<laserscan_xyz_t> &)> velodyne::xyzCallback

Definition at line 404 of file data.h.


Variable Documentation

Definition at line 53 of file data.h.

const int velodyne::BLOCKS_PER_PACKET = 12 [static]

Definition at line 93 of file data.h.

const float velodyne::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 60 of file data.h.

const float velodyne::DISTANCE_MAX_UNITS [static]
Initial value:

Definition at line 62 of file data.h.

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

meters

Definition at line 61 of file data.h.

Initial value:
    {
       4,  5, 26, 27,  6,  7,  0,  1,
       8,  9,  2,  3, 16, 17, 10, 11,
      18, 19, 12, 13, 20, 21, 14, 15,
      28, 29, 22, 23, 30, 31, 24, 25,
      36, 37, 58, 59, 38, 39, 32, 33,
      40, 41, 34, 35, 48, 49, 42, 43,
      50, 51, 44, 45, 52, 53, 46, 47,
      60, 61, 54, 55, 62, 63, 56, 57
    }

convert laser number to ring sequence (inverse of LASER_SEQUENCE)

Definition at line 40 of file ring_sequence.h.

Initial value:
    {
      6,  7, 10, 11,  0,  1,  4,  5,
      8,  9, 14, 15, 18, 19, 22, 23,
     12, 13, 16, 17, 20, 21, 26, 27,
     30, 31,  2,  3, 24, 25, 28, 29,
     38, 39, 42, 43, 32, 33, 36, 37,
     40, 41, 46, 47, 50, 51, 54, 55,
     44, 45, 48, 49, 52, 53, 58, 59,
     62, 63, 34, 35, 56, 57, 60, 61
    }

ring sequence for device laser numbers

Definition at line 27 of file ring_sequence.h.

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

Definition at line 65 of file data.h.

const int velodyne::N_LASERS = 64

number of lasers

Definition at line 24 of file ring_sequence.h.

const int velodyne::PACKET_SIZE = 1206 [static]

Definition at line 92 of file data.h.

const int velodyne::PACKET_STATUS_SIZE = 4 [static]

Definition at line 94 of file data.h.

const int velodyne::PACKETS_PER_REV = 260 [static]

Definition at line 96 of file data.h.

const int velodyne::RAW_SCAN_SIZE = 3 [static]

Definition at line 51 of file data.h.

const float velodyne::ROTATION_MAX_UNITS = 36000 [static]

hundredths of degrees

Definition at line 56 of file data.h.

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

degrees

Definition at line 55 of file data.h.

const int velodyne::SCANS_PER_BLOCK = 32 [static]

Definition at line 52 of file data.h.

Definition at line 95 of file data.h.

Definition at line 97 of file data.h.

const int velodyne::SIZE_BLOCK = 100 [static]

Raw Velodyne packet constants and structures.

Definition at line 50 of file data.h.

uint16_t velodyne::UDP_PORT_NUMBER = 2368 [static]

Definition at line 46 of file input.h.

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

Definition at line 64 of file data.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerator Defines


velodyne_common
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Fri Jan 11 10:05:57 2013