Point Cloud Library (PCL)  1.8.1-dev
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
List of all members | Classes | Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Static Protected Attributes
pcl::HDLGrabber Class Reference

Grabber for the Velodyne High-Definition-Laser (HDL) More...

#include <pcl/io/hdl_grabber.h>

+ Inheritance diagram for pcl::HDLGrabber:

Classes

struct  HDLDataPacket
 
struct  HDLFiringData
 
struct  HDLLaserCorrection
 
struct  HDLLaserReturn
 

Public Types

typedef void( sig_cb_velodyne_hdl_scan_point_cloud_xyz )(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZ > > &, float, float)
 Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne. More...
 
typedef void( sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba )(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZRGBA > > &, float, float)
 Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne. More...
 
typedef
sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba 
sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb
 
typedef void( sig_cb_velodyne_hdl_scan_point_cloud_xyzi )(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZI > > &, float startAngle, float)
 Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne with the returned intensity. More...
 
typedef void( sig_cb_velodyne_hdl_sweep_point_cloud_xyz )(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZ > > &)
 Signal used for a 360 degree sweep Represents multiple corrected packets from the HDL Velodyne This signal is sent when the Velodyne passes angle "0". More...
 
typedef void( sig_cb_velodyne_hdl_sweep_point_cloud_xyzi )(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZI > > &)
 Signal used for a 360 degree sweep Represents multiple corrected packets from the HDL Velodyne with the returned intensity This signal is sent when the Velodyne passes angle "0". More...
 
typedef void( sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba )(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZRGBA > > &)
 Signal used for a 360 degree sweep Represents multiple corrected packets from the HDL Velodyne This signal is sent when the Velodyne passes angle "0". More...
 
typedef
sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba 
sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgb
 

Public Member Functions

 HDLGrabber (const std::string &correctionsFile="", const std::string &pcapFile="")
 Constructor taking an optional path to an HDL corrections file. More...
 
 HDLGrabber (const boost::asio::ip::address &ipAddress, const uint16_t port, const std::string &correctionsFile="")
 Constructor taking a specified IP/port and an optional path to an HDL corrections file. More...
 
virtual ~HDLGrabber () throw ()
 virtual Destructor inherited from the Grabber interface. More...
 
virtual void start ()
 Starts processing the Velodyne packets, either from the network or PCAP file. More...
 
virtual void stop ()
 Stops processing the Velodyne packets, either from the network or PCAP file. More...
 
virtual std::string getName () const
 Obtains the name of this I/O Grabber. More...
 
virtual bool isRunning () const
 Check if the grabber is still running. More...
 
virtual float getFramesPerSecond () const
 Returns the number of frames per second. More...
 
void filterPackets (const boost::asio::ip::address &ipAddress, const uint16_t port=443)
 Allows one to filter packets based on the SOURCE IP address and PORT This can be used, for instance, if multiple HDL LIDARs are on the same network. More...
 
void setLaserColorRGB (const pcl::RGB &color, const uint8_t laserNumber)
 Allows one to customize the colors used by each laser. More...
 
template<typename IterT >
void setLaserColorRGB (const IterT &begin, const IterT &end)
 Allows one to customize the colors used for each of the lasers. More...
 
void setMinimumDistanceThreshold (float &minThreshold)
 Any returns from the HDL with a distance less than this are discarded. More...
 
void setMaximumDistanceThreshold (float &maxThreshold)
 Any returns from the HDL with a distance greater than this are discarded. More...
 
float getMinimumDistanceThreshold ()
 Returns the current minimum distance threshold, in meters. More...
 
float getMaximumDistanceThreshold ()
 Returns the current maximum distance threshold, in meters. More...
 
virtual uint8_t getMaximumNumberOfLasers () const
 Returns the maximum number of lasers. More...
 
- Public Member Functions inherited from pcl::Grabber
 Grabber ()
 Constructor. More...
 
virtual ~Grabber () throw ()
 virtual destructor. More...
 
template<typename T >
boost::signals2::connection registerCallback (const boost::function< T > &callback)
 registers a callback function/method to a signal with the corresponding signature More...
 
template<typename T >
bool providesCallback () const
 indicates whether a signal with given parameter-type exists or not More...
 

Protected Types

