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{
176  timing_offsets.clear();
177  ROS_WARN("Timings not supported for model %s", config_.model.c_str());
178  }
179 
180  if (timing_offsets.size()){
181  // ROS_INFO("VELODYNE TIMING TABLE:");
182  for (size_t x = 0; x < timing_offsets.size(); ++x){
183  for (size_t y = 0; y < timing_offsets[x].size(); ++y){
184  printf("%04.3f ", timing_offsets[x][y] * 1e6);
185  }
186  printf("\n");
187  }
188  return true;
189  }
190  else{
191  ROS_WARN("NO TIMING OFFSETS CALCULATED. ARE YOU USING A SUPPORTED VELODYNE SENSOR?");
192  }
193  return false;
194  }
195 
197  boost::optional<velodyne_pointcloud::Calibration> RawData::setup(ros::NodeHandle private_nh)
198  {
199  private_nh.param("model", config_.model, std::string("64E"));
200  buildTimings();
201 
202  // get path to angles.config file for this device
203  if (!private_nh.getParam("calibration", config_.calibrationFile))
204  {
205  ROS_ERROR_STREAM("No calibration angles specified! Using test values!");
206 
207  // have to use something: grab unit test version as a default
208  std::string pkgPath = ros::package::getPath("velodyne_pointcloud");
209  config_.calibrationFile = pkgPath + "/params/64e_utexas.yaml";
210  }
211 
212  ROS_INFO_STREAM("correction angles: " << config_.calibrationFile);
213 
215  if (!calibration_.initialized) {
216  ROS_ERROR_STREAM("Unable to open calibration file: " <<
218  return boost::none;
219  }
220 
221  ROS_INFO_STREAM("Number of lasers: " << calibration_.num_lasers << ".");
222 
223  // Set up cached values for sin and cos of all the possible headings
224  for (uint16_t rot_index = 0; rot_index < ROTATION_MAX_UNITS; ++rot_index) {
225  float rotation = angles::from_degrees(ROTATION_RESOLUTION * rot_index);
226  cos_rot_table_[rot_index] = cosf(rotation);
227  sin_rot_table_[rot_index] = sinf(rotation);
228  }
229  return calibration_;
230  }
231 
233  int RawData::setupOffline(std::string calibration_file, double max_range_, double min_range_)
234  {
235 
236  config_.max_range = max_range_;
237  config_.min_range = min_range_;
238  ROS_INFO_STREAM("data ranges to publish: ["
239  << config_.min_range << ", "
240  << config_.max_range << "]");
241 
242  config_.calibrationFile = calibration_file;
243 
244  ROS_INFO_STREAM("correction angles: " << config_.calibrationFile);
245 
247  if (!calibration_.initialized) {
248  ROS_ERROR_STREAM("Unable to open calibration file: " << config_.calibrationFile);
249  return -1;
250  }
251 
252  // Set up cached values for sin and cos of all the possible headings
253  for (uint16_t rot_index = 0; rot_index < ROTATION_MAX_UNITS; ++rot_index) {
254  float rotation = angles::from_degrees(ROTATION_RESOLUTION * rot_index);
255  cos_rot_table_[rot_index] = cosf(rotation);
256  sin_rot_table_[rot_index] = sinf(rotation);
257  }
258  return 0;
259  }
260 
261 
267  void RawData::unpack(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase& data, const ros::Time& scan_start_time)
268  {
270  ROS_DEBUG_STREAM("Received packet, time: " << pkt.stamp);
271 
273  if (calibration_.num_lasers == 16)
274  {
275  unpack_vlp16(pkt, data, scan_start_time);
276  return;
277  }
278 
279  float time_diff_start_to_this_packet = (pkt.stamp - scan_start_time).toSec();
280 
281  const raw_packet_t *raw = (const raw_packet_t *) &pkt.data[0];
282 
283  for (int i = 0; i < BLOCKS_PER_PACKET; i++) {
284 
285  // upper bank lasers are numbered [0..31]
286  // NOTE: this is a change from the old velodyne_common implementation
287 
288  int bank_origin = 0;
289  if (raw->blocks[i].header == LOWER_BANK) {
290  // lower bank lasers are [32..63]
291  bank_origin = 32;
292  }
293 
294  for (int j = 0, k = 0; j < SCANS_PER_BLOCK; j++, k += RAW_SCAN_SIZE) {
295 
296  float x, y, z;
297  float intensity;
298  const uint8_t laser_number = j + bank_origin;
299  float time = 0;
300 
301  const LaserCorrection &corrections = calibration_.laser_corrections[laser_number];
302 
304  const raw_block_t &block = raw->blocks[i];
305  union two_bytes tmp;
306  tmp.bytes[0] = block.data[k];
307  tmp.bytes[1] = block.data[k+1];
308 
309  /*condition added to avoid calculating points which are not
310  in the interesting defined area (min_angle < area < max_angle)*/
311  if ((block.rotation >= config_.min_angle
312  && block.rotation <= config_.max_angle
315  && (raw->blocks[i].rotation <= config_.max_angle
316  || raw->blocks[i].rotation >= config_.min_angle))){
317 
318  if (timing_offsets.size())
319  {
320  time = timing_offsets[i][j] + time_diff_start_to_this_packet;
321  }
322 
323  if (tmp.uint == 0) // no valid laser beam return
324  {
325  // call to addPoint is still required since output could be organized
326  data.addPoint(nanf(""), nanf(""), nanf(""), corrections.laser_ring, raw->blocks[i].rotation, nanf(""), nanf(""), time);
327  continue;
328  }
329 
331  distance += corrections.dist_correction;
332 
333  float cos_vert_angle = corrections.cos_vert_correction;
334  float sin_vert_angle = corrections.sin_vert_correction;
335  float cos_rot_correction = corrections.cos_rot_correction;
336  float sin_rot_correction = corrections.sin_rot_correction;
337 
338  // cos(a-b) = cos(a)*cos(b) + sin(a)*sin(b)
339  // sin(a-b) = sin(a)*cos(b) - cos(a)*sin(b)
340  float cos_rot_angle =
341  cos_rot_table_[block.rotation] * cos_rot_correction +
342  sin_rot_table_[block.rotation] * sin_rot_correction;
343  float sin_rot_angle =
344  sin_rot_table_[block.rotation] * cos_rot_correction -
345  cos_rot_table_[block.rotation] * sin_rot_correction;
346 
347  float horiz_offset = corrections.horiz_offset_correction;
348  float vert_offset = corrections.vert_offset_correction;
349 
350  // Compute the distance in the xy plane (w/o accounting for rotation)
355  float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
356 
357  // Calculate temporal X, use absolute value.
358  float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
359  // Calculate temporal Y, use absolute value
360  float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
361  if (xx < 0) xx=-xx;
362  if (yy < 0) yy=-yy;
363 
364  // Get 2points calibration values,Linear interpolation to get distance
365  // correction for X and Y, that means distance correction use
366  // different value at different distance
367  float distance_corr_x = 0;
368  float distance_corr_y = 0;
369  if (corrections.two_pt_correction_available) {
370  distance_corr_x =
371  (corrections.dist_correction - corrections.dist_correction_x)
372  * (xx - 2.4) / (25.04 - 2.4)
373  + corrections.dist_correction_x;
374  distance_corr_x -= corrections.dist_correction;
375  distance_corr_y =
376  (corrections.dist_correction - corrections.dist_correction_y)
377  * (yy - 1.93) / (25.04 - 1.93)
378  + corrections.dist_correction_y;
379  distance_corr_y -= corrections.dist_correction;
380  }
381 
382  float distance_x = distance + distance_corr_x;
387  xy_distance = distance_x * cos_vert_angle - vert_offset * sin_vert_angle ;
389  x = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
390 
391  float distance_y = distance + distance_corr_y;
392  xy_distance = distance_y * cos_vert_angle - vert_offset * sin_vert_angle ;
397  y = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
398 
399  // Using distance_y is not symmetric, but the velodyne manual
400  // does this.
405  z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
406 
408  float x_coord = y;
409  float y_coord = -x;
410  float z_coord = z;
411 
414  float min_intensity = corrections.min_intensity;
415  float max_intensity = corrections.max_intensity;
416 
417  intensity = raw->blocks[i].data[k+2];
418 
419  float focal_offset = 256
420  * (1 - corrections.focal_distance / 13100)
421  * (1 - corrections.focal_distance / 13100);
422  float focal_slope = corrections.focal_slope;
423  intensity += focal_slope * (std::abs(focal_offset - 256 *
424  SQR(1 - static_cast<float>(tmp.uint)/65535)));
425  intensity = (intensity < min_intensity) ? min_intensity : intensity;
426  intensity = (intensity > max_intensity) ? max_intensity : intensity;
427 
428  data.addPoint(x_coord, y_coord, z_coord, corrections.laser_ring, raw->blocks[i].rotation, distance, intensity, time);
429  }
430  }
431  data.newLine();
432  }
433  }
434 
440  void RawData::unpack_vlp16(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase& data, const ros::Time& scan_start_time)
441  {
442  float azimuth;
443  float azimuth_diff;
444  int raw_azimuth_diff;
445  float last_azimuth_diff=0;
446  float azimuth_corrected_f;
447  int azimuth_corrected;
448  float x, y, z;
449  float intensity;
450 
451  float time_diff_start_to_this_packet = (pkt.stamp - scan_start_time).toSec();
452 
453  const raw_packet_t *raw = (const raw_packet_t *) &pkt.data[0];
454 
455  for (int block = 0; block < BLOCKS_PER_PACKET; block++) {
456 
457  // ignore packets with mangled or otherwise different contents
458  if (UPPER_BANK != raw->blocks[block].header) {
459  // Do not flood the log with messages, only issue at most one
460  // of these warnings per minute.
461  ROS_WARN_STREAM_THROTTLE(60, "skipping invalid VLP-16 packet: block "
462  << block << " header value is "
463  << raw->blocks[block].header);
464  return; // bad packet: skip the rest
465  }
466 
467  // Calculate difference between current and next block's azimuth angle.
468  azimuth = (float)(raw->blocks[block].rotation);
469  if (block < (BLOCKS_PER_PACKET-1)){
470  raw_azimuth_diff = raw->blocks[block+1].rotation - raw->blocks[block].rotation;
471  azimuth_diff = (float)((36000 + raw_azimuth_diff)%36000);
472  // some packets contain an angle overflow where azimuth_diff < 0
473  if(raw_azimuth_diff < 0)//raw->blocks[block+1].rotation - raw->blocks[block].rotation < 0)
474  {
475  ROS_WARN_STREAM_THROTTLE(60, "Packet containing angle overflow, first angle: " << raw->blocks[block].rotation << " second angle: " << raw->blocks[block+1].rotation);
476  // 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
477  if(last_azimuth_diff > 0){
478  azimuth_diff = last_azimuth_diff;
479  }
480  // otherwise we are not able to use this data
481  // TODO: we might just not use the second 16 firings
482  else{
483  continue;
484  }
485  }
486  last_azimuth_diff = azimuth_diff;
487  }else{
488  azimuth_diff = last_azimuth_diff;
489  }
490 
491  for (int firing=0, k=0; firing < VLP16_FIRINGS_PER_BLOCK; firing++){
492  for (int dsr=0; dsr < VLP16_SCANS_PER_FIRING; dsr++, k+=RAW_SCAN_SIZE){
494 
496  union two_bytes tmp;
497  tmp.bytes[0] = raw->blocks[block].data[k];
498  tmp.bytes[1] = raw->blocks[block].data[k+1];
499 
501  azimuth_corrected_f = azimuth + (azimuth_diff * ((dsr*VLP16_DSR_TOFFSET) + (firing*VLP16_FIRING_TOFFSET)) / VLP16_BLOCK_TDURATION);
502  azimuth_corrected = ((int)round(azimuth_corrected_f)) % 36000;
503 
504  /*condition added to avoid calculating points which are not
505  in the interesting defined area (min_angle < area < max_angle)*/
506  if ((azimuth_corrected >= config_.min_angle
507  && azimuth_corrected <= config_.max_angle
510  && (azimuth_corrected <= config_.max_angle
511  || azimuth_corrected >= config_.min_angle))){
512 
513  // convert polar coordinates to Euclidean XYZ
515  distance += corrections.dist_correction;
516 
517  float cos_vert_angle = corrections.cos_vert_correction;
518  float sin_vert_angle = corrections.sin_vert_correction;
519  float cos_rot_correction = corrections.cos_rot_correction;
520  float sin_rot_correction = corrections.sin_rot_correction;
521 
522  // cos(a-b) = cos(a)*cos(b) + sin(a)*sin(b)
523  // sin(a-b) = sin(a)*cos(b) - cos(a)*sin(b)
524  float cos_rot_angle =
525  cos_rot_table_[azimuth_corrected] * cos_rot_correction +
526  sin_rot_table_[azimuth_corrected] * sin_rot_correction;
527  float sin_rot_angle =
528  sin_rot_table_[azimuth_corrected] * cos_rot_correction -
529  cos_rot_table_[azimuth_corrected] * sin_rot_correction;
530 
531  float horiz_offset = corrections.horiz_offset_correction;
532  float vert_offset = corrections.vert_offset_correction;
533 
534  // Compute the distance in the xy plane (w/o accounting for rotation)
539  float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
540 
541  // Calculate temporal X, use absolute value.
542  float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
543  // Calculate temporal Y, use absolute value
544  float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
545  if (xx < 0) xx=-xx;
546  if (yy < 0) yy=-yy;
547 
548  // Get 2points calibration values,Linear interpolation to get distance
549  // correction for X and Y, that means distance correction use
550  // different value at different distance
551  float distance_corr_x = 0;
552  float distance_corr_y = 0;
553  if (corrections.two_pt_correction_available) {
554  distance_corr_x =
555  (corrections.dist_correction - corrections.dist_correction_x)
556  * (xx - 2.4) / (25.04 - 2.4)
557  + corrections.dist_correction_x;
558  distance_corr_x -= corrections.dist_correction;
559  distance_corr_y =
560  (corrections.dist_correction - corrections.dist_correction_y)
561  * (yy - 1.93) / (25.04 - 1.93)
562  + corrections.dist_correction_y;
563  distance_corr_y -= corrections.dist_correction;
564  }
565 
566  float distance_x = distance + distance_corr_x;
571  xy_distance = distance_x * cos_vert_angle - vert_offset * sin_vert_angle ;
572  x = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
573 
574  float distance_y = distance + distance_corr_y;
579  xy_distance = distance_y * cos_vert_angle - vert_offset * sin_vert_angle ;
580  y = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
581 
582  // Using distance_y is not symmetric, but the velodyne manual
583  // does this.
588  z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
589 
590 
592  float x_coord = y;
593  float y_coord = -x;
594  float z_coord = z;
595 
597  float min_intensity = corrections.min_intensity;
598  float max_intensity = corrections.max_intensity;
599 
600  intensity = raw->blocks[block].data[k+2];
601 
602  float focal_offset = 256 * SQR(1 - corrections.focal_distance / 13100);
603  float focal_slope = corrections.focal_slope;
604  intensity += focal_slope * (std::abs(focal_offset - 256 *
605  SQR(1 - tmp.uint/65535)));
606  intensity = (intensity < min_intensity) ? min_intensity : intensity;
607  intensity = (intensity > max_intensity) ? max_intensity : intensity;
608 
609  float time = 0;
610  if (timing_offsets.size())
611  time = timing_offsets[block][firing * 16 + dsr] + time_diff_start_to_this_packet;
612 
613  data.addPoint(x_coord, y_coord, z_coord, corrections.laser_ring, azimuth_corrected, distance, intensity, time);
614  }
615  }
616  data.newLine();
617  }
618  }
619  }
620 } // namespace velodyne_rawdata
Raw Velodyne packet.
Definition: rawdata.h:124
int scansPerPacket() const
Definition: rawdata.cc:80
Interfaces for interpreting raw packets from the Velodyne 3D LIDAR.
float cos_rot_table_[ROTATION_MAX_UNITS]
Definition: rawdata.h:196
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:233
Raw Velodyne data block.
Definition: rawdata.h:88
std::string calibrationFile
calibration file name
Definition: rawdata.h:179
std::vector< std::vector< float > > timing_offsets
Definition: rawdata.h:199
static const int SCANS_PER_BLOCK
Definition: rawdata.h:64
virtual void addPoint(float x, float y, float z, const uint16_t ring, const uint16_t azimuth, const float distance, const float intensity, const float time)=0
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:52
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
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:440
float sin_vert_correction
sine of vert_correction
Definition: calibration.h:72
static const float ROTATION_RESOLUTION
Definition: rawdata.h:67
static const uint16_t UPPER_BANK
Definition: rawdata.h:71
static const int RAW_SCAN_SIZE
Definition: rawdata.h:63
static const float VLP16_FIRING_TOFFSET
Definition: rawdata.h:79
std::vector< LaserCorrection > laser_corrections
Definition: calibration.h:83
float SQR(float val)
Definition: rawdata.cc:41
int max_angle
maximum angle to publish
Definition: rawdata.h:183
static const uint16_t ROTATION_MAX_UNITS
Definition: rawdata.h:68
raw_block_t blocks[BLOCKS_PER_PACKET]
Definition: rawdata.h:126
static double from_degrees(double degrees)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
static const uint16_t LOWER_BANK
Definition: rawdata.h:72
static const float VLP16_DSR_TOFFSET
Definition: rawdata.h:78
#define ROS_DEBUG_STREAM(args)
uint16_t rotation
0-35999, divide by 100 to get degrees
Definition: rawdata.h:91
ROSLIB_DECL std::string getPath(const std::string &package_name)
TFSIMD_FORCE_INLINE const tfScalar & z() const
#define ROS_WARN_STREAM_THROTTLE(rate, args)
correction values for a single laser
Definition: calibration.h:52
static const float VLP16_BLOCK_TDURATION
Definition: rawdata.h:77
int min_angle
minimum angle to publish
Definition: rawdata.h:182
#define ROS_INFO_STREAM(args)
double min_range
minimum range to publish
Definition: rawdata.h:181
double max_range
maximum range to publish
Definition: rawdata.h:180
float sin_rot_correction
sine of rot_correction
Definition: calibration.h:70
static const int BLOCKS_PER_PACKET
Definition: rawdata.h:108
static const int VLP16_SCANS_PER_FIRING
Definition: rawdata.h:76
bool getParam(const std::string &key, std::string &s) const
void unpack(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw packet to point cloud
Definition: rawdata.cc:267
float sin_rot_table_[ROTATION_MAX_UNITS]
Definition: rawdata.h:195
int laser_ring
ring number for this laser
Definition: calibration.h:74
uint8_t data[BLOCK_DATA_SIZE]
Definition: rawdata.h:92
float cos_rot_correction
cosine of rot_correction
Definition: calibration.h:69
bool buildTimings()
setup per-point timing offsets
Definition: rawdata.cc:95
#define ROS_ERROR_STREAM(args)
uint16_t header
UPPER_BANK or LOWER_BANK.
Definition: rawdata.h:90
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:75
velodyne_pointcloud::Calibration calibration_
Definition: rawdata.h:194
boost::optional< velodyne_pointcloud::Calibration > setup(ros::NodeHandle private_nh)
Set up for data processing.
Definition: rawdata.cc:197


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Sep 6 2020 03:25:30