41 #include "pcl/pcl_config.h"
44 #include <pcl/io/grabber.h>
45 #include <pcl/io/impl/synchronized_queue.hpp>
47 #include <pcl/point_cloud.h>
48 #include <boost/asio.hpp>
52 #define HDL_Grabber_toRadians(x) ((x) * M_PI / 180.0)
102 const std::string& pcapFile =
"");
110 const std::uint16_t port,
111 const std::string& correctionsFile =
"");
129 getName () const override;
135 isRunning () const override;
140 getFramesPerSecond () const override;
146 filterPackets (const
boost::asio::ip::address& ipAddress,
147 const std::uint16_t port = 443);
155 const std::uint8_t laserNumber);
161 template<typename IterT>
void
162 setLaserColorRGB (const IterT& begin, const IterT& end)
164 std::copy (begin, end, laser_rgb_mapping_);
198 static const std::uint16_t HDL_DATA_PORT = 2368;
199 static const std::uint16_t HDL_NUM_ROT_ANGLES = 36001;
200 static const std::uint8_t HDL_LASER_PER_FIRING = 32;
201 static const std::uint8_t HDL_MAX_NUM_LASERS = 64;
202 static const std::uint8_t HDL_FIRING_PER_PKT = 12;
206 BLOCK_0_TO_31 = 0xeeff, BLOCK_32_TO_63 = 0xddff
209 #pragma pack(push, 1)
262 const std::uint16_t endAngle);
265 std::uint16_t azimuth,
271 static double *cos_lookup_table_;
272 static double *sin_lookup_table_;
274 boost::asio::ip::udp::endpoint udp_listener_endpoint_;
275 boost::asio::ip::address source_address_filter_;
276 std::uint16_t source_port_filter_;
277 boost::asio::io_context hdl_read_socket_service_;
278 boost::asio::ip::udp::socket *hdl_read_socket_;
279 std::string pcap_file_name_;
280 std::thread *queue_consumer_thread_;
281 std::thread *hdl_read_packet_thread_;
282 bool terminate_read_packet_thread_;
283 pcl::RGB laser_rgb_mapping_[HDL_MAX_NUM_LASERS];
284 float min_distance_threshold_;
285 float max_distance_threshold_;
290 virtual boost::asio::ip::address
291 getDefaultNetworkAddress ();
294 initialize (
const std::string& correctionsFile =
"");
297 processVelodynePackets ();
300 enqueueHDLPacket (
const std::uint8_t *data,
301 std::size_t bytesReceived);
304 loadCorrectionsFile (
const std::string& correctionsFile);
307 loadHDL32Corrections ();
310 readPacketsFromSocket ();
314 readPacketsFromPcap();
319 isAddressUnspecified (
const boost::asio::ip::address& ip_address);
Grabber interface for PCL 1.x device drivers.
Grabber for the Velodyne High-Definition-Laser (HDL)
boost::signals2::signal< sig_cb_velodyne_hdl_scan_point_cloud_xyz > * scan_xyz_signal_
void(const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &, float, float) sig_cb_velodyne_hdl_scan_point_cloud_xyzi
Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne with the returned...
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.
void setMinimumDistanceThreshold(float &minThreshold)
Any returns from the HDL with a distance less than this are discarded.
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr current_scan_xyzrgba_
boost::signals2::signal< sig_cb_velodyne_hdl_sweep_point_cloud_xyz > * sweep_xyz_signal_
~HDLGrabber() noexcept override
virtual Destructor inherited from the Grabber interface.
pcl::PointCloud< pcl::PointXYZI >::Ptr current_scan_xyzi_
virtual std::uint8_t getMaximumNumberOfLasers() const
Returns the maximum number of lasers.
boost::signals2::signal< sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba > * sweep_xyzrgba_signal_
void computeXYZI(pcl::PointXYZI &pointXYZI, std::uint16_t azimuth, HDLLaserReturn laserReturn, HDLLaserCorrection correction) const
void setMaximumDistanceThreshold(float &maxThreshold)
Any returns from the HDL with a distance greater than this are discarded.
boost::signals2::signal< sig_cb_velodyne_hdl_sweep_point_cloud_xyzi > * sweep_xyzi_signal_
float getMinimumDistanceThreshold()
Returns the current minimum distance threshold, in meters.
void(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &) sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba
Signal used for a 360 degree sweep Represents multiple corrected packets from the HDL Velodyne This s...
float getMaximumDistanceThreshold()
Returns the current maximum distance threshold, in meters.
void(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &) sig_cb_velodyne_hdl_sweep_point_cloud_xyz
Signal used for a 360 degree sweep Represents multiple corrected packets from the HDL Velodyne This s...
HDLGrabber(const std::string &correctionsFile="", const std::string &pcapFile="")
Constructor taking an optional path to an HDL corrections file.
void(const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &) sig_cb_velodyne_hdl_sweep_point_cloud_xyzi
Signal used for a 360 degree sweep Represents multiple corrected packets from the HDL Velodyne with t...
void fireCurrentScan(const std::uint16_t startAngle, const std::uint16_t endAngle)
void(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &, float, float) sig_cb_velodyne_hdl_scan_point_cloud_xyz
Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne.
pcl::PointCloud< pcl::PointXYZ >::Ptr current_scan_xyz_
std::uint16_t last_azimuth_
void(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &, float, float) sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba
Signal used for a single sector Represents 1 corrected packet from the HDL Velodyne.
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_
shared_ptr< PointCloud< PointT > > Ptr
shared_ptr< const PointCloud< PointT > > ConstPtr
Defines all the PCL implemented PointT point type structures.
Defines all the PCL and non-PCL macros used.
std::uint32_t gpsTimestamp
std::uint16_t blockIdentifier
std::uint16_t rotationalPosition
double cosVertOffsetCorrection
double distanceCorrection
double horizontalOffsetCorrection
double sinVertOffsetCorrection
double verticalOffsetCorrection
double verticalCorrection
A structure representing RGB color information.