enum  HDLBlock { BLOCK_0_TO_31 = 0xeeff, BLOCK_32_TO_63 = 0xddff }
 
typedef struct
pcl::HDLGrabber::HDLLaserReturn 
HDLLaserReturn
 

Protected Member Functions

void fireCurrentSweep ()
 
void fireCurrentScan (const uint16_t startAngle, const uint16_t endAngle)
 
void computeXYZI (pcl::PointXYZI &pointXYZI, uint16_t azimuth, HDLLaserReturn laserReturn, HDLLaserCorrection correction)
 
- Protected Member Functions inherited from pcl::Grabber
virtual void signalsChanged ()
 
template<typename T >
boost::signals2::signal< T > * find_signal () const
 
template<typename T >
int num_slots () const
 
template<typename T >
void disconnect_all_slots ()
 
template<typename T >
void block_signal ()
 
template<typename T >
void unblock_signal ()
 
void block_signals ()
 
void unblock_signals ()
 
template<typename T >
boost::signals2::signal< T > * createSignal ()
 

Protected Attributes

HDLLaserCorrection laser_corrections_ [HDL_MAX_NUM_LASERS]
 
uint16_t last_azimuth_
 
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZ > > 
current_scan_xyz_
 
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZ > > 
current_sweep_xyz_
 
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZI > > 
current_scan_xyzi_
 
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZI > > 
current_sweep_xyzi_
 
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZRGBA > > 
current_scan_xyzrgba_
 
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZRGBA > > 
current_sweep_xyzrgba_
 
boost::signals2::signal
< sig_cb_velodyne_hdl_sweep_point_cloud_xyz > * 
sweep_xyz_signal_
 
boost::signals2::signal
< sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba > * 
sweep_xyzrgba_signal_
 
boost::signals2::signal
< sig_cb_velodyne_hdl_sweep_point_cloud_xyzi > * 
sweep_xyzi_signal_
 
boost::signals2::signal
< sig_cb_velodyne_hdl_scan_point_cloud_xyz > * 
scan_xyz_signal_
 
boost::signals2::signal
< sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba > * 
scan_xyzrgba_signal_
 
boost::signals2::signal
< sig_cb_velodyne_hdl_scan_point_cloud_xyzi > * 
scan_xyzi_signal_
 
- Protected Attributes inherited from pcl::Grabber
std::map< std::string,
boost::signals2::signal_base * > 
signals_
 
std::map< std::string,
std::vector
< boost::signals2::connection > > 
connections_
 
std::map< std::string,
std::vector
< boost::signals2::shared_connection_block > > 
shared_connections_
 

Static Protected Attributes

static const uint16_t HDL_DATA_PORT = 2368
 
static const uint16_t HDL_NUM_ROT_ANGLES = 36001
 
static const uint8_t HDL_LASER_PER_FIRING = 32
 
static const uint8_t HDL_MAX_NUM_LASERS = 64
 
static const uint8_t HDL_FIRING_PER_PKT = 12
 

Detailed Description

Grabber for the Velodyne High-Definition-Laser (HDL)

Author
Keven Ring keven.nosp@m.@mit.nosp@m.re.or.nosp@m.g

Definition at line 60 of file hdl_grabber.h.

Member Typedef Documentation

typedef void( pcl::HDLGrabber::sig_cb_velodyne_hdl_scan_point_cloud_xyz)(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZ > > &, float, float)

Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne.

Definition at line 67 of file hdl_grabber.h.

typedef void( pcl::HDLGrabber::sig_cb_velodyne_hdl_scan_point_cloud_xyzi)(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZI > > &, float startAngle, float)

Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne with the returned intensity.

Definition at line 86 of file hdl_grabber.h.

Definition at line 80 of file hdl_grabber.h.

typedef void( pcl::HDLGrabber::sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba)(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZRGBA > > &, float, float)

Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne.

Each laser has a different RGB

Definition at line 75 of file hdl_grabber.h.

typedef void( pcl::HDLGrabber::sig_cb_velodyne_hdl_sweep_point_cloud_xyz)(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZ > > &)

Signal used for a 360 degree sweep Represents multiple corrected packets from the HDL Velodyne This signal is sent when the Velodyne passes angle "0".

