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  *
5  * License: Modified BSD Software License Agreement
6  *
7  * $Id$
8  */
9 
28 #include <fstream>
29 #include <math.h>
30 
31 #include <ros/ros.h>
32 #include <ros/package.h>
33 #include <angles/angles.h>
34 
36 
37 namespace velodyne_rawdata
38 {
39 inline float SQR(float val) { return val*val; }
40 
42  //
43  // RawData base class implementation
44  //
46 
48 
50  void RawData::setParameters(double min_range,
51  double max_range,
52  double view_direction,
53  double view_width)
54  {
55  config_.min_range = min_range;
56  config_.max_range = max_range;
57 
58  //converting angle parameters into the velodyne reference (rad)
59  config_.tmp_min_angle = view_direction + view_width/2;
60  config_.tmp_max_angle = view_direction - view_width/2;
61 
62  //computing positive modulo to keep theses angles into [0;2*M_PI]
63  config_.tmp_min_angle = fmod(fmod(config_.tmp_min_angle,2*M_PI) + 2*M_PI,2*M_PI);
64  config_.tmp_max_angle = fmod(fmod(config_.tmp_max_angle,2*M_PI) + 2*M_PI,2*M_PI);
65 
66  //converting into the hardware velodyne ref (negative yaml and degrees)
67  //adding 0.5 perfomrs a centered double to int conversion
68  config_.min_angle = 100 * (2*M_PI - config_.tmp_min_angle) * 180 / M_PI + 0.5;
69  config_.max_angle = 100 * (2*M_PI - config_.tmp_max_angle) * 180 / M_PI + 0.5;
71  {
72  //avoid returning empty cloud if min_angle = max_angle
73  config_.min_angle = 0;
74  config_.max_angle = 36000;
75  }
76  }
77 
79  {
80  if( calibration_.num_lasers == 16)
81  {
84  }
85  else{
87  }
88  }
89 
91  boost::optional<velodyne_pointcloud::Calibration> RawData::setup(ros::NodeHandle private_nh)
92  {
93  // get path to angles.config file for this device
94  if (!private_nh.getParam("calibration", config_.calibrationFile))
95  {
96  ROS_ERROR_STREAM("No calibration angles specified! Using test values!");
97 
98  // have to use something: grab unit test version as a default
99  std::string pkgPath = ros::package::getPath("velodyne_pointcloud");
100  config_.calibrationFile = pkgPath + "/params/64e_utexas.yaml";
101  }
102 
103  ROS_INFO_STREAM("correction angles: " << config_.calibrationFile);
104 
106  if (!calibration_.initialized) {
107  ROS_ERROR_STREAM("Unable to open calibration file: " <<
109  return boost::none;
110  }
111 
112  ROS_INFO_STREAM("Number of lasers: " << calibration_.num_lasers << ".");
113 
114  // Set up cached values for sin and cos of all the possible headings
115  for (uint16_t rot_index = 0; rot_index < ROTATION_MAX_UNITS; ++rot_index) {
116  float rotation = angles::from_degrees(ROTATION_RESOLUTION * rot_index);
117  cos_rot_table_[rot_index] = cosf(rotation);
118  sin_rot_table_[rot_index] = sinf(rotation);
119  }
120  return calibration_;
121  }
122 
123 
125  int RawData::setupOffline(std::string calibration_file, double max_range_, double min_range_)
126  {
127 
128  config_.max_range = max_range_;
129  config_.min_range = min_range_;
130  ROS_INFO_STREAM("data ranges to publish: ["
131  << config_.min_range << ", "
132  << config_.max_range << "]");
133 
134  config_.calibrationFile = calibration_file;
135 
136  ROS_INFO_STREAM("correction angles: " << config_.calibrationFile);
137 
139  if (!calibration_.initialized) {
140  ROS_ERROR_STREAM("Unable to open calibration file: " <<
142  return -1;
143  }
144 
145  // Set up cached values for sin and cos of all the possible headings
146  for (uint16_t rot_index = 0; rot_index < ROTATION_MAX_UNITS; ++rot_index) {
147  float rotation = angles::from_degrees(ROTATION_RESOLUTION * rot_index);
148  cos_rot_table_[rot_index] = cosf(rotation);
149  sin_rot_table_[rot_index] = sinf(rotation);
150  }
151  return 0;
152  }
153 
154 
160  void RawData::unpack(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase& data)
161  {
163  ROS_DEBUG_STREAM("Received packet, time: " << pkt.stamp);
164 
166  if (calibration_.num_lasers == 16)
167  {
168  unpack_vlp16(pkt, data);
169  return;
170  }
171 
172  const raw_packet_t *raw = (const raw_packet_t *) &pkt.data[0];
173 
174  for (int i = 0; i < BLOCKS_PER_PACKET; i++) {
175 
176  // upper bank lasers are numbered [0..31]
177  // NOTE: this is a change from the old velodyne_common implementation
178 
179  int bank_origin = 0;
180  if (raw->blocks[i].header == LOWER_BANK) {
181  // lower bank lasers are [32..63]
182  bank_origin = 32;
183  }
184 
185  for (int j = 0, k = 0; j < SCANS_PER_BLOCK; j++, k += RAW_SCAN_SIZE) {
186 
187  float x, y, z;
188  float intensity;
189  const uint8_t laser_number = j + bank_origin;
190 
191  const LaserCorrection &corrections = calibration_.laser_corrections[laser_number];
192 
194  const raw_block_t &block = raw->blocks[i];
195  union two_bytes tmp;
196  tmp.bytes[0] = block.data[k];
197  tmp.bytes[1] = block.data[k+1];
198  if (tmp.bytes[0]==0 &&tmp.bytes[1]==0 ) //no laser beam return
199  {
200  continue;
201  }
202 
203  /*condition added to avoid calculating points which are not
204  in the interesting defined area (min_angle < area < max_angle)*/
205  if ((block.rotation >= config_.min_angle
206  && block.rotation <= config_.max_angle
209  && (raw->blocks[i].rotation <= config_.max_angle
210  || raw->blocks[i].rotation >= config_.min_angle))){
212  distance += corrections.dist_correction;
213 
214  float cos_vert_angle = corrections.cos_vert_correction;
215  float sin_vert_angle = corrections.sin_vert_correction;
216  float cos_rot_correction = corrections.cos_rot_correction;
217  float sin_rot_correction = corrections.sin_rot_correction;
218 
219  // cos(a-b) = cos(a)*cos(b) + sin(a)*sin(b)
220  // sin(a-b) = sin(a)*cos(b) - cos(a)*sin(b)
221  float cos_rot_angle =
222  cos_rot_table_[block.rotation] * cos_rot_correction +
223  sin_rot_table_[block.rotation] * sin_rot_correction;
224  float sin_rot_angle =
225  sin_rot_table_[block.rotation] * cos_rot_correction -
226  cos_rot_table_[block.rotation] * sin_rot_correction;
227 
228  float horiz_offset = corrections.horiz_offset_correction;
229  float vert_offset = corrections.vert_offset_correction;
230 
231  // Compute the distance in the xy plane (w/o accounting for rotation)
236  float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
237 
238  // Calculate temporal X, use absolute value.
239  float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
240  // Calculate temporal Y, use absolute value
241  float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
242  if (xx < 0) xx=-xx;
243  if (yy < 0) yy=-yy;
244 
245  // Get 2points calibration values,Linear interpolation to get distance
246  // correction for X and Y, that means distance correction use
247  // different value at different distance
248  float distance_corr_x = 0;
249  float distance_corr_y = 0;
250  if (corrections.two_pt_correction_available) {
251  distance_corr_x =
252  (corrections.dist_correction - corrections.dist_correction_x)
253  * (xx - 2.4) / (25.04 - 2.4)
254  + corrections.dist_correction_x;
255  distance_corr_x -= corrections.dist_correction;
256  distance_corr_y =
257  (corrections.dist_correction - corrections.dist_correction_y)
258  * (yy - 1.93) / (25.04 - 1.93)
259  + corrections.dist_correction_y;
260  distance_corr_y -= corrections.dist_correction;
261  }
262 
263  float distance_x = distance + distance_corr_x;
268  xy_distance = distance_x * cos_vert_angle - vert_offset * sin_vert_angle ;
270  x = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
271 
272  float distance_y = distance + distance_corr_y;
273  xy_distance = distance_y * cos_vert_angle - vert_offset * sin_vert_angle ;
278  y = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
279 
280  // Using distance_y is not symmetric, but the velodyne manual
281  // does this.
286  z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
287 
289  float x_coord = y;
290  float y_coord = -x;
291  float z_coord = z;
292 
295  float min_intensity = corrections.min_intensity;
296  float max_intensity = corrections.max_intensity;
297 
298  intensity = raw->blocks[i].data[k+2];
299 
300  float focal_offset = 256
301  * (1 - corrections.focal_distance / 13100)
302  * (1 - corrections.focal_distance / 13100);
303  float focal_slope = corrections.focal_slope;
304  intensity += focal_slope * (std::abs(focal_offset - 256 *
305  SQR(1 - static_cast<float>(tmp.uint)/65535)));
306  intensity = (intensity < min_intensity) ? min_intensity : intensity;
307  intensity = (intensity > max_intensity) ? max_intensity : intensity;
308 
309  data.addPoint(x_coord, y_coord, z_coord, corrections.laser_ring, raw->blocks[i].rotation, distance, intensity);
310  }
311  }
312  data.newLine();
313  }
314  }
315 
321  void RawData::unpack_vlp16(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase& data)
322  {
323  float azimuth;
324  float azimuth_diff;
325  int raw_azimuth_diff;
326  float last_azimuth_diff=0;
327  float azimuth_corrected_f;
328  int azimuth_corrected;
329  float x, y, z;
330  float intensity;
331 
332  const raw_packet_t *raw = (const raw_packet_t *) &pkt.data[0];
333 
334  for (int block = 0; block < BLOCKS_PER_PACKET; block++) {
335 
336  // ignore packets with mangled or otherwise different contents
337  if (UPPER_BANK != raw->blocks[block].header) {
338  // Do not flood the log with messages, only issue at most one
339  // of these warnings per minute.
340  ROS_WARN_STREAM_THROTTLE(60, "skipping invalid VLP-16 packet: block "
341  << block << " header value is "
342  << raw->blocks[block].header);
343  return; // bad packet: skip the rest
344  }
345 
346  // Calculate difference between current and next block's azimuth angle.
347  azimuth = (float)(raw->blocks[block].rotation);
348  if (block < (BLOCKS_PER_PACKET-1)){
349  raw_azimuth_diff = raw->blocks[block+1].rotation - raw->blocks[block].rotation;
350  azimuth_diff = (float)((36000 + raw_azimuth_diff)%36000);
351  // some packets contain an angle overflow where azimuth_diff < 0
352  if(raw_azimuth_diff < 0)//raw->blocks[block+1].rotation - raw->blocks[block].rotation < 0)
353  {
354  ROS_WARN_STREAM_THROTTLE(60, "Packet containing angle overflow, first angle: " << raw->blocks[block].rotation << " second angle: " << raw->blocks[block+1].rotation);
355  // 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
356  if(last_azimuth_diff > 0){
357  azimuth_diff = last_azimuth_diff;
358  }
359  // otherwise we are not able to use this data
360  // TODO: we might just not use the second 16 firings
361  else{
362  continue;
363  }
364  }
365  last_azimuth_diff = azimuth_diff;
366  }else{
367  azimuth_diff = last_azimuth_diff;
368  }
369 
370  for (int firing=0, k=0; firing < VLP16_FIRINGS_PER_BLOCK; firing++){
371  for (int dsr=0; dsr < VLP16_SCANS_PER_FIRING; dsr++, k+=RAW_SCAN_SIZE){
373 
375  union two_bytes tmp;
376  tmp.bytes[0] = raw->blocks[block].data[k];
377  tmp.bytes[1] = raw->blocks[block].data[k+1];
378 
380  azimuth_corrected_f = azimuth + (azimuth_diff * ((dsr*VLP16_DSR_TOFFSET) + (firing*VLP16_FIRING_TOFFSET)) / VLP16_BLOCK_TDURATION);
381  azimuth_corrected = ((int)round(azimuth_corrected_f)) % 36000;
382 
383  /*condition added to avoid calculating points which are not
384  in the interesting defined area (min_angle < area < max_angle)*/
385  if ((azimuth_corrected >= config_.min_angle
386  && azimuth_corrected <= config_.max_angle
389  && (azimuth_corrected <= config_.max_angle
390  || azimuth_corrected >= config_.min_angle))){
391 
392  // convert polar coordinates to Euclidean XYZ
394  distance += corrections.dist_correction;
395 
396  float cos_vert_angle = corrections.cos_vert_correction;
397  float sin_vert_angle = corrections.sin_vert_correction;
398  float cos_rot_correction = corrections.cos_rot_correction;
399  float sin_rot_correction = corrections.sin_rot_correction;
400 
401  // cos(a-b) = cos(a)*cos(b) + sin(a)*sin(b)
402  // sin(a-b) = sin(a)*cos(b) - cos(a)*sin(b)
403  float cos_rot_angle =
404  cos_rot_table_[azimuth_corrected] * cos_rot_correction +
405  sin_rot_table_[azimuth_corrected] * sin_rot_correction;
406  float sin_rot_angle =
407  sin_rot_table_[azimuth_corrected] * cos_rot_correction -
408  cos_rot_table_[azimuth_corrected] * sin_rot_correction;
409 
410  float horiz_offset = corrections.horiz_offset_correction;
411  float vert_offset = corrections.vert_offset_correction;
412 
413  // Compute the distance in the xy plane (w/o accounting for rotation)
418  float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
419 
420  // Calculate temporal X, use absolute value.
421  float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
422  // Calculate temporal Y, use absolute value
423  float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
424  if (xx < 0) xx=-xx;
425  if (yy < 0) yy=-yy;
426 
427  // Get 2points calibration values,Linear interpolation to get distance
428  // correction for X and Y, that means distance correction use
429  // different value at different distance
430  float distance_corr_x = 0;
431  float distance_corr_y = 0;
432  if (corrections.two_pt_correction_available) {
433  distance_corr_x =
434  (corrections.dist_correction - corrections.dist_correction_x)
435  * (xx - 2.4) / (25.04 - 2.4)
436  + corrections.dist_correction_x;
437  distance_corr_x -= corrections.dist_correction;
438  distance_corr_y =
439  (corrections.dist_correction - corrections.dist_correction_y)
440  * (yy - 1.93) / (25.04 - 1.93)
441  + corrections.dist_correction_y;
442  distance_corr_y -= corrections.dist_correction;
443  }
444 
445  float distance_x = distance + distance_corr_x;
450  xy_distance = distance_x * cos_vert_angle - vert_offset * sin_vert_angle ;
451  x = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
452 
453  float distance_y = distance + distance_corr_y;
458  xy_distance = distance_y * cos_vert_angle - vert_offset * sin_vert_angle ;
459  y = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
460 
461  // Using distance_y is not symmetric, but the velodyne manual
462  // does this.
467  z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
468 
469 
471  float x_coord = y;
472  float y_coord = -x;
473  float z_coord = z;
474 
476  float min_intensity = corrections.min_intensity;
477  float max_intensity = corrections.max_intensity;
478 
479  intensity = raw->blocks[block].data[k+2];
480 
481  float focal_offset = 256 * SQR(1 - corrections.focal_distance / 13100);
482  float focal_slope = corrections.focal_slope;
483  intensity += focal_slope * (std::abs(focal_offset - 256 *
484  SQR(1 - tmp.uint/65535)));
485  intensity = (intensity < min_intensity) ? min_intensity : intensity;
486  intensity = (intensity > max_intensity) ? max_intensity : intensity;
487 
488  data.addPoint(x_coord, y_coord, z_coord, corrections.laser_ring, azimuth_corrected, distance, intensity);
489  }
490  }
491  data.newLine();
492  }
493  }
494  }
495 } // namespace velodyne_rawdata
Raw Velodyne packet.
Definition: rawdata.h:123
int scansPerPacket() const
Definition: rawdata.cc:78
Interfaces for interpreting raw packets from the Velodyne 3D LIDAR.
float cos_rot_table_[ROTATION_MAX_UNITS]
Definition: rawdata.h:192
#define ROS_WARN_STREAM_THROTTLE(period, args)
void unpack_vlp16(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data)
convert raw VLP16 packet to point cloud
Definition: rawdata.cc:321
int setupOffline(std::string calibration_file, 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:125
Raw Velodyne data block.
Definition: rawdata.h:87
std::string calibrationFile
calibration file name
Definition: rawdata.h:175
static const int SCANS_PER_BLOCK
Definition: rawdata.h:63
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
void setParameters(double min_range, double max_range, double view_direction, double view_width)
Definition: rawdata.cc:50
TFSIMD_FORCE_INLINE const tfScalar & y() const
void unpack(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data)
convert raw packet to point cloud
Definition: rawdata.cc:160
float sin_vert_correction
sine of vert_correction
Definition: calibration.h:72
static const float ROTATION_RESOLUTION
Definition: rawdata.h:66
static const uint16_t UPPER_BANK
Definition: rawdata.h:70
static const int RAW_SCAN_SIZE
Definition: rawdata.h:62
static const float VLP16_FIRING_TOFFSET
Definition: rawdata.h:78
std::vector< LaserCorrection > laser_corrections
Definition: calibration.h:83
float SQR(float val)
Definition: rawdata.cc:39
int max_angle
maximum angle to publish
Definition: rawdata.h:179
static const uint16_t ROTATION_MAX_UNITS
Definition: rawdata.h:67
raw_block_t blocks[BLOCKS_PER_PACKET]
Definition: rawdata.h:125
static double from_degrees(double degrees)
TFSIMD_FORCE_INLINE const tfScalar & x() const
virtual void addPoint(float x, float y, float z, const uint16_t ring, const uint16_t azimuth, const float distance, const float intensity)=0
static const uint16_t LOWER_BANK
Definition: rawdata.h:71
static const float VLP16_DSR_TOFFSET
Definition: rawdata.h:77
#define ROS_DEBUG_STREAM(args)
uint16_t rotation
0-35999, divide by 100 to get degrees
Definition: rawdata.h:90
ROSLIB_DECL std::string getPath(const std::string &package_name)
TFSIMD_FORCE_INLINE const tfScalar & z() const
correction values for a single laser
Definition: calibration.h:52
static const float VLP16_BLOCK_TDURATION
Definition: rawdata.h:76
int min_angle
minimum angle to publish
Definition: rawdata.h:178
#define ROS_INFO_STREAM(args)
double min_range
minimum range to publish
Definition: rawdata.h:177
double max_range
maximum range to publish
Definition: rawdata.h:176
float sin_rot_correction
sine of rot_correction
Definition: calibration.h:70
static const int BLOCKS_PER_PACKET
Definition: rawdata.h:107
static const int VLP16_SCANS_PER_FIRING
Definition: rawdata.h:75
bool getParam(const std::string &key, std::string &s) const
float sin_rot_table_[ROTATION_MAX_UNITS]
Definition: rawdata.h:191
int laser_ring
ring number for this laser
Definition: calibration.h:74
uint8_t data[BLOCK_DATA_SIZE]
Definition: rawdata.h:91
float cos_rot_correction
cosine of rot_correction
Definition: calibration.h:69
#define ROS_ERROR_STREAM(args)
uint16_t header
UPPER_BANK or LOWER_BANK.
Definition: rawdata.h:89
void read(const std::string &calibration_file)
Definition: calibration.cc:251
float cos_vert_correction
cosine of vert_correction
Definition: calibration.h:71
static const int VLP16_FIRINGS_PER_BLOCK
Definition: rawdata.h:74
velodyne_pointcloud::Calibration calibration_
Definition: rawdata.h:190
boost::optional< velodyne_pointcloud::Calibration > setup(ros::NodeHandle private_nh)
Set up for data processing.
Definition: rawdata.cc:91


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Thu Jul 4 2019 19:09:30