Classes | Public Types | Public Member Functions | Protected Types | Static Protected Attributes | Private Member Functions | Private Attributes | Static Private Attributes
pcl::HDLGrabber Class Reference

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

#include <hdl_grabber.h>

Inheritance diagram for pcl::HDLGrabber:
Inheritance graph
[legend]

List of all members.

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.
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.
typedef void( sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb )(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.
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".
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".
typedef void( sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgb )(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.

Public Member Functions

void filterPackets (const boost::asio::ip::address &ipAddress, const unsigned short 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.
virtual float getFramesPerSecond () const
 Returns the number of frames per second.
float getMaximumDistanceThreshold ()
 Returns the current maximum distance threshold, in meters.
float getMinimumDistanceThreshold ()
 Returns the current minimum distance threshold, in meters.
virtual std::string getName () const
 Obtains the name of this I/O Grabber.
 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].
 HDLGrabber (const boost::asio::ip::address &ipAddress, const unsigned short port, const std::string &correctionsFile="")
 Constructor taking a pecified IP/port and an optional path to an HDL corrections file.
virtual bool isRunning () const
 Check if the grabber is still running.
void setLaserColorRGB (const pcl::RGB &color, unsigned int laserNumber)
 Allows one to customize the colors used for each of the lasers.
void 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 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 start ()
 Starts processing the Velodyne packets, either from the network or PCAP file.
virtual void stop ()
 Stops processing the Velodyne packets, either from the network or PCAP file.
virtual ~HDLGrabber () throw ()
 virtual Destructor inherited from the Grabber interface. It never throws.

Protected Types

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

Static Protected Attributes

static const int HDL_DATA_PORT = 2368
static const
boost::asio::ip::address 
HDL_DEFAULT_NETWORK_ADDRESS = boost::asio::ip::address::from_string ("192.168.3.255")
static const int HDL_FIRING_PER_PKT = 12
static const int HDL_LASER_PER_FIRING = 32
static const int HDL_MAX_NUM_LASERS = 64
static const int HDL_NUM_ROT_ANGLES = 36001

Private Member Functions

void computeXYZI (pcl::PointXYZI &pointXYZI, int azimuth, HDLLaserReturn laserReturn, HDLLaserCorrection correction)
void enqueueHDLPacket (const unsigned char *data, std::size_t bytesReceived)
void fireCurrentScan (const unsigned short startAngle, const unsigned short endAngle)
void fireCurrentSweep ()
void initialize (const std::string &correctionsFile)
bool isAddressUnspecified (const boost::asio::ip::address &ip_address)
void loadCorrectionsFile (const std::string &correctionsFile)
void loadHDL32Corrections ()
void processVelodynePackets ()
void readPacketsFromSocket ()
void toPointClouds (HDLDataPacket *dataPacket)

Private Attributes

boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZ > > 
current_scan_xyz_
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZI > > 
current_scan_xyzi_
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZRGBA > > 
current_scan_xyzrgb_
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZ > > 
current_sweep_xyz_
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZI > > 
current_sweep_xyzi_
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZRGBA > > 
current_sweep_xyzrgb_
pcl::SynchronizedQueue
< unsigned char * > 
hdl_data_
boost::thread * hdl_read_packet_thread_
boost::asio::ip::udp::socket * hdl_read_socket_
boost::asio::io_service hdl_read_socket_service_
HDLLaserCorrection laser_corrections_ [HDL_MAX_NUM_LASERS]
pcl::RGB laser_rgb_mapping_ [HDL_MAX_NUM_LASERS]
unsigned int last_azimuth_
float max_distance_threshold_
float min_distance_threshold_
std::string pcap_file_name_
boost::thread * queue_consumer_thread_
boost::signals2::signal
< sig_cb_velodyne_hdl_scan_point_cloud_xyz > * 
scan_xyz_signal_
boost::signals2::signal
< sig_cb_velodyne_hdl_scan_point_cloud_xyzi > * 
scan_xyzi_signal_
boost::signals2::signal
< sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb > * 
scan_xyzrgb_signal_
boost::asio::ip::address source_address_filter_
unsigned short source_port_filter_
boost::signals2::signal
< sig_cb_velodyne_hdl_sweep_point_cloud_xyz > * 
sweep_xyz_signal_
boost::signals2::signal
< sig_cb_velodyne_hdl_sweep_point_cloud_xyzi > * 
sweep_xyzi_signal_
boost::signals2::signal
< sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgb > * 
sweep_xyzrgb_signal_
bool terminate_read_packet_thread_
boost::asio::ip::udp::endpoint udp_listener_endpoint_

Static Private Attributes

static double * cos_lookup_table_ = NULL
static double * sin_lookup_table_ = NULL

Detailed Description

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

Author:
Keven Ring <keven@mitre.org>

Definition at line 59 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 65 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 77 of file hdl_grabber.h.

typedef void( pcl::HDLGrabber::sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb)(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 71 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 84 of file hdl_grabber.h.

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 90 of file hdl_grabber.h.

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 96 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 176 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

Definition at line 59 of file hdl_grabber.cpp.

pcl::HDLGrabber::HDLGrabber ( const boost::asio::ip::address &  ipAddress,
const unsigned short  port,
const std::string correctionsFile = "" 
)

Constructor taking a pecified 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
pcl::HDLGrabber::~HDLGrabber ( ) throw () [virtual]

virtual Destructor inherited from the Grabber interface. It never throws.

Definition at line 122 of file hdl_grabber.cpp.


Member Function Documentation

void pcl::HDLGrabber::computeXYZI ( pcl::PointXYZI pointXYZI,
int  azimuth,
HDLLaserReturn  laserReturn,
HDLLaserCorrection  correction 
) [private]

Definition at line 401 of file hdl_grabber.cpp.

void pcl::HDLGrabber::enqueueHDLPacket ( const unsigned char *  data,
std::size_t  bytesReceived 
) [private]

Definition at line 470 of file hdl_grabber.cpp.

void pcl::HDLGrabber::filterPackets ( const boost::asio::ip::address &  ipAddress,
const unsigned short  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.

Definition at line 573 of file hdl_grabber.cpp.

void pcl::HDLGrabber::fireCurrentScan ( const unsigned short  startAngle,
const unsigned short  endAngle 
) [private]

Definition at line 452 of file hdl_grabber.cpp.

Definition at line 438 of file hdl_grabber.cpp.

float pcl::HDLGrabber::getFramesPerSecond ( ) const [virtual]

Returns the number of frames per second.

Implements pcl::Grabber.

Definition at line 566 of file hdl_grabber.cpp.

Returns the current maximum distance threshold, in meters.

Definition at line 619 of file hdl_grabber.cpp.

Returns the current minimum distance threshold, in meters.

Definition at line 625 of file hdl_grabber.cpp.

Obtains the name of this I/O Grabber.

Returns:
The name of the grabber

Implements pcl::Grabber.

Definition at line 559 of file hdl_grabber.cpp.

void pcl::HDLGrabber::initialize ( const std::string correctionsFile) [private]

Definition at line 136 of file hdl_grabber.cpp.

bool pcl::HDLGrabber::isAddressUnspecified ( const boost::asio::ip::address &  ip_address) [private]

Definition at line 593 of file hdl_grabber.cpp.

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.

Definition at line 551 of file hdl_grabber.cpp.

void pcl::HDLGrabber::loadCorrectionsFile ( const std::string correctionsFile) [private]

Definition at line 200 of file hdl_grabber.cpp.

Definition at line 267 of file hdl_grabber.cpp.

Definition at line 298 of file hdl_grabber.cpp.

Definition at line 631 of file hdl_grabber.cpp.

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

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

Definition at line 582 of file hdl_grabber.cpp.

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.

Definition at line 607 of file hdl_grabber.cpp.

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.

Definition at line 613 of file hdl_grabber.cpp.

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

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

Implements pcl::Grabber.

Definition at line 484 of file hdl_grabber.cpp.

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

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

Implements pcl::Grabber.

Definition at line 523 of file hdl_grabber.cpp.

void pcl::HDLGrabber::toPointClouds ( HDLDataPacket dataPacket) [private]

Definition at line 314 of file hdl_grabber.cpp.


Member Data Documentation

double * pcl::HDLGrabber::cos_lookup_table_ = NULL [static, private]

Definition at line 218 of file hdl_grabber.h.

Definition at line 231 of file hdl_grabber.h.

Definition at line 233 of file hdl_grabber.h.

Definition at line 235 of file hdl_grabber.h.

Definition at line 231 of file hdl_grabber.h.

Definition at line 233 of file hdl_grabber.h.

Definition at line 235 of file hdl_grabber.h.

Definition at line 220 of file hdl_grabber.h.

const int pcl::HDLGrabber::HDL_DATA_PORT = 2368 [static, protected]

Definition at line 169 of file hdl_grabber.h.

const boost::asio::ip::address pcl::HDLGrabber::HDL_DEFAULT_NETWORK_ADDRESS = boost::asio::ip::address::from_string ("192.168.3.255") [static, protected]

Definition at line 174 of file hdl_grabber.h.

const int pcl::HDLGrabber::HDL_FIRING_PER_PKT = 12 [static, protected]

Definition at line 173 of file hdl_grabber.h.

const int pcl::HDLGrabber::HDL_LASER_PER_FIRING = 32 [static, protected]

Definition at line 171 of file hdl_grabber.h.

const int pcl::HDLGrabber::HDL_MAX_NUM_LASERS = 64 [static, protected]

Definition at line 172 of file hdl_grabber.h.

const int pcl::HDLGrabber::HDL_NUM_ROT_ANGLES = 36001 [static, protected]

Definition at line 170 of file hdl_grabber.h.

boost::thread* pcl::HDLGrabber::hdl_read_packet_thread_ [private]

Definition at line 228 of file hdl_grabber.h.

boost::asio::ip::udp::socket* pcl::HDLGrabber::hdl_read_socket_ [private]

Definition at line 225 of file hdl_grabber.h.

boost::asio::io_service pcl::HDLGrabber::hdl_read_socket_service_ [private]

Definition at line 224 of file hdl_grabber.h.

Definition at line 229 of file hdl_grabber.h.

Definition at line 244 of file hdl_grabber.h.

unsigned int pcl::HDLGrabber::last_azimuth_ [private]

Definition at line 237 of file hdl_grabber.h.

Definition at line 246 of file hdl_grabber.h.

Definition at line 245 of file hdl_grabber.h.

Definition at line 226 of file hdl_grabber.h.

boost::thread* pcl::HDLGrabber::queue_consumer_thread_ [private]

Definition at line 227 of file hdl_grabber.h.

Definition at line 241 of file hdl_grabber.h.

Definition at line 243 of file hdl_grabber.h.

Definition at line 242 of file hdl_grabber.h.

double * pcl::HDLGrabber::sin_lookup_table_ = NULL [static, private]

Definition at line 219 of file hdl_grabber.h.

boost::asio::ip::address pcl::HDLGrabber::source_address_filter_ [private]

Definition at line 222 of file hdl_grabber.h.

unsigned short pcl::HDLGrabber::source_port_filter_ [private]

Definition at line 223 of file hdl_grabber.h.

Definition at line 238 of file hdl_grabber.h.

Definition at line 240 of file hdl_grabber.h.

Definition at line 239 of file hdl_grabber.h.

Definition at line 230 of file hdl_grabber.h.

boost::asio::ip::udp::endpoint pcl::HDLGrabber::udp_listener_endpoint_ [private]

Definition at line 221 of file hdl_grabber.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:41:42