Definition at line 95 of file hdl_grabber.h.

typedef void( pcl::HDLGrabber::sig_cb_velodyne_hdl_sweep_point_cloud_xyzi)(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZI > > &)

Signal used for a 360 degree sweep Represents multiple corrected packets from the HDL Velodyne with the returned intensity This signal is sent when the Velodyne passes angle "0".

Definition at line 102 of file hdl_grabber.h.

Definition at line 112 of file hdl_grabber.h.

typedef void( pcl::HDLGrabber::sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba)(const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZRGBA > > &)

Signal used for a 360 degree sweep Represents multiple corrected packets from the HDL Velodyne This signal is sent when the Velodyne passes angle "0".

Each laser has a different RGB

Definition at line 109 of file hdl_grabber.h.

Member Enumeration Documentation

enum pcl::HDLGrabber::HDLBlock
protected
Enumerator
BLOCK_0_TO_31 
BLOCK_32_TO_63 

Definition at line 221 of file hdl_grabber.h.

Constructor & Destructor Documentation

pcl::HDLGrabber::HDLGrabber ( const std::string &  correctionsFile = "",
const std::string &  pcapFile = "" 
)

Constructor taking an optional path to an HDL corrections file.

The Grabber will listen on the default IP/port for data packets [192.168.3.255/2368]

Parameters
[in]correctionsFilePath to a file which contains the correction parameters for the HDL. This parameter is mandatory for the HDL-64, optional for the HDL-32
[in]pcapFilePath to a file which contains previously captured data packets. This parameter is optional
pcl::HDLGrabber::HDLGrabber ( const boost::asio::ip::address &  ipAddress,
const uint16_t  port,
const std::string &  correctionsFile = "" 
)

Constructor taking a specified IP/port and an optional path to an HDL corrections file.

Parameters
[in]ipAddressIP Address that should be used to listen for HDL packets
[in]portUDP Port that should be used to listen for HDL packets
[in]correctionsFilePath to a file which contains the correction parameters for the HDL. This field is mandatory for the HDL-64, optional for the HDL-32
virtual pcl::HDLGrabber::~HDLGrabber ( )
throw (
)
virtual

virtual Destructor inherited from the Grabber interface.

It never throws.

Member Function Documentation

void pcl::HDLGrabber::computeXYZI ( pcl::PointXYZI pointXYZI,
uint16_t  azimuth,
HDLLaserReturn  laserReturn,
HDLLaserCorrection  correction 
)
protected
void pcl::HDLGrabber::filterPackets ( const boost::asio::ip::address &  ipAddress,
const uint16_t  port = 443 
)

Allows one to filter packets based on the SOURCE IP address and PORT This can be used, for instance, if multiple HDL LIDARs are on the same network.

void pcl::HDLGrabber::fireCurrentScan ( const uint16_t  startAngle,
const uint16_t  endAngle 
)
protected
void pcl::HDLGrabber::fireCurrentSweep ( )
protected
virtual float pcl::HDLGrabber::getFramesPerSecond ( ) const
virtual

Returns the number of frames per second.

Implements pcl::Grabber.

float pcl::HDLGrabber::getMaximumDistanceThreshold ( )

Returns the current maximum distance threshold, in meters.

virtual uint8_t pcl::HDLGrabber::getMaximumNumberOfLasers ( ) const
virtual

Returns the maximum number of lasers.

Reimplemented in pcl::VLPGrabber.

float pcl::HDLGrabber::getMinimumDistanceThreshold ( )

Returns the current minimum distance threshold, in meters.

virtual std::string pcl::HDLGrabber::getName ( ) const
virtual

Obtains the name of this I/O Grabber.

Returns
The name of the grabber

Implements pcl::Grabber.

Reimplemented in pcl::VLPGrabber.

virtual bool pcl::HDLGrabber::isRunning ( ) const
virtual

Check if the grabber is still running.

Returns
TRUE if the grabber is running, FALSE otherwise

Implements pcl::Grabber.

void pcl::HDLGrabber::setLaserColorRGB ( const pcl::RGB color,
const uint8_t  laserNumber 
)

Allows one to customize the colors used by each laser.

