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) 107 HDLGrabber (
const std::string& correctionsFile =
"",
108 const std::string& pcapFile =
"");
115 HDLGrabber (
const boost::asio::ip::address& ipAddress,
117 const std::string& correctionsFile =
"");
135 getName () const override;
141 isRunning () const override;
146 getFramesPerSecond () const override;
152 filterPackets (const
boost::asio::ip::address& ipAddress,
160 setLaserColorRGB (const
pcl::
RGB& color,
161 const std::
uint8_t laserNumber);
167 template<typename IterT>
void 168 setLaserColorRGB (const IterT& begin, const IterT& end)
170 std::copy (begin, end, laser_rgb_mapping_);
178 setMinimumDistanceThreshold (
float & minThreshold);
185 setMaximumDistanceThreshold (
float & maxThreshold);
191 getMinimumDistanceThreshold ();
196 getMaximumDistanceThreshold ();
201 getMaximumNumberOfLasers ()
const;
212 BLOCK_0_TO_31 = 0xeeff, BLOCK_32_TO_63 = 0xddff
215 #pragma pack(push, 1) 277 static double *cos_lookup_table_;
278 static double *sin_lookup_table_;
280 boost::asio::ip::udp::endpoint udp_listener_endpoint_;
281 boost::asio::ip::address source_address_filter_;
283 boost::asio::io_service hdl_read_socket_service_;
284 boost::asio::ip::udp::socket *hdl_read_socket_;
285 std::string pcap_file_name_;
286 std::thread *queue_consumer_thread_;
287 std::thread *hdl_read_packet_thread_;
288 bool terminate_read_packet_thread_;
289 pcl::RGB laser_rgb_mapping_[HDL_MAX_NUM_LASERS];
290 float min_distance_threshold_;
291 float max_distance_threshold_;
296 virtual boost::asio::ip::address
297 getDefaultNetworkAddress ();
300 initialize (
const std::string& correctionsFile =
"");
303 processVelodynePackets ();
307 std::size_t bytesReceived);
310 loadCorrectionsFile (
const std::string& correctionsFile);
313 loadHDL32Corrections ();
316 readPacketsFromSocket ();
320 readPacketsFromPcap();
322 #endif //#ifdef HAVE_PCAP 325 isAddressUnspecified (
const boost::asio::ip::address& ip_address);
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...
double verticalCorrection
double horizontalOffsetCorrection
shared_ptr< PointCloud< PointT > > Ptr
boost::signals2::signal< sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba > * sweep_xyzrgba_signal_
double verticalOffsetCorrection
double distanceCorrection
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...
pcl::PointCloud< pcl::PointXYZI >::Ptr current_sweep_xyzi_
sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgb
std::uint16_t blockIdentifier
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr current_sweep_xyzrgba_
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_xyz > * scan_xyz_signal_
boost::signals2::signal< sig_cb_velodyne_hdl_sweep_point_cloud_xyz > * sweep_xyz_signal_
double sinVertOffsetCorrection
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...
Grabber for the Velodyne High-Definition-Laser (HDL)
Grabber interface for PCL 1.x device drivers.
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.
A structure representing RGB color information.
double cosVertOffsetCorrection
Defines all the PCL implemented PointT point type structures.
sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb
boost::signals2::signal< sig_cb_velodyne_hdl_scan_point_cloud_xyzi > * scan_xyzi_signal_
shared_ptr< const PointCloud< PointT > > ConstPtr
std::uint32_t gpsTimestamp
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...
boost::signals2::signal< sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba > * scan_xyzrgba_signal_
#define PCL_DEPRECATED(Major, Minor, Message)
macro for compatibility across compilers and help remove old deprecated items for the Major...
boost::signals2::signal< sig_cb_velodyne_hdl_sweep_point_cloud_xyzi > * sweep_xyzi_signal_
std::uint16_t rotationalPosition
Defines all the PCL and non-PCL macros used.
pcl::PointCloud< pcl::PointXYZ >::Ptr current_sweep_xyz_
std::uint16_t last_azimuth_