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

Grabber for the Velodyne LiDAR (VLP), based on the Velodyne High Definition Laser (HDL) More...

#include <pcl/io/vlp_grabber.h>

+ Inheritance diagram for pcl::VLPGrabber:

Public Member Functions

 VLPGrabber (const std::string &pcapFile="")
 Constructor taking an optional path to an vlp corrections file. More...
 
 VLPGrabber (const boost::asio::ip::address &ipAddress, const uint16_t port)
 Constructor taking a specified IP/port. More...
 
virtual ~VLPGrabber () throw ()
 virtual Destructor inherited from the Grabber interface. More...
 
virtual std::string getName () const
 Obtains the name of this I/O Grabber. 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...
 
virtual uint8_t getMaximumNumberOfLasers () const
 Returns the maximum number of lasers. More...
 
- Public Member Functions inherited from pcl::HDLGrabber
 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 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...
 
- 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...
 

Static Protected Attributes

static const uint8_t VLP_MAX_NUM_LASERS = 16
 
static const uint8_t VLP_DUAL_MODE = 0x39
 
- Static Protected Attributes inherited from pcl::HDLGrabber
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
 

Additional Inherited Members

- Public Types inherited from pcl::HDLGrabber
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
 
- Protected Types inherited from pcl::HDLGrabber
enum  HDLBlock { BLOCK_0_TO_31 = 0xeeff, BLOCK_32_TO_63 = 0xddff }
 
typedef struct
pcl::HDLGrabber::HDLLaserReturn 
HDLLaserReturn
 
- Protected Member Functions inherited from pcl::HDLGrabber
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 inherited from pcl::HDLGrabber
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_
 

Detailed Description

Grabber for the Velodyne LiDAR (VLP), based on the Velodyne High Definition Laser (HDL)

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

Definition at line 58 of file vlp_grabber.h.

Constructor & Destructor Documentation

pcl::VLPGrabber::VLPGrabber ( const std::string &  pcapFile = "")

Constructor taking an optional path to an vlp corrections file.

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

Parameters
[in]pcapFilePath to a file which contains previously captured data packets. This parameter is optional
pcl::VLPGrabber::VLPGrabber ( const boost::asio::ip::address &  ipAddress,
const uint16_t  port 
)

Constructor taking a specified IP/port.

Parameters
[in]ipAddressIP Address that should be used to listen for VLP packets
[in]portUDP Port that should be used to listen for VLP packets
virtual pcl::VLPGrabber::~VLPGrabber ( )
throw (
)
virtual

virtual Destructor inherited from the Grabber interface.

It never throws.

Member Function Documentation

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

Returns the maximum number of lasers.

Reimplemented from pcl::HDLGrabber.

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

Obtains the name of this I/O Grabber.

Returns
The name of the grabber

Reimplemented from pcl::HDLGrabber.

void pcl::VLPGrabber::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::VLPGrabber::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 96 of file vlp_grabber.h.

Member Data Documentation

const uint8_t pcl::VLPGrabber::VLP_DUAL_MODE = 0x39
staticprotected

Definition at line 108 of file vlp_grabber.h.

const uint8_t pcl::VLPGrabber::VLP_MAX_NUM_LASERS = 16
staticprotected

Definition at line 107 of file vlp_grabber.h.


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