Point Cloud Library (PCL)
1.9.1-dev
|
Grabber for the Velodyne High-Definition-Laser (HDL) More...
#include <pcl/io/hdl_grabber.h>
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... | |
~HDLGrabber () throw () | |
virtual Destructor inherited from the Grabber interface. More... | |
void | start () override |
Starts processing the Velodyne packets, either from the network or PCAP file. More... | |
void | stop () override |
Stops processing the Velodyne packets, either from the network or PCAP file. More... | |
std::string | getName () const override |
Obtains the name of this I/O Grabber. More... | |
bool | isRunning () const override |
Check if the grabber is still running. More... | |
float | getFramesPerSecond () const override |
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... | |
![]() | |
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) |
![]() | |
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 () |
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 |
Grabber for the Velodyne High-Definition-Laser (HDL)
Definition at line 59 of file hdl_grabber.h.
|
protected |
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 66 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 85 of file hdl_grabber.h.
typedef sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba pcl::HDLGrabber::sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb |
Definition at line 79 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 74 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 94 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 101 of file hdl_grabber.h.
typedef sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba pcl::HDLGrabber::sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgb |
Definition at line 111 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 108 of file hdl_grabber.h.
|
protected |
Enumerator | |
---|---|
BLOCK_0_TO_31 | |
BLOCK_32_TO_63 |
Definition at line 220 of file hdl_grabber.h.
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]
[in] | correctionsFile | Path 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] | pcapFile | Path 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.
[in] | ipAddress | IP Address that should be used to listen for HDL packets |
[in] | port | UDP Port that should be used to listen for HDL packets |
[in] | correctionsFile | Path 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 Destructor inherited from the Grabber interface.
It never throws.
|
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.
|
protected |
|
protected |
|
overridevirtual |
Returns the number of frames per second.
Implements pcl::Grabber.
float pcl::HDLGrabber::getMaximumDistanceThreshold | ( | ) |
Returns the current maximum distance threshold, in meters.
|
virtual |
Returns the maximum number of lasers.
Reimplemented in pcl::VLPGrabber.
float pcl::HDLGrabber::getMinimumDistanceThreshold | ( | ) |
Returns the current minimum distance threshold, in meters.
|
overridevirtual |
Obtains the name of this I/O Grabber.
Implements pcl::Grabber.
Reimplemented in pcl::VLPGrabber.
|
overridevirtual |
Check if the grabber is still running.
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.
[in] | color | RGB color to set |
[in] | laserNumber | Number of laser to set color |
|
inline |
Allows one to customize the colors used for each of the lasers.
Definition at line 178 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
|
overridevirtual |
Starts processing the Velodyne packets, either from the network or PCAP file.
Implements pcl::Grabber.
|
overridevirtual |
Stops processing the Velodyne packets, either from the network or PCAP file.
Implements pcl::Grabber.
|
protected |
Definition at line 263 of file hdl_grabber.h.
|
protected |
Definition at line 264 of file hdl_grabber.h.
|
protected |
Definition at line 265 of file hdl_grabber.h.
|
protected |
Definition at line 263 of file hdl_grabber.h.
|
protected |
Definition at line 264 of file hdl_grabber.h.
|
protected |
Definition at line 265 of file hdl_grabber.h.
|
staticprotected |
Definition at line 214 of file hdl_grabber.h.
|
staticprotected |
Definition at line 218 of file hdl_grabber.h.
|
staticprotected |
Definition at line 216 of file hdl_grabber.h.
|
staticprotected |
Definition at line 217 of file hdl_grabber.h.
|
staticprotected |
Definition at line 215 of file hdl_grabber.h.
|
protected |
Definition at line 261 of file hdl_grabber.h.
|
protected |
Definition at line 262 of file hdl_grabber.h.
|
protected |
Definition at line 269 of file hdl_grabber.h.
|
protected |
Definition at line 271 of file hdl_grabber.h.
|
protected |
Definition at line 270 of file hdl_grabber.h.
|
protected |
Definition at line 266 of file hdl_grabber.h.
|
protected |
Definition at line 268 of file hdl_grabber.h.
|
protected |
Definition at line 267 of file hdl_grabber.h.