rawdata.cc 32 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870
  1. /*
  2. * Copyright (C) 2007 Austin Robot Technology, Patrick Beeson
  3. * Copyright (C) 2009, 2010, 2012 Austin Robot Technology, Jack O'Quin
  4. * Copyright (C) 2019, Kaarta Inc, Shawn Hanna
  5. *
  6. * License: Modified BSD Software License Agreement
  7. *
  8. * $Id$
  9. */
  10. /**
  11. * @file
  12. *
  13. * Velodyne 3D LIDAR data accessor class implementation.
  14. *
  15. * Class for unpacking raw Velodyne LIDAR packets into useful
  16. * formats.
  17. *
  18. * Derived classes accept raw Velodyne data for either single packets
  19. * or entire rotations, and provide it in various formats for either
  20. * on-line or off-line processing.
  21. *
  22. * @author Patrick Beeson
  23. * @author Jack O'Quin
  24. * @author Shawn Hanna
  25. *
  26. * HDL-64E S2 calibration support provided by Nick Hillier
  27. */
  28. #include <fstream>
  29. #include <math.h>
  30. #include "angles.h"
  31. #include "rawdata.h"
  32. namespace velodyne_rawdata
  33. {
  34. inline float SQR(float val) { return val * val; }
  35. ////////////////////////////////////////////////////////////////////////
  36. //
  37. // RawData base class implementation
  38. //
  39. ////////////////////////////////////////////////////////////////////////
  40. RawData::RawData() {}
  41. /** Update parameters: conversions and update */
  42. void RawData::setParameters(double min_range,
  43. double max_range,
  44. double view_direction,
  45. double view_width)
  46. {
  47. config_.min_range = min_range;
  48. config_.max_range = max_range;
  49. //converting angle parameters into the velodyne reference (rad)
  50. config_.tmp_min_angle = view_direction + view_width / 2;
  51. config_.tmp_max_angle = view_direction - view_width / 2;
  52. //computing positive modulo to keep theses angles into [0;2*M_PI]
  53. config_.tmp_min_angle = fmod(fmod(config_.tmp_min_angle, 2 * M_PI) + 2 * M_PI, 2 * M_PI);
  54. config_.tmp_max_angle = fmod(fmod(config_.tmp_max_angle, 2 * M_PI) + 2 * M_PI, 2 * M_PI);
  55. //converting into the hardware velodyne ref (negative yaml and degrees)
  56. //adding 0.5 perfomrs a centered double to int conversion
  57. config_.min_angle = 100 * (2 * M_PI - config_.tmp_min_angle) * 180 / M_PI + 0.5;
  58. config_.max_angle = 100 * (2 * M_PI - config_.tmp_max_angle) * 180 / M_PI + 0.5;
  59. if (config_.min_angle == config_.max_angle)
  60. {
  61. //avoid returning empty cloud if min_angle = max_angle
  62. config_.min_angle = 0;
  63. config_.max_angle = 36000;
  64. }
  65. }
  66. int RawData::scansPerPacket() const
  67. {
  68. if (calibration_.num_lasers == 16)
  69. {
  70. return BLOCKS_PER_PACKET * VLP16_FIRINGS_PER_BLOCK *
  71. VLP16_SCANS_PER_FIRING;
  72. }
  73. else
  74. {
  75. return BLOCKS_PER_PACKET * SCANS_PER_BLOCK;
  76. }
  77. }
  78. /**
  79. * Build a timing table for each block/firing. Stores in timing_offsets vector
  80. */
  81. bool RawData::buildTimings()
  82. {
  83. // vlp16
  84. if (config_.model == "VLP16")
  85. {
  86. // timing table calculation, from velodyne user manual
  87. timing_offsets.resize(12);
  88. for (size_t i = 0; i < timing_offsets.size(); ++i)
  89. {
  90. timing_offsets[i].resize(32);
  91. }
  92. // constants
  93. double full_firing_cycle = 55.296 * 1e-6; // seconds
  94. double single_firing = 2.304 * 1e-6; // seconds
  95. double dataBlockIndex, dataPointIndex;
  96. bool dual_mode = false;
  97. // compute timing offsets
  98. for (size_t x = 0; x < timing_offsets.size(); ++x)
  99. {
  100. for (size_t y = 0; y < timing_offsets[x].size(); ++y)
  101. {
  102. if (dual_mode)
  103. {
  104. dataBlockIndex = (x - (x % 2)) + (y / 16);
  105. }
  106. else
  107. {
  108. dataBlockIndex = (x * 2) + (y / 16);
  109. }
  110. dataPointIndex = y % 16;
  111. //timing_offsets[block][firing]
  112. timing_offsets[x][y] = (full_firing_cycle * dataBlockIndex) + (single_firing * dataPointIndex);
  113. }
  114. }
  115. }
  116. // vlp32
  117. else if (config_.model == "32C")
  118. {
  119. // timing table calculation, from velodyne user manual
  120. timing_offsets.resize(12);
  121. for (size_t i = 0; i < timing_offsets.size(); ++i)
  122. {
  123. timing_offsets[i].resize(32);
  124. }
  125. // constants
  126. double full_firing_cycle = 55.296 * 1e-6; // seconds
  127. double single_firing = 2.304 * 1e-6; // seconds
  128. double dataBlockIndex, dataPointIndex;
  129. bool dual_mode = false;
  130. // compute timing offsets
  131. for (size_t x = 0; x < timing_offsets.size(); ++x)
  132. {
  133. for (size_t y = 0; y < timing_offsets[x].size(); ++y)
  134. {
  135. if (dual_mode)
  136. {
  137. dataBlockIndex = x / 2;
  138. }
  139. else
  140. {
  141. dataBlockIndex = x;
  142. }
  143. dataPointIndex = y / 2;
  144. timing_offsets[x][y] = (full_firing_cycle * dataBlockIndex) + (single_firing * dataPointIndex);
  145. }
  146. }
  147. }
  148. // hdl32
  149. else if (config_.model == "32E")
  150. {
  151. // timing table calculation, from velodyne user manual
  152. timing_offsets.resize(12);
  153. for (size_t i = 0; i < timing_offsets.size(); ++i)
  154. {
  155. timing_offsets[i].resize(32);
  156. }
  157. // constants
  158. double full_firing_cycle = 46.080 * 1e-6; // seconds
  159. double single_firing = 1.152 * 1e-6; // seconds
  160. double dataBlockIndex, dataPointIndex;
  161. bool dual_mode = false;
  162. // compute timing offsets
  163. for (size_t x = 0; x < timing_offsets.size(); ++x)
  164. {
  165. for (size_t y = 0; y < timing_offsets[x].size(); ++y)
  166. {
  167. if (dual_mode)
  168. {
  169. dataBlockIndex = x / 2;
  170. }
  171. else
  172. {
  173. dataBlockIndex = x;
  174. }
  175. dataPointIndex = y / 2;
  176. timing_offsets[x][y] = (full_firing_cycle * dataBlockIndex) + (single_firing * dataPointIndex);
  177. }
  178. }
  179. }
  180. else if (config_.model == "VLS128")
  181. {
  182. timing_offsets.resize(3);
  183. for (size_t i = 0; i < timing_offsets.size(); ++i)
  184. {
  185. timing_offsets[i].resize(17); // 17 (+1 for the maintenance time after firing group 8)
  186. }
  187. double full_firing_cycle = VLS128_SEQ_TDURATION * 1e-6; //seconds
  188. double single_firing = VLS128_CHANNEL_TDURATION * 1e-6; // seconds
  189. double offset_paket_time = VLS128_TOH_ADJUSTMENT * 1e-6; //seconds
  190. double sequenceIndex, firingGroupIndex;
  191. // Compute timing offsets
  192. for (size_t x = 0; x < timing_offsets.size(); ++x)
  193. {
  194. for (size_t y = 0; y < timing_offsets[x].size(); ++y)
  195. {
  196. sequenceIndex = x;
  197. firingGroupIndex = y;
  198. timing_offsets[x][y] = (full_firing_cycle * sequenceIndex) + (single_firing * firingGroupIndex) - offset_paket_time;
  199. LOG(INFO) << " firing_seque" << x << " firing_group" << y << "offset" << timing_offsets[x][y];
  200. }
  201. }
  202. }
  203. else
  204. {
  205. timing_offsets.clear();
  206. LOG(WARNING) << "Timings not supported for model" << config_.model.c_str();
  207. }
  208. if (timing_offsets.size())
  209. {
  210. // // ROS_INFO("VELODYNE TIMING TABLE:");
  211. // for (size_t x = 0; x < timing_offsets.size(); ++x)
  212. // {
  213. // for (size_t y = 0; y < timing_offsets[x].size(); ++y)
  214. // {
  215. // printf("%04.3f ", timing_offsets[x][y] * 1e6);
  216. // }
  217. // printf("\n");
  218. // }
  219. return true;
  220. }
  221. else
  222. {
  223. LOG(WARNING) << "NO TIMING OFFSETS CALCULATED. ARE YOU USING A SUPPORTED VELODYNE SENSOR?";
  224. }
  225. return false;
  226. }
  227. /** Set up for on-line operation. */
  228. bool RawData::setup(std::string model, std::string calib_file, double max_range, double min_range, int min_angle, int max_angle)
  229. {
  230. config_.model = model;
  231. config_.calibrationFile = calib_file;
  232. config_.max_range = max_range;
  233. config_.min_range = min_range;
  234. config_.min_angle = min_angle*100;
  235. config_.max_angle = max_angle*100;
  236. if(!buildTimings())
  237. {
  238. return false;
  239. }
  240. // // get path to angles.config file for this device
  241. // if (!private_nh.getParam("calibration", config_.calibrationFile))
  242. // {
  243. // ROS_ERROR_STREAM("No calibration angles specified! Using test values!");
  244. // // have to use something: grab unit test version as a default
  245. // std::string pkgPath = ros::package::getPath("velodyne_pointcloud");
  246. // config_.calibrationFile = pkgPath + "/params/64e_utexas.yaml";
  247. // }
  248. // ROS_INFO_STREAM("correction angles: " << config_.calibrationFile);
  249. if (!loadCalibration())
  250. {
  251. mb_initialized = false;
  252. return false;
  253. }
  254. // ROS_INFO_STREAM("Number of lasers: " << calibration_.num_lasers << ".");
  255. setupSinCosCache();
  256. setupAzimuthCache();
  257. mb_initialized = true;
  258. return true;
  259. }
  260. /** Set up for offline operation */
  261. int RawData::setupOffline(std::string calibration_file, double max_range_, double min_range_)
  262. {
  263. config_.max_range = max_range_;
  264. config_.min_range = min_range_;
  265. LOG(INFO) << "data ranges to publish: ["
  266. << config_.min_range << ", "
  267. << config_.max_range << "]";
  268. config_.calibrationFile = calibration_file;
  269. LOG(INFO) << "correction angles: " << config_.calibrationFile;
  270. if (!loadCalibration())
  271. {
  272. return -1;
  273. }
  274. LOG(INFO) << "Number of lasers: " << calibration_.num_lasers << ".";
  275. setupSinCosCache();
  276. setupAzimuthCache();
  277. return 0;
  278. }
  279. bool RawData::loadCalibration()
  280. {
  281. calibration_.read(config_.calibrationFile);
  282. if (!calibration_.initialized)
  283. {
  284. LOG(ERROR) << "Unable to open calibration file: " << config_.calibrationFile;
  285. return false;
  286. }
  287. return true;
  288. }
  289. void RawData::setupSinCosCache()
  290. {
  291. // Set up cached values for sin and cos of all the possible headings
  292. for (uint16_t rot_index = 0; rot_index < ROTATION_MAX_UNITS; ++rot_index)
  293. {
  294. float rotation = angles::from_degrees(ROTATION_RESOLUTION * rot_index);
  295. cos_rot_table_[rot_index] = cosf(rotation);
  296. sin_rot_table_[rot_index] = sinf(rotation);
  297. }
  298. if (config_.model == "VLS128")
  299. {
  300. for (uint8_t i = 0; i < 16; i++)
  301. {
  302. vls_128_laser_azimuth_cache[i] =
  303. (VLS128_CHANNEL_TDURATION / VLS128_SEQ_TDURATION) * (i + i / 8);
  304. }
  305. }
  306. }
  307. void RawData::setupAzimuthCache()
  308. {
  309. if (config_.model == "VLS128")
  310. {
  311. for (uint8_t i = 0; i < 16; i++)
  312. {
  313. vls_128_laser_azimuth_cache[i] =
  314. (VLS128_CHANNEL_TDURATION / VLS128_SEQ_TDURATION) * (i + i / 8);
  315. }
  316. }
  317. else
  318. {
  319. LOG(WARNING) << "No Azimuth Cache configured for model " << config_.model.c_str();
  320. }
  321. }
  322. /** @brief convert raw packet to point cloud
  323. *
  324. * @param pkt raw packet to unpack
  325. * @param pc shared pointer to point cloud (points are appended)
  326. */
  327. void RawData::unpack(const unsigned char *pkt, std::vector<Lidar_point> &data)
  328. {
  329. using velodyne_pointcloud::LaserCorrection;
  330. // LOG(INFO)<<"Received packet";
  331. /** special parsing for the VLS128 **/
  332. if (pkt[1205] == VLS128_MODEL_ID)
  333. { // VLS 128
  334. unpack_vls128(pkt, data);
  335. return;
  336. }
  337. /** special parsing for the VLP16 **/
  338. if (calibration_.num_lasers == 16)
  339. {
  340. unpack_vlp16(pkt, data);
  341. return;
  342. }
  343. // float time_diff_start_to_this_packet = (pkt.stamp - scan_start_time).toSec();
  344. const raw_packet_t *raw = (const raw_packet_t *)&pkt[0];
  345. for (int i = 0; i < BLOCKS_PER_PACKET; i++)
  346. {
  347. // upper bank lasers are numbered [0..31]
  348. // NOTE: this is a change from the old velodyne_common implementation
  349. int bank_origin = 0;
  350. if (raw->blocks[i].header == LOWER_BANK)
  351. {
  352. // lower bank lasers are [32..63]
  353. bank_origin = 32;
  354. }
  355. for (int j = 0, k = 0; j < SCANS_PER_BLOCK; j++, k += RAW_SCAN_SIZE)
  356. {
  357. float x, y, z;
  358. float intensity;
  359. const uint8_t laser_number = j + bank_origin;
  360. float time = 0;
  361. const LaserCorrection &corrections = calibration_.laser_corrections[laser_number];
  362. /** Position Calculation */
  363. const raw_block_t &block = raw->blocks[i];
  364. union two_bytes tmp;
  365. tmp.bytes[0] = block.data[k];
  366. tmp.bytes[1] = block.data[k + 1];
  367. /*condition added to avoid calculating points which are not
  368. in the interesting defined area (min_angle < area < max_angle)*/
  369. if ((block.rotation >= config_.min_angle && block.rotation <= config_.max_angle && config_.min_angle < config_.max_angle) || (config_.min_angle > config_.max_angle && (raw->blocks[i].rotation <= config_.max_angle || raw->blocks[i].rotation >= config_.min_angle)))
  370. {
  371. if (timing_offsets.size())
  372. {
  373. time = timing_offsets[i][j]; // +time_diff_start_to_this_packet;
  374. }
  375. if (tmp.uint == 0) // no valid laser beam return
  376. {
  377. // call to addPoint is still required since output could be organized
  378. data.push_back(Lidar_point(0.0f, 0.0f, 0.0f, corrections.laser_ring, raw->blocks[i].rotation, 0.0f, 0.0f, time));
  379. continue;
  380. }
  381. float distance = tmp.uint * calibration_.distance_resolution_m;
  382. distance += corrections.dist_correction;
  383. float cos_vert_angle = corrections.cos_vert_correction;
  384. float sin_vert_angle = corrections.sin_vert_correction;
  385. float cos_rot_correction = corrections.cos_rot_correction;
  386. float sin_rot_correction = corrections.sin_rot_correction;
  387. // cos(a-b) = cos(a)*cos(b) + sin(a)*sin(b)
  388. // sin(a-b) = sin(a)*cos(b) - cos(a)*sin(b)
  389. float cos_rot_angle =
  390. cos_rot_table_[block.rotation] * cos_rot_correction +
  391. sin_rot_table_[block.rotation] * sin_rot_correction;
  392. float sin_rot_angle =
  393. sin_rot_table_[block.rotation] * cos_rot_correction -
  394. cos_rot_table_[block.rotation] * sin_rot_correction;
  395. float horiz_offset = corrections.horiz_offset_correction;
  396. float vert_offset = corrections.vert_offset_correction;
  397. // Compute the distance in the xy plane (w/o accounting for rotation)
  398. /**the new term of 'vert_offset * sin_vert_angle'
  399. * was added to the expression due to the mathemathical
  400. * model we used.
  401. */
  402. float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
  403. // Calculate temporal X, use absolute value.
  404. float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
  405. // Calculate temporal Y, use absolute value
  406. float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
  407. if (xx < 0)
  408. xx = -xx;
  409. if (yy < 0)
  410. yy = -yy;
  411. // Get 2points calibration values,Linear interpolation to get distance
  412. // correction for X and Y, that means distance correction use
  413. // different value at different distance
  414. float distance_corr_x = 0;
  415. float distance_corr_y = 0;
  416. if (corrections.two_pt_correction_available)
  417. {
  418. distance_corr_x =
  419. (corrections.dist_correction - corrections.dist_correction_x) * (xx - 2.4) / (25.04 - 2.4) + corrections.dist_correction_x;
  420. distance_corr_x -= corrections.dist_correction;
  421. distance_corr_y =
  422. (corrections.dist_correction - corrections.dist_correction_y) * (yy - 1.93) / (25.04 - 1.93) + corrections.dist_correction_y;
  423. distance_corr_y -= corrections.dist_correction;
  424. }
  425. float distance_x = distance + distance_corr_x;
  426. /**the new term of 'vert_offset * sin_vert_angle'
  427. * was added to the expression due to the mathemathical
  428. * model we used.
  429. */
  430. xy_distance = distance_x * cos_vert_angle - vert_offset * sin_vert_angle;
  431. ///the expression wiht '-' is proved to be better than the one with '+'
  432. x = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
  433. float distance_y = distance + distance_corr_y;
  434. xy_distance = distance_y * cos_vert_angle - vert_offset * sin_vert_angle;
  435. /**the new term of 'vert_offset * sin_vert_angle'
  436. * was added to the expression due to the mathemathical
  437. * model we used.
  438. */
  439. y = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
  440. // Using distance_y is not symmetric, but the velodyne manual
  441. // does this.
  442. /**the new term of 'vert_offset * cos_vert_angle'
  443. * was added to the expression due to the mathemathical
  444. * model we used.
  445. */
  446. z = distance_y * sin_vert_angle + vert_offset * cos_vert_angle;
  447. /** Use standard ROS coordinate system (right-hand rule) */
  448. float x_coord = y;
  449. float y_coord = -x;
  450. float z_coord = z;
  451. /** Intensity Calculation */
  452. float min_intensity = corrections.min_intensity;
  453. float max_intensity = corrections.max_intensity;
  454. intensity = raw->blocks[i].data[k + 2];
  455. float focal_offset = 256 * (1 - corrections.focal_distance / 13100) * (1 - corrections.focal_distance / 13100);
  456. float focal_slope = corrections.focal_slope;
  457. intensity += focal_slope * (std::abs(focal_offset - 256 *
  458. SQR(1 - static_cast<float>(tmp.uint) / 65535)));
  459. intensity = (intensity < min_intensity) ? min_intensity : intensity;
  460. intensity = (intensity > max_intensity) ? max_intensity : intensity;
  461. data.push_back(Lidar_point(x_coord, y_coord, z_coord, corrections.laser_ring, raw->blocks[i].rotation, distance, intensity, time));
  462. }
  463. }
  464. // data.newLine();
  465. }
  466. }
  467. /** @brief convert raw VLS128 packet to point cloud
  468. *
  469. * @param pkt raw packet to unpack
  470. * @param pc shared pointer to point cloud (points are appended)
  471. */
  472. void RawData::unpack_vls128(const unsigned char *pkt, std::vector<Lidar_point> &data)
  473. {
  474. float azimuth_diff, azimuth_corrected_f;
  475. float last_azimuth_diff = 0;
  476. uint16_t azimuth, azimuth_next, azimuth_corrected;
  477. float x_coord, y_coord, z_coord;
  478. float distance;
  479. const raw_packet_t *raw = (const raw_packet_t *)&pkt[0];
  480. union two_bytes tmp;
  481. float cos_vert_angle, sin_vert_angle, cos_rot_correction, sin_rot_correction;
  482. float cos_rot_angle, sin_rot_angle;
  483. float xy_distance;
  484. // float time_diff_start_to_this_packet = (pkt.stamp - scan_start_time).toSec();
  485. uint8_t laser_number, firing_order;
  486. bool dual_return = (pkt[1204] == 57);
  487. for (int block = 0; block < BLOCKS_PER_PACKET - (4 * dual_return); block++)
  488. {
  489. // cache block for use
  490. const raw_block_t &current_block = raw->blocks[block];
  491. float time = 0;
  492. int bank_origin = 0;
  493. // Used to detect which bank of 32 lasers is in this block
  494. switch (current_block.header)
  495. {
  496. case VLS128_BANK_1:
  497. bank_origin = 0;
  498. break;
  499. case VLS128_BANK_2:
  500. bank_origin = 32;
  501. break;
  502. case VLS128_BANK_3:
  503. bank_origin = 64;
  504. break;
  505. case VLS128_BANK_4:
  506. bank_origin = 96;
  507. break;
  508. default:
  509. // ignore packets with mangled or otherwise different contents
  510. // Do not flood the log with messages, only issue at most one
  511. // of these warnings per minute.
  512. LOG_EVERY_N(INFO, 10000) << "skipping invalid VLS-128 packet: block "
  513. << block << " header value is "
  514. << raw->blocks[block].header;
  515. return; // bad packet: skip the rest
  516. }
  517. // Calculate difference between current and next block's azimuth angle.
  518. if (block == 0)
  519. {
  520. azimuth = current_block.rotation;
  521. }
  522. else
  523. {
  524. azimuth = azimuth_next;
  525. }
  526. if (block < (BLOCKS_PER_PACKET - (1 + dual_return)))
  527. {
  528. // Get the next block rotation to calculate how far we rotate between blocks
  529. azimuth_next = raw->blocks[block + (1 + dual_return)].rotation;
  530. // Finds the difference between two successive blocks
  531. azimuth_diff = (float)((36000 + azimuth_next - azimuth) % 36000);
  532. // This is used when the last block is next to predict rotation amount
  533. last_azimuth_diff = azimuth_diff;
  534. }
  535. else
  536. {
  537. // This makes the assumption the difference between the last block and the next packet is the
  538. // same as the last to the second to last.
  539. // Assumes RPM doesn't change much between blocks
  540. azimuth_diff = (block == BLOCKS_PER_PACKET - (4 * dual_return) - 1) ? 0 : last_azimuth_diff;
  541. }
  542. // condition added to avoid calculating points which are not in the interesting defined area (min_angle < area < max_angle)
  543. if ((config_.min_angle < config_.max_angle && azimuth >= config_.min_angle && azimuth <= config_.max_angle) || (config_.min_angle > config_.max_angle))
  544. {
  545. for (int j = 0, k = 0; j < SCANS_PER_BLOCK; j++, k += RAW_SCAN_SIZE)
  546. {
  547. // distance extraction
  548. tmp.bytes[0] = current_block.data[k];
  549. tmp.bytes[1] = current_block.data[k + 1];
  550. distance = tmp.uint * VLS128_DISTANCE_RESOLUTION;
  551. if (pointInRange(distance))
  552. {
  553. laser_number = j + bank_origin; // Offset the laser in this block by which block it's in
  554. firing_order = laser_number / 8; // VLS-128 fires 8 lasers at a time
  555. if (timing_offsets.size())
  556. {
  557. time = timing_offsets[block / 4][firing_order + laser_number / 64]; // + time_diff_start_to_this_packet;
  558. }
  559. velodyne_pointcloud::LaserCorrection &corrections = calibration_.laser_corrections[laser_number];
  560. // correct for the laser rotation as a function of timing during the firings
  561. azimuth_corrected_f = azimuth + (azimuth_diff * vls_128_laser_azimuth_cache[firing_order]);
  562. azimuth_corrected = ((uint16_t)round(azimuth_corrected_f)) % 36000;
  563. // convert polar coordinates to Euclidean XYZ
  564. cos_vert_angle = corrections.cos_vert_correction;
  565. sin_vert_angle = corrections.sin_vert_correction;
  566. cos_rot_correction = corrections.cos_rot_correction;
  567. sin_rot_correction = corrections.sin_rot_correction;
  568. // cos(a-b) = cos(a)*cos(b) + sin(a)*sin(b)
  569. // sin(a-b) = sin(a)*cos(b) - cos(a)*sin(b)
  570. cos_rot_angle =
  571. cos_rot_table_[azimuth_corrected] * cos_rot_correction +
  572. sin_rot_table_[azimuth_corrected] * sin_rot_correction;
  573. sin_rot_angle =
  574. sin_rot_table_[azimuth_corrected] * cos_rot_correction -
  575. cos_rot_table_[azimuth_corrected] * sin_rot_correction;
  576. // Compute the distance in the xy plane (w/o accounting for rotation)
  577. xy_distance = distance * cos_vert_angle;
  578. data.push_back(Lidar_point(xy_distance * cos_rot_angle,
  579. -(xy_distance * sin_rot_angle),
  580. distance * sin_vert_angle,
  581. corrections.laser_ring,
  582. azimuth_corrected,
  583. distance,
  584. current_block.data[k + 2],
  585. time));
  586. }
  587. }
  588. // data.newLine();
  589. }
  590. }
  591. }
  592. /** @brief convert raw VLP16 packet to point cloud
  593. *
  594. * @param pkt raw packet to unpack
  595. * @param data vector of self-defined point cloud (points are appended)
  596. */
  597. void RawData::unpack_vlp16(const unsigned char *pkt, std::vector<Lidar_point> &data)
  598. {
  599. float azimuth;
  600. float azimuth_diff;
  601. int raw_azimuth_diff;
  602. float last_azimuth_diff = 0;
  603. float azimuth_corrected_f;
  604. int azimuth_corrected;
  605. float x, y, z;
  606. float intensity;
  607. // float time_diff_start_to_this_packet = (pkt.stamp - scan_start_time).toSec();
  608. const raw_packet_t *raw = (const raw_packet_t *)&pkt[0];
  609. float packet_timestamp = ((unsigned long)(raw->revolution & 0xff) << 8 | (unsigned long)(raw->revolution & 0xff00) | (unsigned long)(raw->status[0]) << 16 | (unsigned long)(raw->status[1]) << 24) * 1e-6;
  610. // LOG_EVERY_N(INFO, 10) << "packet timestamp: " << packet_timestamp;
  611. for (int block = 0; block < BLOCKS_PER_PACKET; block++)
  612. {
  613. // ignore packets with mangled or otherwise different contents
  614. if (UPPER_BANK != raw->blocks[block].header)
  615. {
  616. // Do not flood the log with messages, only issue at most one
  617. // of these warnings per minute.
  618. LOG_EVERY_N(INFO, 1000) << "skipping invalid VLP-16 packet: block "
  619. << block << " header value is "
  620. << raw->blocks[block].header;
  621. return; // bad packet: skip the rest
  622. }
  623. // Calculate difference between current and next block's azimuth angle.
  624. azimuth = (float)(raw->blocks[block].rotation);
  625. if (block < (BLOCKS_PER_PACKET - 1))
  626. {
  627. raw_azimuth_diff = raw->blocks[block + 1].rotation - raw->blocks[block].rotation;
  628. azimuth_diff = (float)((36000 + raw_azimuth_diff) % 36000);
  629. // some packets contain an angle overflow where azimuth_diff < 0
  630. if (raw_azimuth_diff < 0) //raw->blocks[block+1].rotation - raw->blocks[block].rotation < 0)
  631. {
  632. LOG_EVERY_N(INFO, 10000) << "Packet containing angle overflow, first angle: " << raw->blocks[block].rotation << " second angle: " << raw->blocks[block + 1].rotation;
  633. // if last_azimuth_diff was not zero, we can assume that the velodyne's speed did not change very much and use the same difference
  634. if (last_azimuth_diff > 0)
  635. {
  636. azimuth_diff = last_azimuth_diff;
  637. }
  638. // otherwise we are not able to use this data
  639. // TODO: we might just not use the second 16 firings
  640. else
  641. {
  642. continue;
  643. }
  644. }
  645. last_azimuth_diff = azimuth_diff;
  646. }
  647. else
  648. {
  649. azimuth_diff = last_azimuth_diff;
  650. }
  651. for (int firing = 0, k = 0; firing < VLP16_FIRINGS_PER_BLOCK; firing++)
  652. {
  653. for (int dsr = 0; dsr < VLP16_SCANS_PER_FIRING; dsr++, k += RAW_SCAN_SIZE)
  654. {
  655. velodyne_pointcloud::LaserCorrection &corrections = calibration_.laser_corrections[dsr];
  656. /** Position Calculation */
  657. union two_bytes tmp;
  658. tmp.bytes[0] = raw->blocks[block].data[k];
  659. tmp.bytes[1] = raw->blocks[block].data[k + 1];
  660. /** correct for the laser rotation as a function of timing during the firings **/
  661. azimuth_corrected_f = azimuth + (azimuth_diff * ((dsr * VLP16_DSR_TOFFSET) + (firing * VLP16_FIRING_TOFFSET)) / VLP16_BLOCK_TDURATION);
  662. azimuth_corrected = ((int)round(azimuth_corrected_f)) % 36000;
  663. /*condition added to avoid calculating points which are not
  664. in the interesting defined area (min_angle < area < max_angle)*/
  665. if ((azimuth_corrected >= config_.min_angle && azimuth_corrected <= config_.max_angle && config_.min_angle < config_.max_angle) || (config_.min_angle > config_.max_angle && (azimuth_corrected <= config_.max_angle || azimuth_corrected >= config_.min_angle)))
  666. {
  667. // convert polar coordinates to Euclidean XYZ
  668. float distance = tmp.uint * calibration_.distance_resolution_m;
  669. distance += corrections.dist_correction;
  670. // added by yct, range limit
  671. if(!pointInRange(distance))
  672. continue;
  673. float cos_vert_angle = corrections.cos_vert_correction;
  674. float sin_vert_angle = corrections.sin_vert_correction;
  675. float cos_rot_correction = corrections.cos_rot_correction;
  676. float sin_rot_correction = corrections.sin_rot_correction;
  677. // cos(a-b) = cos(a)*cos(b) + sin(a)*sin(b)
  678. // sin(a-b) = sin(a)*cos(b) - cos(a)*sin(b)
  679. float cos_rot_angle =
  680. cos_rot_table_[azimuth_corrected] * cos_rot_correction +
  681. sin_rot_table_[azimuth_corrected] * sin_rot_correction;
  682. float sin_rot_angle =
  683. sin_rot_table_[azimuth_corrected] * cos_rot_correction -
  684. cos_rot_table_[azimuth_corrected] * sin_rot_correction;
  685. float horiz_offset = corrections.horiz_offset_correction;
  686. float vert_offset = corrections.vert_offset_correction;
  687. // Compute the distance in the xy plane (w/o accounting for rotation)
  688. /**the new term of 'vert_offset * sin_vert_angle'
  689. * was added to the expression due to the mathemathical
  690. * model we used.
  691. */
  692. float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
  693. // Calculate temporal X, use absolute value.
  694. float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
  695. // Calculate temporal Y, use absolute value
  696. float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
  697. if (xx < 0)
  698. xx = -xx;
  699. if (yy < 0)
  700. yy = -yy;
  701. // Get 2points calibration values,Linear interpolation to get distance
  702. // correction for X and Y, that means distance correction use
  703. // different value at different distance
  704. float distance_corr_x = 0;
  705. float distance_corr_y = 0;
  706. if (corrections.two_pt_correction_available)
  707. {
  708. distance_corr_x =
  709. (corrections.dist_correction - corrections.dist_correction_x) * (xx - 2.4) / (25.04 - 2.4) + corrections.dist_correction_x;
  710. distance_corr_x -= corrections.dist_correction;
  711. distance_corr_y =
  712. (corrections.dist_correction - corrections.dist_correction_y) * (yy - 1.93) / (25.04 - 1.93) + corrections.dist_correction_y;
  713. distance_corr_y -= corrections.dist_correction;
  714. }
  715. float distance_x = distance + distance_corr_x;
  716. /**the new term of 'vert_offset * sin_vert_angle'
  717. * was added to the expression due to the mathemathical
  718. * model we used.
  719. */
  720. xy_distance = distance_x * cos_vert_angle - vert_offset * sin_vert_angle;
  721. x = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
  722. float distance_y = distance + distance_corr_y;
  723. /**the new term of 'vert_offset * sin_vert_angle'
  724. * was added to the expression due to the mathemathical
  725. * model we used.
  726. */
  727. xy_distance = distance_y * cos_vert_angle - vert_offset * sin_vert_angle;
  728. y = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
  729. // Using distance_y is not symmetric, but the velodyne manual
  730. // does this.
  731. /**the new term of 'vert_offset * cos_vert_angle'
  732. * was added to the expression due to the mathemathical
  733. * model we used.
  734. */
  735. z = distance_y * sin_vert_angle + vert_offset * cos_vert_angle;
  736. /** Use standard ROS coordinate system (right-hand rule) */
  737. float x_coord = y;
  738. float y_coord = -x;
  739. float z_coord = z;
  740. /** Intensity Calculation */
  741. float min_intensity = corrections.min_intensity;
  742. float max_intensity = corrections.max_intensity;
  743. intensity = raw->blocks[block].data[k + 2];
  744. float focal_offset = 256 * SQR(1 - corrections.focal_distance / 13100);
  745. float focal_slope = corrections.focal_slope;
  746. intensity += focal_slope * (std::abs(focal_offset - 256 *
  747. SQR(1 - tmp.uint / 65535)));
  748. intensity = (intensity < min_intensity) ? min_intensity : intensity;
  749. intensity = (intensity > max_intensity) ? max_intensity : intensity;
  750. float time = 0;
  751. if (timing_offsets.size())
  752. time = timing_offsets[block][firing * 16 + dsr]; // + time_diff_start_to_this_packet;
  753. data.push_back(Lidar_point(x_coord, y_coord, z_coord, corrections.laser_ring, azimuth_corrected, distance, intensity, time+packet_timestamp));
  754. }
  755. }
  756. // data.newLine();
  757. }
  758. }
  759. }
  760. } // namespace velodyne_rawdata