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)
101 HDLGrabber (
const std::string& correctionsFile =
"",
102 const std::string& pcapFile =
"");
109 HDLGrabber (
const boost::asio::ip::address& ipAddress,
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);
154 setLaserColorRGB (const
pcl::
RGB& color,
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_);
172 setMinimumDistanceThreshold (
float & minThreshold);
179 setMaximumDistanceThreshold (
float & maxThreshold);
185 getMinimumDistanceThreshold ();
190 getMaximumDistanceThreshold ();
195 getMaximumNumberOfLasers ()
const;
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)
261 fireCurrentScan (
const std::uint16_t startAngle,
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_service 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();
316 #endif //#ifdef HAVE_PCAP
319 isAddressUnspecified (
const boost::asio::ip::address& ip_address);