rawdata.cc
Go to the documentation of this file.
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 
30 #include <fstream>
31 #include <math.h>
32 
33 #include <ros/ros.h>
34 #include <ros/package.h>
35 #include <angles/angles.h>
36 
38 
39 namespace velodyne_rawdata
40 {
41 inline float SQR(float val) { return val*val; }
42 
44  //
45  // RawData base class implementation
46  //
48 
50 
52  void RawData::setParameters(double min_range,
53  double max_range,
54  double view_direction,
55  double view_width)
56  {
57  config_.min_range = min_range;
58  config_.max_range = max_range;
59 
60  //converting angle parameters into the velodyne reference (rad)
61  config_.tmp_min_angle = view_direction + view_width/2;
62  config_.tmp_max_angle = view_direction - view_width/2;
63 
64  //computing positive modulo to keep theses angles into [0;2*M_PI]
65  config_.tmp_min_angle = fmod(fmod(config_.tmp_min_angle,2*M_PI) + 2*M_PI,2*M_PI);
66  config_.tmp_max_angle = fmod(fmod(config_.tmp_max_angle,2*M_PI) + 2*M_PI,2*M_PI);
67 
68  //converting into the hardware velodyne ref (negative yaml and degrees)
69  //adding 0.5 perfomrs a centered double to int conversion
70  config_.min_angle = 100 * (2*M_PI - config_.tmp_min_angle) * 180 / M_PI + 0.5;
71  config_.max_angle = 100 * (2*M_PI - config_.tmp_max_angle) * 180 / M_PI + 0.5;
73  {
74  //avoid returning empty cloud if min_angle = max_angle
75  config_.min_angle = 0;
76  config_.max_angle = 36000;
77  }
78  }
79 
81  {
82  if( calibration_.num_lasers == 16)
83  {
86  }
87  else{
89  }
90  }
91 
96  // vlp16
97  if (config_.model == "VLP16"){
98  // timing table calculation, from velodyne user manual
99  timing_offsets.resize(12);
100  for (size_t i=0; i < timing_offsets.size(); ++i){
101  timing_offsets[i].resize(32);
102  }
103  // constants
104  double full_firing_cycle = 55.296 * 1e-6; // seconds
105  double single_firing = 2.304 * 1e-6; // seconds
106  double dataBlockIndex, dataPointIndex;
107  bool dual_mode = false;
108  // compute timing offsets
109  for (size_t x = 0; x < timing_offsets.size(); ++x){
110  for (size_t y = 0; y < timing_offsets[x].size(); ++y){
111  if (dual_mode){
112  dataBlockIndex = (x - (x % 2)) + (y / 16);
113  }
114  else{
115  dataBlockIndex = (x * 2) + (y / 16);
116  }
117  dataPointIndex = y % 16;
118  //timing_offsets[block][firing]
119  timing_offsets[x][y] = (full_firing_cycle * dataBlockIndex) + (single_firing * dataPointIndex);
120  }
121  }
122  }
123  // vlp32
124  else if (config_.model == "32C"){
125  // timing table calculation, from velodyne user manual
126  timing_offsets.resize(12);
127  for (size_t i=0; i < timing_offsets.size(); ++i){
128  timing_offsets[i].resize(32);
129  }
130  // constants
131  double full_firing_cycle = 55.296 * 1e-6; // seconds
132  double single_firing = 2.304 * 1e-6; // seconds
133  double dataBlockIndex, dataPointIndex;
134  bool dual_mode = false;
135  // compute timing offsets
136  for (size_t x = 0; x < timing_offsets.size(); ++x){
137  for (size_t y = 0; y < timing_offsets[x].size(); ++y){
138  if (dual_mode){
139  dataBlockIndex = x / 2;
140  }
141  else{
142  dataBlockIndex = x;
143  }
144  dataPointIndex = y / 2;
145  timing_offsets[x][y] = (full_firing_cycle * dataBlockIndex) + (single_firing * dataPointIndex);
146  }
147  }
148  }
149  // hdl32
150  else if (config_.model == "32E"){
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  timing_offsets[i].resize(32);
155  }
156  // constants
157  double full_firing_cycle = 46.080 * 1e-6; // seconds
158  double single_firing = 1.152 * 1e-6; // seconds
159  double dataBlockIndex, dataPointIndex;
160  bool dual_mode = false;
161  // compute timing offsets
162  for (size_t x = 0; x < timing_offsets.size(); ++x){
163  for (size_t y = 0; y < timing_offsets[x].size(); ++y){
164  if (dual_mode){
165  dataBlockIndex = x / 2;
166  }
167  else{
168  dataBlockIndex = x;
169  }
170  dataPointIndex = y / 2;
171  timing_offsets[x][y] = (full_firing_cycle * dataBlockIndex) + (single_firing * dataPointIndex);
172  }
173  }
174  }
175  else if (config_.model == "VLS128"){
176 
177  timing_offsets.resize(3);
178  for(size_t i=0; i < timing_offsets.size(); ++i)
179  {
180  timing_offsets[i].resize(17); // 17 (+1 for the maintenance time after firing group 8)
181  }
182 
183  double full_firing_cycle = VLS128_SEQ_TDURATION * 1e-6; //seconds
184  double single_firing = VLS128_CHANNEL_TDURATION * 1e-6; // seconds
185  double offset_paket_time = VLS128_TOH_ADJUSTMENT * 1e-6; //seconds
186  double sequenceIndex, firingGroupIndex;
187  // Compute timing offsets
188  for (size_t x = 0; x < timing_offsets.size(); ++x){
189  for (size_t y = 0; y < timing_offsets[x].size(); ++y){
190 
191  sequenceIndex = x;
192  firingGroupIndex = y;
193  timing_offsets[x][y] = (full_firing_cycle * sequenceIndex) + (single_firing * firingGroupIndex) - offset_paket_time;
194  ROS_DEBUG(" firing_seque %lu firing_group %lu offset %f",x,y,timing_offsets[x][y]);
195  }
196  }
197  }
198  else{
199  timing_offsets.clear();
200  ROS_WARN("Timings not supported for model %s", config_.model.c_str());
201  }
202 
203  if (timing_offsets.size()){
204  // ROS_INFO("VELODYNE TIMING TABLE:");
205  for (size_t x = 0; x < timing_offsets.size(); ++x){
206  for (size_t y = 0; y < timing_offsets[x].size(); ++y){
207  printf("%04.3f ", timing_offsets[x][y] * 1e6);
208  }
209  printf("\n");
210  }
211  return true;
212  }
213  else{
214  ROS_WARN("NO TIMING OFFSETS CALCULATED. ARE YOU USING A SUPPORTED VELODYNE SENSOR?");
215  }
216  return false;
217  }
218 
220  boost::optional<velodyne_pointcloud::Calibration> RawData::setup(ros::NodeHandle private_nh)
221  {
222 
223  if (!private_nh.getParam("model", config_.model))
224  {
225  config_.model = std::string("64E");
226  ROS_ERROR("No Velodyne Sensor Model specified using default %s!", config_.model.c_str());
227 
228  }
229 
230  buildTimings();
231 
232  // get path to angles.config file for this device
233  if (!private_nh.getParam("calibration", config_.calibrationFile))
234  {
235  ROS_ERROR_STREAM("No calibration angles specified! Using test values!");
236 
237  // have to use something: grab unit test version as a default
238  std::string pkgPath = ros::package::getPath("velodyne_pointcloud");
239  config_.calibrationFile = pkgPath + "/params/64e_utexas.yaml";
240  }
241 
242  ROS_INFO_STREAM("correction angles: " << config_.calibrationFile);
243 
244  if (!loadCalibration()) {
245  return boost::none;
246  }
247  ROS_INFO_STREAM("Number of lasers: " << calibration_.num_lasers << ".");
248 
251 
252  return calibration_;
253  }
254 
256  int RawData::setupOffline(std::string calibration_file, std::string model,
257  double max_range_, double min_range_)
258  {
259 
260  config_.model = model;
261  buildTimings();
262 
263  config_.max_range = max_range_;
264  config_.min_range = min_range_;
265  ROS_INFO_STREAM("data ranges to publish: ["
266  << config_.min_range << ", "
267  << config_.max_range << "]");
268 
269  config_.calibrationFile = calibration_file;
270 
271  ROS_INFO_STREAM("correction angles: " << config_.calibrationFile);
272 
273  if (!loadCalibration()) {
274  return -1;
275  }
276  ROS_INFO_STREAM("Number of lasers: " << calibration_.num_lasers << ".");
277 
280 
281  return 0;
282  }
283 
285 
287  if (!calibration_.initialized) {
288  ROS_ERROR_STREAM("Unable to open calibration file: " << config_.calibrationFile);
289  return false;
290  }
291  return true;
292 
293  }
295  {
296  // Set up cached values for sin and cos of all the possible headings
297  for (uint16_t rot_index = 0; rot_index < ROTATION_MAX_UNITS; ++rot_index) {
298  float rotation = angles::from_degrees(ROTATION_RESOLUTION * rot_index);
299  cos_rot_table_[rot_index] = cosf(rotation);
300  sin_rot_table_[rot_index] = sinf(rotation);
301  }
302 
303  if (config_.model == "VLS128") {
304  for (uint8_t i = 0; i < 16; i++) {
307  }
308  }
309  }
310 
312 {
313  if (config_.model == "VLS128") {
314  for (uint8_t i = 0; i < 16; i++) {
317  }
318  }
319  else{
320  ROS_WARN("No Azimuth Cache configured for model %s", config_.model.c_str());
321  }
322 }
323 
324 
330  void RawData::unpack(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase& data, const ros::Time& scan_start_time)
331  {
333  ROS_DEBUG_STREAM("Received packet, time: " << pkt.stamp);
334 
336  if (pkt.data[1205] == VLS128_MODEL_ID) { // VLS 128
337  unpack_vls128(pkt, data, scan_start_time);
338  return;
339  }
340 
342  if (calibration_.num_lasers == 16)
343  {
344  unpack_vlp16(pkt, data, scan_start_time);
345  return;
346  }
347 
348  float time_diff_start_to_this_packet = (pkt.stamp - scan_start_time).toSec();
349 
350  const raw_packet_t *raw = (const raw_packet_t *) &pkt.data[0];
351 
352  for (int i = 0; i < BLOCKS_PER_PACKET; i++) {
353 
354  // upper bank lasers are numbered [0..31]
355  // NOTE: this is a change from the old velodyne_common implementation
356 
357  int bank_origin = 0;
358  if (raw->blocks[i].header == LOWER_BANK) {
359  // lower bank lasers are [32..63]
360  bank_origin = 32;
361  }
362 
363  for (int j = 0, k = 0; j < SCANS_PER_BLOCK; j++, k += RAW_SCAN_SIZE) {
364 
365  float x, y, z;
366  float intensity;
367  const uint8_t laser_number = j + bank_origin;
368  float time = 0;
369 
370  const LaserCorrection &corrections = calibration_.laser_corrections[laser_number];
371 
373  const raw_block_t &block = raw->blocks[i];
374  union two_bytes tmp;
375  tmp.bytes[0] = block.data[k];
376  tmp.bytes[1] = block.data[k+1];
377 
378  /*condition added to avoid calculating points which are not
379  in the interesting defined area (min_angle < area < max_angle)*/
380  if ((block.rotation >= config_.min_angle
381  && block.rotation <= config_.max_angle
384  && (raw->blocks[i].rotation <= config_.max_angle
385  || raw->blocks[i].rotation >= config_.min_angle))){
386 
387  if (timing_offsets.size())
388  {
389  time = timing_offsets[i][j] + time_diff_start_to_this_packet;
390  }
391 
392  if (tmp.uint == 0) // no valid laser beam return
393  {
394  // call to addPoint is still required since output could be organized
395  data.addPoint(nanf(""), nanf(""), nanf(""), corrections.laser_ring, raw->blocks[i].rotation, nanf(""), nanf(""), time);
396  continue;
397  }
398 
399  float distance = tmp.uint * calibration_.distance_resolution_m;
400  distance += corrections.dist_correction;
401 
402  float cos_vert_angle = corrections.cos_vert_correction;
403  float sin_vert_angle = corrections.sin_vert_correction;
404  float cos_rot_correction = corrections.cos_rot_correction;
405  float sin_rot_correction = corrections.sin_rot_correction;
406 
407  // cos(a-b) = cos(a)*cos(b) + sin(a)*sin(b)
408  // sin(a-b) = sin(a)*cos(b) - cos(a)*sin(b)
409  float cos_rot_angle =
410  cos_rot_table_[block.rotation] * cos_rot_correction +
411  sin_rot_table_[block.rotation] * sin_rot_correction;
412  float sin_rot_angle =
413  sin_rot_table_[block.rotation] * cos_rot_correction -
414  cos_rot_table_[block.rotation] * sin_rot_correction;
415 
416  float horiz_offset = corrections.horiz_offset_correction;
417  float vert_offset = corrections.vert_offset_correction;
418 
419  // Compute the distance in the xy plane (w/o accounting for rotation)
424  float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
425 
426  // Calculate temporal X, use absolute value.
427  float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
428  // Calculate temporal Y, use absolute value
429  float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
430  if (xx < 0) xx=-xx;
431  if (yy < 0) yy=-yy;
432 
433  // Get 2points calibration values,Linear interpolation to get distance
434  // correction for X and Y, that means distance correction use
435  // different value at different distance
436  float distance_corr_x = 0;
437  float distance_corr_y = 0;
438  if (corrections.two_pt_correction_available) {
439  distance_corr_x =
440  (corrections.dist_correction - corrections.dist_correction_x)
441  * (xx - 2.4) / (25.04 - 2.4)
442  + corrections.dist_correction_x;
443  distance_corr_x -= corrections.dist_correction;
444  distance_corr_y =
445  (corrections.dist_correction - corrections.dist_correction_y)
446  * (yy - 1.93) / (25.04 - 1.93)
447  + corrections.dist_correction_y;
448  distance_corr_y -= corrections.dist_correction;
449  }
450 
451  float distance_x = distance + distance_corr_x;
456  xy_distance = distance_x * cos_vert_angle - vert_offset * sin_vert_angle ;
458  x = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
459 
460  float distance_y = distance + distance_corr_y;
461  xy_distance = distance_y * cos_vert_angle - vert_offset * sin_vert_angle ;
466  y = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
467 
468  // Using distance_y is not symmetric, but the velodyne manual
469  // does this.
474  z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
475 
477  float x_coord = y;
478  float y_coord = -x;
479  float z_coord = z;
480 
483  float min_intensity = corrections.min_intensity;
484  float max_intensity = corrections.max_intensity;
485 
486  intensity = raw->blocks[i].data[k+2];
487 
488  float focal_offset = 256
489  * (1 - corrections.focal_distance / 13100)
490  * (1 - corrections.focal_distance / 13100);
491  float focal_slope = corrections.focal_slope;
492  intensity += focal_slope * (std::abs(focal_offset - 256 *
493  SQR(1 - static_cast<float>(tmp.uint)/65535)));
494  intensity = (intensity < min_intensity) ? min_intensity : intensity;
495  intensity = (intensity > max_intensity) ? max_intensity : intensity;
496 
497  data.addPoint(x_coord, y_coord, z_coord, corrections.laser_ring, raw->blocks[i].rotation, distance, intensity, time);
498  }
499  }
500  data.newLine();
501  }
502  }
503 
509 void RawData::unpack_vls128(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase& data,
510  const ros::Time& scan_start_time) {
511  float azimuth_diff, azimuth_corrected_f;
512  float last_azimuth_diff = 0;
513  uint16_t azimuth, azimuth_next, azimuth_corrected;
514  float x_coord, y_coord, z_coord;
515  float distance;
516  const raw_packet_t *raw = (const raw_packet_t *) &pkt.data[0];
517  union two_bytes tmp;
518 
519  float cos_vert_angle, sin_vert_angle, cos_rot_correction, sin_rot_correction;
520  float cos_rot_angle, sin_rot_angle;
521  float xy_distance;
522 
523  float time_diff_start_to_this_packet = (pkt.stamp - scan_start_time).toSec();
524 
525  uint8_t laser_number, firing_order;
526  bool dual_return = (pkt.data[1204] == 57);
527 
528  for (int block = 0; block < BLOCKS_PER_PACKET - (4* dual_return); block++) {
529  // cache block for use
530  const raw_block_t &current_block = raw->blocks[block];
531  float time = 0;
532 
533  int bank_origin = 0;
534  // Used to detect which bank of 32 lasers is in this block
535  switch (current_block.header) {
536  case VLS128_BANK_1:
537  bank_origin = 0;
538  break;
539  case VLS128_BANK_2:
540  bank_origin = 32;
541  break;
542  case VLS128_BANK_3:
543  bank_origin = 64;
544  break;
545  case VLS128_BANK_4:
546  bank_origin = 96;
547  break;
548  default:
549  // ignore packets with mangled or otherwise different contents
550  // Do not flood the log with messages, only issue at most one
551  // of these warnings per minute.
552  ROS_WARN_STREAM_THROTTLE(60, "skipping invalid VLS-128 packet: block "
553  << block << " header value is "
554  << raw->blocks[block].header);
555  return; // bad packet: skip the rest
556  }
557 
558  // Calculate difference between current and next block's azimuth angle.
559  if (block == 0) {
560  azimuth = current_block.rotation;
561  } else {
562  azimuth = azimuth_next;
563  }
564  if (block < (BLOCKS_PER_PACKET - (1+dual_return))) {
565  // Get the next block rotation to calculate how far we rotate between blocks
566  azimuth_next = raw->blocks[block + (1+dual_return)].rotation;
567 
568  // Finds the difference between two successive blocks
569  azimuth_diff = (float)((36000 + azimuth_next - azimuth) % 36000);
570 
571  // This is used when the last block is next to predict rotation amount
572  last_azimuth_diff = azimuth_diff;
573  } else {
574  // This makes the assumption the difference between the last block and the next packet is the
575  // same as the last to the second to last.
576  // Assumes RPM doesn't change much between blocks
577  azimuth_diff = (block == BLOCKS_PER_PACKET - (4*dual_return)-1) ? 0 : last_azimuth_diff;
578  }
579 
580  // condition added to avoid calculating points which are not in the interesting defined area (min_angle < area < max_angle)
581  if ((config_.min_angle < config_.max_angle && azimuth >= config_.min_angle && azimuth <= config_.max_angle) || (config_.min_angle > config_.max_angle)) {
582  for (int j = 0, k = 0; j < SCANS_PER_BLOCK; j++, k += RAW_SCAN_SIZE) {
583  // distance extraction
584  tmp.bytes[0] = current_block.data[k];
585  tmp.bytes[1] = current_block.data[k + 1];
586  distance = tmp.uint * VLS128_DISTANCE_RESOLUTION;
587 
588 
589 
590  if (pointInRange(distance)) {
591  laser_number = j + bank_origin; // Offset the laser in this block by which block it's in
592  firing_order = laser_number / 8; // VLS-128 fires 8 lasers at a time
593 
594  if (timing_offsets.size())
595  {
596  time = timing_offsets[block/4][firing_order + laser_number/64] + time_diff_start_to_this_packet;
597  }
598 
600 
601  // correct for the laser rotation as a function of timing during the firings
602  azimuth_corrected_f = azimuth + (azimuth_diff * vls_128_laser_azimuth_cache[firing_order]);
603  azimuth_corrected = ((uint16_t) round(azimuth_corrected_f)) % 36000;
604 
605  // convert polar coordinates to Euclidean XYZ
606  cos_vert_angle = corrections.cos_vert_correction;
607  sin_vert_angle = corrections.sin_vert_correction;
608  cos_rot_correction = corrections.cos_rot_correction;
609  sin_rot_correction = corrections.sin_rot_correction;
610 
611  // cos(a-b) = cos(a)*cos(b) + sin(a)*sin(b)
612  // sin(a-b) = sin(a)*cos(b) - cos(a)*sin(b)
613  cos_rot_angle =
614  cos_rot_table_[azimuth_corrected] * cos_rot_correction +
615  sin_rot_table_[azimuth_corrected] * sin_rot_correction;
616  sin_rot_angle =
617  sin_rot_table_[azimuth_corrected] * cos_rot_correction -
618  cos_rot_table_[azimuth_corrected] * sin_rot_correction;
619 
620  // Compute the distance in the xy plane (w/o accounting for rotation)
621  xy_distance = distance * cos_vert_angle;
622 
623  data.addPoint(xy_distance * cos_rot_angle,
624  -(xy_distance * sin_rot_angle),
625  distance * sin_vert_angle,
626  corrections.laser_ring,
627  azimuth_corrected,
628  distance,
629  current_block.data[k + 2],
630  time);
631  }
632  }
633 
634  if (current_block.header == VLS128_BANK_4)
635  {
636  // add a new line only after the last bank (VLS128_BANK_4)
637  data.newLine();
638  }
639  }
640  }
641 }
642 
648  void RawData::unpack_vlp16(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase& data, const ros::Time& scan_start_time)
649  {
650  float azimuth;
651  float azimuth_diff;
652  int raw_azimuth_diff;
653  float last_azimuth_diff=0;
654  float azimuth_corrected_f;
655  int azimuth_corrected;
656  float x, y, z;
657  float intensity;
658 
659  float time_diff_start_to_this_packet = (pkt.stamp - scan_start_time).toSec();
660 
661  const raw_packet_t *raw = (const raw_packet_t *) &pkt.data[0];
662 
663  for (int block = 0; block < BLOCKS_PER_PACKET; block++) {
664 
665  // ignore packets with mangled or otherwise different contents
666  if (UPPER_BANK != raw->blocks[block].header) {
667  // Do not flood the log with messages, only issue at most one
668  // of these warnings per minute.
669  ROS_WARN_STREAM_THROTTLE(60, "skipping invalid VLP-16 packet: block "
670  << block << " header value is "
671  << raw->blocks[block].header);
672  return; // bad packet: skip the rest
673  }
674 
675  // Calculate difference between current and next block's azimuth angle.
676  azimuth = (float)(raw->blocks[block].rotation);
677  if (block < (BLOCKS_PER_PACKET-1)){
678  raw_azimuth_diff = raw->blocks[block+1].rotation - raw->blocks[block].rotation;
679  azimuth_diff = (float)((36000 + raw_azimuth_diff)%36000);
680  // some packets contain an angle overflow where azimuth_diff < 0
681  if(raw_azimuth_diff < 0)//raw->blocks[block+1].rotation - raw->blocks[block].rotation < 0)
682  {
683  ROS_WARN_STREAM_THROTTLE(60, "Packet containing angle overflow, first angle: " << raw->blocks[block].rotation << " second angle: " << raw->blocks[block+1].rotation);
684  // 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
685  if(last_azimuth_diff > 0){
686  azimuth_diff = last_azimuth_diff;
687  }
688  // otherwise we are not able to use this data
689  // TODO: we might just not use the second 16 firings
690  else{
691  continue;
692  }
693  }
694  last_azimuth_diff = azimuth_diff;
695  }else{
696  azimuth_diff = last_azimuth_diff;
697  }
698 
699  for (int firing=0, k=0; firing < VLP16_FIRINGS_PER_BLOCK; firing++){
700  for (int dsr=0; dsr < VLP16_SCANS_PER_FIRING; dsr++, k+=RAW_SCAN_SIZE){
702 
704  union two_bytes tmp;
705  tmp.bytes[0] = raw->blocks[block].data[k];
706  tmp.bytes[1] = raw->blocks[block].data[k+1];
707 
709  azimuth_corrected_f = azimuth + (azimuth_diff * ((dsr*VLP16_DSR_TOFFSET) + (firing*VLP16_FIRING_TOFFSET)) / VLP16_BLOCK_TDURATION);
710  azimuth_corrected = ((int)round(azimuth_corrected_f)) % 36000;
711 
712  /*condition added to avoid calculating points which are not
713  in the interesting defined area (min_angle < area < max_angle)*/
714  if ((azimuth_corrected >= config_.min_angle
715  && azimuth_corrected <= config_.max_angle
718  && (azimuth_corrected <= config_.max_angle
719  || azimuth_corrected >= config_.min_angle))){
720 
721  // convert polar coordinates to Euclidean XYZ
722  float distance = tmp.uint * calibration_.distance_resolution_m;
723  distance += corrections.dist_correction;
724 
725  float cos_vert_angle = corrections.cos_vert_correction;
726  float sin_vert_angle = corrections.sin_vert_correction;
727  float cos_rot_correction = corrections.cos_rot_correction;
728  float sin_rot_correction = corrections.sin_rot_correction;
729 
730  // cos(a-b) = cos(a)*cos(b) + sin(a)*sin(b)
731  // sin(a-b) = sin(a)*cos(b) - cos(a)*sin(b)
732  float cos_rot_angle =
733  cos_rot_table_[azimuth_corrected] * cos_rot_correction +
734  sin_rot_table_[azimuth_corrected] * sin_rot_correction;
735  float sin_rot_angle =
736  sin_rot_table_[azimuth_corrected] * cos_rot_correction -
737  cos_rot_table_[azimuth_corrected] * sin_rot_correction;
738 
739  float horiz_offset = corrections.horiz_offset_correction;
740  float vert_offset = corrections.vert_offset_correction;
741 
742  // Compute the distance in the xy plane (w/o accounting for rotation)
747  float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
748 
749  // Calculate temporal X, use absolute value.
750  float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
751  // Calculate temporal Y, use absolute value
752  float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
753  if (xx < 0) xx=-xx;
754  if (yy < 0) yy=-yy;
755 
756  // Get 2points calibration values,Linear interpolation to get distance
757  // correction for X and Y, that means distance correction use
758  // different value at different distance
759  float distance_corr_x = 0;
760  float distance_corr_y = 0;
761  if (corrections.two_pt_correction_available) {
762  distance_corr_x =
763  (corrections.dist_correction - corrections.dist_correction_x)
764  * (xx - 2.4) / (25.04 - 2.4)
765  + corrections.dist_correction_x;
766  distance_corr_x -= corrections.dist_correction;
767  distance_corr_y =
768  (corrections.dist_correction - corrections.dist_correction_y)
769  * (yy - 1.93) / (25.04 - 1.93)
770  + corrections.dist_correction_y;
771  distance_corr_y -= corrections.dist_correction;
772  }
773 
774  float distance_x = distance + distance_corr_x;
779  xy_distance = distance_x * cos_vert_angle - vert_offset * sin_vert_angle ;
780  x = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
781 
782  float distance_y = distance + distance_corr_y;
787  xy_distance = distance_y * cos_vert_angle - vert_offset * sin_vert_angle ;
788  y = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
789 
790  // Using distance_y is not symmetric, but the velodyne manual
791  // does this.
796  z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
797 
798 
800  float x_coord = y;
801  float y_coord = -x;
802  float z_coord = z;
803 
805  float min_intensity = corrections.min_intensity;
806  float max_intensity = corrections.max_intensity;
807 
808  intensity = raw->blocks[block].data[k+2];
809 
810  float focal_offset = 256 * SQR(1 - corrections.focal_distance / 13100);
811  float focal_slope = corrections.focal_slope;
812  intensity += focal_slope * (std::abs(focal_offset - 256 *
813  SQR(1 - static_cast<float>(tmp.uint) / 65535)));
814  intensity = (intensity < min_intensity) ? min_intensity : intensity;
815  intensity = (intensity > max_intensity) ? max_intensity : intensity;
816 
817  float time = 0;
818  if (timing_offsets.size())
819  time = timing_offsets[block][firing * 16 + dsr] + time_diff_start_to_this_packet;
820 
821  data.addPoint(x_coord, y_coord, z_coord, corrections.laser_ring, azimuth_corrected, distance, intensity, time);
822  }
823  }
824  data.newLine();
825  }
826  }
827  }
828 } // namespace velodyne_rawdata
velodyne_rawdata::RawData::Config::tmp_min_angle
double tmp_min_angle
Definition: rawdata.h:206
velodyne_rawdata::SCANS_PER_BLOCK
static const int SCANS_PER_BLOCK
Definition: rawdata.h:64
velodyne_rawdata::ROTATION_MAX_UNITS
static const uint16_t ROTATION_MAX_UNITS
Definition: rawdata.h:68
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
velodyne_rawdata::VLP16_BLOCK_TDURATION
static const float VLP16_BLOCK_TDURATION
Definition: rawdata.h:77
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
velodyne_rawdata::RawData::pointInRange
bool pointInRange(float range)
Definition: rawdata.h:241
velodyne_rawdata::VLP16_FIRINGS_PER_BLOCK
static const int VLP16_FIRINGS_PER_BLOCK
Definition: rawdata.h:75
angles::from_degrees
static double from_degrees(double degrees)
velodyne_rawdata::BLOCKS_PER_PACKET
static const int BLOCKS_PER_PACKET
Definition: rawdata.h:108
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
velodyne_rawdata::raw_packet::blocks
raw_block_t blocks[BLOCKS_PER_PACKET]
Definition: rawdata.h:141
velodyne_rawdata::VLS128_TOH_ADJUSTMENT
static const float VLS128_TOH_ADJUSTMENT
Definition: rawdata.h:121
velodyne_rawdata::DataContainerBase
Definition: datacontainerbase.h:47
velodyne_pointcloud::Calibration::initialized
bool initialized
Definition: calibration.h:85
velodyne_pointcloud::LaserCorrection::vert_offset_correction
float vert_offset_correction
Definition: calibration.h:61
velodyne_rawdata::two_bytes::bytes
uint8_t bytes[2]
Definition: rawdata.h:104
velodyne_rawdata::RawData::Config::min_range
double min_range
minimum range to publish
Definition: rawdata.h:202
velodyne_rawdata::RawData::RawData
RawData()
Definition: rawdata.cc:49
velodyne_rawdata::VLS128_BANK_1
static const uint16_t VLS128_BANK_1
Definition: rawdata.h:114
velodyne_rawdata::UPPER_BANK
static const uint16_t UPPER_BANK
Definition: rawdata.h:71
velodyne_rawdata::VLP16_DSR_TOFFSET
static const float VLP16_DSR_TOFFSET
Definition: rawdata.h:78
velodyne_rawdata::RawData::setupSinCosCache
void setupSinCosCache()
Definition: rawdata.cc:294
velodyne_rawdata::RawData::Config::min_angle
int min_angle
minimum angle to publish
Definition: rawdata.h:203
velodyne_pointcloud::Calibration::num_lasers
int num_lasers
Definition: calibration.h:84
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
velodyne_rawdata::RawData::buildTimings
bool buildTimings()
setup per-point timing offsets
Definition: rawdata.cc:95
velodyne_rawdata::two_bytes
Definition: rawdata.h:101
velodyne_rawdata::RawData::unpack
void unpack(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw packet to point cloud
Definition: rawdata.cc:330
data
data
velodyne_rawdata::RawData::sin_rot_table_
float sin_rot_table_[ROTATION_MAX_UNITS]
Definition: rawdata.h:216
velodyne_pointcloud::LaserCorrection::sin_vert_correction
float sin_vert_correction
sine of vert_correction
Definition: calibration.h:72
velodyne_rawdata::VLS128_BANK_4
static const uint16_t VLS128_BANK_4
Definition: rawdata.h:117
velodyne_rawdata::VLS128_MODEL_ID
static const float VLS128_MODEL_ID
Definition: rawdata.h:123
velodyne_pointcloud::Calibration::laser_corrections
std::vector< LaserCorrection > laser_corrections
Definition: calibration.h:83
velodyne_rawdata::RawData::setup
boost::optional< velodyne_pointcloud::Calibration > setup(ros::NodeHandle private_nh)
Set up for data processing.
Definition: rawdata.cc:220
velodyne_rawdata::SQR
float SQR(float val)
Definition: rawdata.cc:41
ROS_WARN_STREAM_THROTTLE
#define ROS_WARN_STREAM_THROTTLE(period, args)
velodyne_rawdata::RawData::loadCalibration
bool loadCalibration()
Definition: rawdata.cc:284
velodyne_rawdata::VLS128_CHANNEL_TDURATION
static const float VLS128_CHANNEL_TDURATION
Definition: rawdata.h:119
rawdata.h
Interfaces for interpreting raw packets from the Velodyne 3D LIDAR.
velodyne_rawdata::raw_block::header
uint16_t header
UPPER_BANK or LOWER_BANK.
Definition: rawdata.h:90
velodyne_rawdata::raw_block
Raw Velodyne data block.
Definition: rawdata.h:88
velodyne_rawdata::RawData::setupOffline
int setupOffline(std::string calibration_file, std::string model, double max_range_, double min_range_)
Set up for data processing offline. Performs the same initialization as in setup, in the abscence of ...
Definition: rawdata.cc:256
velodyne_pointcloud::LaserCorrection
correction values for a single laser
Definition: calibration.h:52
ROS_DEBUG
#define ROS_DEBUG(...)
velodyne_pointcloud::LaserCorrection::focal_slope
float focal_slope
Definition: calibration.h:66
velodyne_rawdata::RawData::calibration_
velodyne_pointcloud::Calibration calibration_
Definition: rawdata.h:215
velodyne_rawdata::two_bytes::uint
uint16_t uint
Definition: rawdata.h:103
velodyne_rawdata::RawData::setupAzimuthCache
void setupAzimuthCache()
Definition: rawdata.cc:311
velodyne_rawdata::RawData::Config::max_angle
int max_angle
maximum angle to publish
Definition: rawdata.h:204
velodyne_pointcloud::LaserCorrection::dist_correction_y
float dist_correction_y
Definition: calibration.h:60
velodyne_rawdata
Definition: datacontainerbase.h:45
velodyne_rawdata::RawData::vls_128_laser_azimuth_cache
float vls_128_laser_azimuth_cache[16]
Definition: rawdata.h:220
velodyne_rawdata::RawData::unpack_vls128
void unpack_vls128(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw VLS128 packet to point cloud
Definition: rawdata.cc:509
ROS_WARN
#define ROS_WARN(...)
velodyne_rawdata::raw_packet
Raw Velodyne packet.
Definition: rawdata.h:139
velodyne_rawdata::ROTATION_RESOLUTION
static const float ROTATION_RESOLUTION
Definition: rawdata.h:67
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
velodyne_pointcloud::LaserCorrection::min_intensity
int min_intensity
Definition: calibration.h:64
package.h
velodyne_rawdata::RawData::cos_rot_table_
float cos_rot_table_[ROTATION_MAX_UNITS]
Definition: rawdata.h:217
velodyne_rawdata::VLS128_DISTANCE_RESOLUTION
static const float VLS128_DISTANCE_RESOLUTION
Definition: rawdata.h:122
velodyne_pointcloud::LaserCorrection::sin_rot_correction
float sin_rot_correction
sine of rot_correction
Definition: calibration.h:70
velodyne_rawdata::VLP16_FIRING_TOFFSET
static const float VLP16_FIRING_TOFFSET
Definition: rawdata.h:79
velodyne_pointcloud::LaserCorrection::cos_vert_correction
float cos_vert_correction
cosine of vert_correction
Definition: calibration.h:71
velodyne_pointcloud::Calibration::distance_resolution_m
float distance_resolution_m
Definition: calibration.h:81
velodyne_rawdata::RawData::timing_offsets
std::vector< std::vector< float > > timing_offsets
Definition: rawdata.h:223
ros::Time
velodyne_rawdata::VLS128_BANK_2
static const uint16_t VLS128_BANK_2
Definition: rawdata.h:115
velodyne_rawdata::RawData::setParameters
void setParameters(double min_range, double max_range, double view_direction, double view_width)
Definition: rawdata.cc:52
velodyne_rawdata::raw_block::data
uint8_t data[BLOCK_DATA_SIZE]
Definition: rawdata.h:92
velodyne_pointcloud::LaserCorrection::two_pt_correction_available
bool two_pt_correction_available
Definition: calibration.h:58
ROS_ERROR
#define ROS_ERROR(...)
velodyne_rawdata::VLP16_SCANS_PER_FIRING
static const int VLP16_SCANS_PER_FIRING
Definition: rawdata.h:76
velodyne_pointcloud::LaserCorrection::laser_ring
int laser_ring
ring number for this laser
Definition: calibration.h:74
velodyne_rawdata::RawData::Config::model
std::string model
Definition: rawdata.h:199
velodyne_pointcloud::LaserCorrection::dist_correction
float dist_correction
Definition: calibration.h:57
velodyne_rawdata::RawData::unpack_vlp16
void unpack_vlp16(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw VLP16 packet to point cloud
Definition: rawdata.cc:648
velodyne_rawdata::RAW_SCAN_SIZE
static const int RAW_SCAN_SIZE
Definition: rawdata.h:63
velodyne_rawdata::VLS128_SEQ_TDURATION
static const float VLS128_SEQ_TDURATION
Definition: rawdata.h:120
velodyne_rawdata::LOWER_BANK
static const uint16_t LOWER_BANK
Definition: rawdata.h:72
velodyne_rawdata::RawData::scansPerPacket
int scansPerPacket() const
Definition: rawdata.cc:80
velodyne_rawdata::RawData::Config::tmp_max_angle
double tmp_max_angle
Definition: rawdata.h:207
velodyne_pointcloud::LaserCorrection::horiz_offset_correction
float horiz_offset_correction
Definition: calibration.h:62
velodyne_pointcloud::Calibration::read
void read(const std::string &calibration_file)
Definition: calibration.cc:251
velodyne_rawdata::raw_block::rotation
uint16_t rotation
0-35999, divide by 100 to get degrees
Definition: rawdata.h:91
velodyne_pointcloud::LaserCorrection::focal_distance
float focal_distance
Definition: calibration.h:65
velodyne_pointcloud::LaserCorrection::cos_rot_correction
float cos_rot_correction
cosine of rot_correction
Definition: calibration.h:69
velodyne_rawdata::RawData::Config::calibrationFile
std::string calibrationFile
calibration file name
Definition: rawdata.h:200
velodyne_rawdata::VLS128_BANK_3
static const uint16_t VLS128_BANK_3
Definition: rawdata.h:116
ros::NodeHandle
angles.h
velodyne_pointcloud::LaserCorrection::max_intensity
int max_intensity
Definition: calibration.h:63
velodyne_rawdata::RawData::config_
Config config_
Definition: rawdata.h:210
velodyne_pointcloud::LaserCorrection::dist_correction_x
float dist_correction_x
Definition: calibration.h:59
velodyne_rawdata::RawData::Config::max_range
double max_range
maximum range to publish
Definition: rawdata.h:201


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Tue May 2 2023 02:28:04