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... | |
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 struct Velodyne::raw_packet | raw_packet_t |
Raw Velodyne packet. | |
typedef boost::function< void(const std::vector< laserscan_t > &scan, ros::Time time, const std::string &frame_id)> | scanCallback |
type of callback function to receive laser scans | |
typedef boost::function< void(const std::vector< laserscan_xyz_t > &scan, ros::Time stamp, const std::string &frame_id)> | xyzCallback |
type of callback function to receive XYZ laser scans | |
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 | 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 const uint16_t | UPPER_BANK = 0xeeff |
typedef struct Velodyne::laserscan Velodyne::laserscan_t |
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)
typedef struct Velodyne::laserscan_xyz Velodyne::laserscan_xyz_t |
a single laser scan in XYZ format
Data are in the Velodyne's frame of reference.
typedef struct Velodyne::raw_block Velodyne::raw_block_t |
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 struct Velodyne::raw_packet Velodyne::raw_packet_t |
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.
status has either a temperature encoding or the microcode level
typedef boost::function<void(const std::vector<laserscan_t> &scan, ros::Time time, const std::string &frame_id)> Velodyne::scanCallback |
type of callback function to receive laser scans
scan | vector containing the laser scans for a single packet | |
time | ROS time stamp of packet | |
frame_id | ROS frame ID of packet |
Definition at line 54 of file data_scans.h.
typedef boost::function<void(const std::vector<laserscan_xyz_t> &scan, ros::Time stamp, const std::string &frame_id)> Velodyne::xyzCallback |
type of callback function to receive XYZ laser scans
scan | vector containing the XYZ scans for a single packet | |
stamp | ROS time stamp of packet | |
frame_id | ROS frame ID of packet |
Definition at line 49 of file data_xyz.h.
const int Velodyne::BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE) [static] |
Definition at line 42 of file data_base.h.
const int Velodyne::BLOCKS_PER_PACKET = 12 [static] |
Definition at line 82 of file data_base.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 49 of file data_base.h.
const float Velodyne::DISTANCE_MAX_UNITS [static] |
(DISTANCE_MAX / DISTANCE_RESOLUTION + 1.0)
Definition at line 51 of file data_base.h.
const float Velodyne::DISTANCE_RESOLUTION = 0.002f [static] |
meters
Definition at line 50 of file data_base.h.
const uint16_t Velodyne::LOWER_BANK = 0xddff [static] |
Definition at line 54 of file data_base.h.
const int Velodyne::PACKET_SIZE = 1206 [static] |
Definition at line 81 of file data_base.h.
const int Velodyne::PACKET_STATUS_SIZE = 4 [static] |
Definition at line 83 of file data_base.h.
const int Velodyne::PACKETS_PER_REV = 260 [static] |
Definition at line 85 of file data_base.h.
const int Velodyne::RAW_SCAN_SIZE = 3 [static] |
Definition at line 40 of file data_base.h.
const float Velodyne::ROTATION_MAX_UNITS = 36000 [static] |
hundredths of degrees
Definition at line 45 of file data_base.h.
const float Velodyne::ROTATION_RESOLUTION = 0.01f [static] |
degrees
Definition at line 44 of file data_base.h.
const int Velodyne::SCANS_PER_BLOCK = 32 [static] |
Definition at line 41 of file data_base.h.
const int Velodyne::SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET) [static] |
Definition at line 84 of file data_base.h.
const int Velodyne::SCANS_PER_REV = (SCANS_PER_PACKET * PACKETS_PER_REV) [static] |
Definition at line 86 of file data_base.h.
const int Velodyne::SIZE_BLOCK = 100 [static] |
Raw Velodyne packet constants and structures.
Definition at line 39 of file data_base.h.
const uint16_t Velodyne::UPPER_BANK = 0xeeff [static] |
Definition at line 53 of file data_base.h.