Classes | Public Member Functions | Private Member Functions | Private Attributes
velodyne_rawdata::RawData Class Reference

Velodyne data conversion class. More...

#include <rawdata.h>

List of all members.

Classes

struct  Config

Public Member Functions

 RawData ()
int scansPerPacket () const
void setParameters (double min_range, double max_range, double view_direction, double view_width)
boost::optional
< velodyne_pointcloud::Calibration
setup (ros::NodeHandle private_nh)
 Set up for data processing.
int setupOffline (std::string calibration_file, 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.
void unpack (const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data)
 convert raw packet to point cloud
 ~RawData ()

Private Member Functions

void unpack_vlp16 (const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data)
 convert raw VLP16 packet to point cloud

Private Attributes

velodyne_pointcloud::Calibration calibration_
Config config_
float cos_rot_table_ [ROTATION_MAX_UNITS]
float sin_rot_table_ [ROTATION_MAX_UNITS]

Detailed Description

Velodyne data conversion class.

Definition at line 132 of file rawdata.h.


Constructor & Destructor Documentation

Definition at line 47 of file rawdata.cc.

Definition at line 136 of file rawdata.h.


Member Function Documentation

Definition at line 78 of file rawdata.cc.

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 50 of file rawdata.cc.

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 91 of file rawdata.cc.

int velodyne_rawdata::RawData::setupOffline ( std::string  calibration_file,
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
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 125 of file rawdata.cc.

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

convert raw packet to point cloud

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

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 160 of file rawdata.cc.

void velodyne_rawdata::RawData::unpack_vlp16 ( const velodyne_msgs::VelodynePacket &  pkt,
DataContainerBase data 
) [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 321 of file rawdata.cc.


Member Data Documentation

Calibration file

Definition at line 190 of file rawdata.h.

Definition at line 185 of file rawdata.h.

Definition at line 192 of file rawdata.h.

Definition at line 191 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 Wed Jul 3 2019 19:32:23