Parameters
[in]colorRGB color to set
[in]laserNumberNumber of laser to set color
template<typename IterT >
void pcl::HDLGrabber::setLaserColorRGB ( const IterT &  begin,
const IterT &  end 
)
inline

Allows one to customize the colors used for each of the lasers.

Parameters
[in]beginbegin iterator of RGB color array
[in]endend iterator of RGB color array

Definition at line 179 of file hdl_grabber.h.

void pcl::HDLGrabber::setMaximumDistanceThreshold ( float &  maxThreshold)

Any returns from the HDL with a distance greater than this are discarded.

This value is in meters Default: 10000.0

void pcl::HDLGrabber::setMinimumDistanceThreshold ( float &  minThreshold)

Any returns from the HDL with a distance less than this are discarded.

This value is in meters Default: 0.0

virtual void pcl::HDLGrabber::start ( )
virtual

Starts processing the Velodyne packets, either from the network or PCAP file.

Implements pcl::Grabber.

virtual void pcl::HDLGrabber::stop ( )
virtual

Stops processing the Velodyne packets, either from the network or PCAP file.

Implements pcl::Grabber.

Member Data Documentation

boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> > pcl::HDLGrabber::current_scan_xyz_
protected

Definition at line 264 of file hdl_grabber.h.

boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> > pcl::HDLGrabber::current_scan_xyzi_
protected

Definition at line 265 of file hdl_grabber.h.

boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGBA> > pcl::HDLGrabber::current_scan_xyzrgba_
protected

Definition at line 266 of file hdl_grabber.h.

boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> > pcl::HDLGrabber::current_sweep_xyz_
protected

Definition at line 264 of file hdl_grabber.h.

boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> > pcl::HDLGrabber::current_sweep_xyzi_
protected

Definition at line 265 of file hdl_grabber.h.

boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGBA> > pcl::HDLGrabber::current_sweep_xyzrgba_
protected

Definition at line 266 of file hdl_grabber.h.

const uint16_t pcl::HDLGrabber::HDL_DATA_PORT = 2368
staticprotected

Definition at line 215 of file hdl_grabber.h.

const uint8_t pcl::HDLGrabber::HDL_FIRING_PER_PKT = 12
staticprotected

Definition at line 219 of file hdl_grabber.h.

const uint8_t pcl::HDLGrabber::HDL_LASER_PER_FIRING = 32
staticprotected

Definition at line 217 of file hdl_grabber.h.

const uint8_t pcl::HDLGrabber::HDL_MAX_NUM_LASERS = 64
staticprotected

Definition at line 218 of file hdl_grabber.h.

const uint16_t pcl::HDLGrabber::HDL_NUM_ROT_ANGLES = 36001
staticprotected

Definition at line 216 of file hdl_grabber.h.

HDLLaserCorrection pcl::HDLGrabber::laser_corrections_[HDL_MAX_NUM_LASERS]
protected

Definition at line 262 of file hdl_grabber.h.

uint16_t pcl::HDLGrabber::last_azimuth_
protected

Definition at line 263 of file hdl_grabber.h.

boost::signals2::signal<sig_cb_velodyne_hdl_scan_point_cloud_xyz>* pcl::HDLGrabber::scan_xyz_signal_
protected

Definition at line 270 of file hdl_grabber.h.

boost::signals2::signal<sig_cb_velodyne_hdl_scan_point_cloud_xyzi>* pcl::HDLGrabber::scan_xyzi_signal_
protected

Definition at line 272 of file hdl_grabber.h.

boost::signals2::signal<sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba>* pcl::HDLGrabber::scan_xyzrgba_signal_
protected

Definition at line 271 of file hdl_grabber.h.

boost::signals2::signal<sig_cb_velodyne_hdl_sweep_point_cloud_xyz>* pcl::HDLGrabber::sweep_xyz_signal_
protected

Definition at line 267 of file hdl_grabber.h.

boost::signals2::signal<sig_cb_velodyne_hdl_sweep_point_cloud_xyzi>* pcl::HDLGrabber::sweep_xyzi_signal_
protected

Definition at line 269 of file hdl_grabber.h.

boost::signals2::signal<sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba>* pcl::HDLGrabber::sweep_xyzrgba_signal_
protected

Definition at line 268 of file hdl_grabber.h.


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