30 #include <pcl/pcl_config.h>
32 #if PCL_VERSION_COMPARE(<, 1, 9, 0)
33 #define VLP_MAX_NUM_LASERS 16
34 #define VLP_DUAL_MODE 0x39
54 const int HALFHOUR_TO_SEC = 1800;
55 double retval = stamp;
56 if (nominal_stamp > stamp) {
57 if (nominal_stamp - stamp > HALFHOUR_TO_SEC) {
58 retval = retval + 2*HALFHOUR_TO_SEC;
60 }
else if (stamp - nominal_stamp > HALFHOUR_TO_SEC) {
61 retval = retval - 2*HALFHOUR_TO_SEC;
72 const int HOUR_TO_SEC = 3600;
76 uint32_t cur_hour = time_nom / HOUR_TO_SEC;
77 double stamp = double(cur_hour * HOUR_TO_SEC) + double(
data) / 1000000;
83 const std::string& pcapFile,
88 Lidar(frameRate, localTransform),
89 pcl::VLPGrabber(pcapFile),
90 timingOffsetsDualMode_(
false),
92 startSweepTimeHost_(0),
93 organized_(organized),
97 UDEBUG(
"Using PCAP file \"%s\"", pcapFile.c_str());
100 const boost::asio::ip::address& ipAddress,
107 Lidar(frameRate, localTransform),
108 pcl::VLPGrabber(ipAddress, port),
109 timingOffsetsDualMode_(
false),
111 startSweepTimeHost_(0),
112 organized_(organized),
113 useHostTime_(useHostTime),
114 stampLast_(stampLast)
116 UDEBUG(
"Using network lidar with IP=%s port=%d", ipAddress.to_string().c_str(), port);
121 UDEBUG(
"Stopping lidar...");
137 UDEBUG(
"Stopping lidar...");
155 UDEBUG(
"Lidar capture started");
171 double full_firing_cycle = 55.296 * 1
e-6;
172 double single_firing = 2.304 * 1
e-6;
173 double dataBlockIndex, dataPointIndex;
178 dataBlockIndex = (
x - (
x % 2)) + (
y / 16);
181 dataBlockIndex = (
x * 2) + (
y / 16);
183 dataPointIndex =
y % 16;
185 timingOffsets_[
x][
y] = (full_firing_cycle * dataBlockIndex) + (single_firing * dataPointIndex);
193 if (
sizeof(HDLLaserReturn) != 3)
204 bool dualMode = dataPacket->mode == VLP_DUAL_MODE;
218 double interpolated_azimuth_delta;
224 if (dataPacket->firingData[index].rotationalPosition < dataPacket->firingData[0].rotationalPosition)
226 interpolated_azimuth_delta = ((dataPacket->firingData[index].rotationalPosition + 36000) - dataPacket->firingData[0].rotationalPosition) / 2.0;
230 interpolated_azimuth_delta = (dataPacket->firingData[index].rotationalPosition - dataPacket->firingData[0].rotationalPosition) / 2.0;
235 HDLFiringData firing_data = dataPacket->firingData[
i];
239 double current_azimuth = firing_data.rotationalPosition;
240 if (
j >= VLP_MAX_NUM_LASERS)
242 current_azimuth += interpolated_azimuth_delta;
244 if (current_azimuth > 36000)
246 current_azimuth -= 36000;
253 if (current_azimuth < HDLGrabber::last_azimuth_)
307 HDLGrabber::computeXYZI (xyzi, current_azimuth, firing_data.laserReturns[
j], laser_corrections_[
j % VLP_MAX_NUM_LASERS]);
312 xyzit.
i = xyzi.intensity;
313 xyzit.
t = timeSinceStartOfThisScan;
323 last_azimuth_ = current_azimuth;
327 pcl::PointXYZI dual_xyzi;
328 HDLGrabber::computeXYZI (dual_xyzi, current_azimuth, dataPacket->firingData[
i + 1].laserReturns[
j], laser_corrections_[
j % VLP_MAX_NUM_LASERS]);
332 xyzit.
x = dual_xyzi.y;
333 xyzit.
y = -dual_xyzi.x;
334 xyzit.
z = dual_xyzi.z;
335 xyzit.
i = dual_xyzi.intensity;
336 xyzit.
t = timeSinceStartOfThisScan;
339 else if ((dual_xyzi.x != xyzi.x || dual_xyzi.y != xyzi.y || dual_xyzi.z != xyzi.z)
342 xyzit.
x = dual_xyzi.y;
343 xyzit.
y = -dual_xyzi.x;
344 xyzit.
z = dual_xyzi.z;
345 xyzit.
i = dual_xyzi.intensity;
346 xyzit.
t = timeSinceStartOfThisScan;
372 UWARN(
"Did not receive any scans for the past 5 seconds.");