Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
velodyne_rawdata::RawData Class Reference

Velodyne data conversion class. More...

#include <rawdata.h>

Classes

struct  Config
 

Public Member Functions

bool loadCalibration ()
 
 RawData ()
 
int scansPerPacket () const
 
void setParameters (double min_range, double max_range, double view_direction, double view_width)
 
boost::optional< velodyne_pointcloud::Calibrationsetup (ros::NodeHandle private_nh)
 Set up for data processing. More...
 
void setupAzimuthCache ()
 
int setupOffline (std::string calibration_file, std::string model, double max_range_, double min_range_)
 Set up for data processing offline. Performs the same initialization as in setup, in the abscence of a ros::NodeHandle. this method is useful if unpacking data directly from bag files, without passing through a communication overhead. More...
 
void setupSinCosCache ()
 
void unpack (const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
 convert raw packet to point cloud More...
 
 ~RawData ()
 

Private Member Functions

bool buildTimings ()
 setup per-point timing offsets More...
 
bool pointInRange (float range)
 
void unpack_vlp16 (const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
 convert raw VLP16 packet to point cloud More...
 
void unpack_vls128 (const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
 convert raw VLS128 packet to point cloud More...
 

Private Attributes

velodyne_pointcloud::Calibration calibration_
 
Config config_
 
float cos_rot_table_ [ROTATION_MAX_UNITS]
 
float sin_rot_table_ [ROTATION_MAX_UNITS]
 
std::vector< std::vector< float > > timing_offsets
 
float vls_128_laser_azimuth_cache [16]
 

Detailed Description

Velodyne data conversion class.

Definition at line 148 of file rawdata.h.

Constructor & Destructor Documentation

◆ RawData()

velodyne_rawdata::RawData::RawData ( )

Definition at line 49 of file rawdata.cc.

◆ ~RawData()

velodyne_rawdata::RawData::~RawData ( )
inline

Definition at line 152 of file rawdata.h.

Member Function Documentation

◆ buildTimings()

bool velodyne_rawdata::RawData::buildTimings ( )
private

setup per-point timing offsets

Runs during initialization and determines the firing time for each point in the scan

NOTE: Does not support all sensors yet (vlp16, vlp32, and hdl32 are currently supported)

Build a timing table for each block/firing. Stores in timing_offsets vector

Definition at line 95 of file rawdata.cc.

◆ loadCalibration()

bool velodyne_rawdata::RawData::loadCalibration ( )

Definition at line 284 of file rawdata.cc.

◆ pointInRange()

bool velodyne_rawdata::RawData::pointInRange ( float  range)
inlineprivate

in-line test whether a point is in range

Definition at line 241 of file rawdata.h.

◆ scansPerPacket()

int velodyne_rawdata::RawData::scansPerPacket ( ) const

Definition at line 80 of file rawdata.cc.

◆ setParameters()

void velodyne_rawdata::RawData::setParameters ( double  min_range,
double  max_range,
double  view_direction,
double  view_width 
)

Update parameters: conversions and update

Definition at line 52 of file rawdata.cc.

◆ setup()

boost::optional< velodyne_pointcloud::Calibration > velodyne_rawdata::RawData::setup ( ros::NodeHandle  private_nh)

Set up for data processing.

Perform initializations needed before data processing can begin:

  • read device-specific angles calibration
Parameters
private_nhprivate node handle for ROS parameters
Returns
an optional calibration

Set up for on-line operation.

Definition at line 220 of file rawdata.cc.

◆ setupAzimuthCache()

void velodyne_rawdata::RawData::setupAzimuthCache ( )

Definition at line 311 of file rawdata.cc.

◆ setupOffline()

int velodyne_rawdata::RawData::setupOffline ( std::string  calibration_file,
std::string  model,
double  max_range_,
double  min_range_ 
)

Set up for data processing offline. Performs the same initialization as in setup, in the abscence of a ros::NodeHandle. this method is useful if unpacking data directly from bag files, without passing through a communication overhead.

Parameters
calibration_filepath to the calibration file
modelsensor model type
max_range_cutoff for maximum range
min_range_cutoff for minimum range
Returns
0 if successful; errno value for failure

Set up for offline operation

Definition at line 256 of file rawdata.cc.

◆ setupSinCosCache()

void velodyne_rawdata::RawData::setupSinCosCache ( )

Definition at line 294 of file rawdata.cc.

◆ unpack()

void velodyne_rawdata::RawData::unpack ( const velodyne_msgs::VelodynePacket &  pkt,
DataContainerBase data,
const ros::Time scan_start_time 
)

convert raw packet to point cloud

Parameters
pktraw packet to unpack
pcshared pointer to point cloud (points are appended)

special parsing for the VLS128

special parsing for the VLP16

Position Calculation

the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.

the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.

the expression wiht '-' is proved to be better than the one with '+'

the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.

the new term of 'vert_offset * cos_vert_angle' was added to the expression due to the mathemathical model we used.

Use standard ROS coordinate system (right-hand rule)

Intensity Calculation

Definition at line 330 of file rawdata.cc.

◆ unpack_vlp16()

void velodyne_rawdata::RawData::unpack_vlp16 ( const velodyne_msgs::VelodynePacket &  pkt,
DataContainerBase data,
const ros::Time scan_start_time 
)
private

convert raw VLP16 packet to point cloud

add private function to handle the VLP16

Parameters
pktraw packet to unpack
pcshared pointer to point cloud (points are appended)

Position Calculation

correct for the laser rotation as a function of timing during the firings

the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.

the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.

the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.

the new term of 'vert_offset * cos_vert_angle' was added to the expression due to the mathemathical model we used.

Use standard ROS coordinate system (right-hand rule)

Intensity Calculation

Definition at line 648 of file rawdata.cc.

◆ unpack_vls128()

void velodyne_rawdata::RawData::unpack_vls128 ( const velodyne_msgs::VelodynePacket &  pkt,
DataContainerBase data,
const ros::Time scan_start_time 
)
private

convert raw VLS128 packet to point cloud

Parameters
pktraw packet to unpack
pcshared pointer to point cloud (points are appended)

Definition at line 509 of file rawdata.cc.

Member Data Documentation

◆ calibration_

velodyne_pointcloud::Calibration velodyne_rawdata::RawData::calibration_
private

Calibration file

Definition at line 215 of file rawdata.h.

◆ config_

Config velodyne_rawdata::RawData::config_
private

Definition at line 210 of file rawdata.h.

◆ cos_rot_table_

float velodyne_rawdata::RawData::cos_rot_table_[ROTATION_MAX_UNITS]
private

Definition at line 217 of file rawdata.h.

◆ sin_rot_table_

float velodyne_rawdata::RawData::sin_rot_table_[ROTATION_MAX_UNITS]
private

Definition at line 216 of file rawdata.h.

◆ timing_offsets

std::vector< std::vector<float> > velodyne_rawdata::RawData::timing_offsets
private

Definition at line 223 of file rawdata.h.

◆ vls_128_laser_azimuth_cache

float velodyne_rawdata::RawData::vls_128_laser_azimuth_cache[16]
private

Definition at line 220 of file rawdata.h.


The documentation for this class was generated from the following files:


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Fri Aug 2 2024 08:46:25