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 | |
using | sig_cb_velodyne_hdl_scan_point_cloud_xyz = void(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &, float, float) |
Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne. More... |
|
using | sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba = void(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &, float, float) |
Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne. More... |
|
using | sig_cb_velodyne_hdl_scan_point_cloud_xyzi = void(const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &, float, float) |
Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne with the returned intensity. More... |
|
using | sig_cb_velodyne_hdl_sweep_point_cloud_xyz = void(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &) |
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... |
|
using | sig_cb_velodyne_hdl_sweep_point_cloud_xyzi = void(const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &) |
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... |
|
using | sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba = void(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &) |
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... |
|
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 std::uint16_t port, const std::string &correctionsFile="") | |
Constructor taking a specified IP/port and an optional path to an HDL corrections file. More... |
|
~HDLGrabber () noexcept | |
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 std::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 std::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 std::uint8_t | getMaximumNumberOfLasers () const |
Returns the maximum number of lasers. More... |
|
Public Member Functions inherited from pcl::Grabber | |
Grabber ()=default | |
Default ctor. More... |
|
Grabber (const Grabber &)=delete | |
No copy ctor since Grabber can't be copied. More... |
|
Grabber & | operator= (const Grabber &)=delete |
No copy assign operator since Grabber can't be copied. More... |
|
Grabber (Grabber &&)=default | |
Move ctor. More... |
|
Grabber & | operator= (Grabber &&)=default |
Move assign operator. More... |
|
virtual | ~Grabber () noexcept=default |
virtual destructor. More... |
|
template<typename T > | |
boost::signals2::connection | registerCallback (const std::function< T > &callback) |
registers a callback function/method to a signal with the corresponding signature More... |
|
template<typename T > | |
bool | providesCallback () const noexcept |
indicates whether a signal with given parameter-type exists or not More... |
|
bool | toggle () |
For devices that are streaming, stopped streams are started and running stream are stopped. More... |
|
Protected Types | |
enum | HDLBlock { BLOCK_0_TO_31 = 0xeeff, BLOCK_32_TO_63 = 0xddff } |
Protected Member Functions | |
void | fireCurrentSweep () |
void | fireCurrentScan (const std::uint16_t startAngle, const std::uint16_t endAngle) |
void | computeXYZI (pcl::PointXYZI &pointXYZI, std::uint16_t azimuth, HDLLaserReturn laserReturn, HDLLaserCorrection correction) const |
Protected Member Functions inherited from pcl::Grabber | |
virtual void | signalsChanged () |
template<typename T > | |
boost::signals2::signal< T > * | find_signal () const noexcept |
template<typename T > | |
int | num_slots () const noexcept |
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 std::uint16_t | HDL_DATA_PORT = 2368 |
static const std::uint16_t | HDL_NUM_ROT_ANGLES = 36001 |
static const std::uint8_t | HDL_LASER_PER_FIRING = 32 |
static const std::uint8_t | HDL_MAX_NUM_LASERS = 64 |
static const std::uint8_t | HDL_FIRING_PER_PKT = 12 |
Grabber for the Velodyne High-Definition-Laser (HDL)
Definition at line 61 of file hdl_grabber.h.
using pcl::HDLGrabber::sig_cb_velodyne_hdl_scan_point_cloud_xyz = void (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &, 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.
using pcl::HDLGrabber::sig_cb_velodyne_hdl_scan_point_cloud_xyzi = void (const pcl::PointCloud<pcl::PointXYZI>::ConstPtr &, float, 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.
using pcl::HDLGrabber::sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba = void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &, 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 72 of file hdl_grabber.h.
using pcl::HDLGrabber::sig_cb_velodyne_hdl_sweep_point_cloud_xyz = void (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &) |
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 83 of file hdl_grabber.h.
using pcl::HDLGrabber::sig_cb_velodyne_hdl_sweep_point_cloud_xyzi = void (const pcl::PointCloud<pcl::PointXYZI>::ConstPtr &) |
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 89 of file hdl_grabber.h.
using pcl::HDLGrabber::sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba = void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &) |
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 95 of file hdl_grabber.h.
| protected |
Enumerator | |
---|---|
BLOCK_0_TO_31 | |
BLOCK_32_TO_63 |
Definition at line 204 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 std::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 |
| noexcept |
virtual Destructor inherited from the Grabber interface.
It never throws.
| protected |
void pcl::HDLGrabber::filterPackets | ( | const boost::asio::ip::address & | ipAddress, |
const std::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.
| inline |
Allows one to customize the colors used for each of the lasers.
Definition at line 162 of file hdl_grabber.h.
void pcl::HDLGrabber::setLaserColorRGB | ( | const pcl::RGB & | color, |
const std::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 |
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 247 of file hdl_grabber.h.
| protected |
Definition at line 248 of file hdl_grabber.h.
| protected |
Definition at line 249 of file hdl_grabber.h.
| protected |
Definition at line 247 of file hdl_grabber.h.
| protected |
Definition at line 248 of file hdl_grabber.h.
| protected |
Definition at line 249 of file hdl_grabber.h.
| staticprotected |
Definition at line 198 of file hdl_grabber.h.
| staticprotected |
Definition at line 202 of file hdl_grabber.h.
| staticprotected |
Definition at line 200 of file hdl_grabber.h.
| staticprotected |
Definition at line 201 of file hdl_grabber.h.
| staticprotected |
Definition at line 199 of file hdl_grabber.h.
| protected |
Definition at line 245 of file hdl_grabber.h.
| protected |
Definition at line 246 of file hdl_grabber.h.
| protected |
Definition at line 253 of file hdl_grabber.h.
| protected |
Definition at line 255 of file hdl_grabber.h.
| protected |
Definition at line 254 of file hdl_grabber.h.
| protected |
Definition at line 250 of file hdl_grabber.h.
| protected |
Definition at line 252 of file hdl_grabber.h.
| protected |
Definition at line 251 of file hdl_grabber.h.
© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1_h_d_l_grabber.html