41 inline float SQR(
float val) {
return val*val; }
54 double view_direction,
104 double full_firing_cycle = 55.296 * 1e-6;
105 double single_firing = 2.304 * 1e-6;
106 double dataBlockIndex, dataPointIndex;
107 bool dual_mode =
false;
112 dataBlockIndex = (
x - (
x % 2)) + (
y / 16);
115 dataBlockIndex = (
x * 2) + (
y / 16);
117 dataPointIndex =
y % 16;
119 timing_offsets[
x][
y] = (full_firing_cycle * dataBlockIndex) + (single_firing * dataPointIndex);
131 double full_firing_cycle = 55.296 * 1e-6;
132 double single_firing = 2.304 * 1e-6;
133 double dataBlockIndex, dataPointIndex;
134 bool dual_mode =
false;
139 dataBlockIndex =
x / 2;
144 dataPointIndex =
y / 2;
145 timing_offsets[
x][
y] = (full_firing_cycle * dataBlockIndex) + (single_firing * dataPointIndex);
157 double full_firing_cycle = 46.080 * 1e-6;
158 double single_firing = 1.152 * 1e-6;
159 double dataBlockIndex, dataPointIndex;
160 bool dual_mode =
false;
165 dataBlockIndex =
x / 2;
170 dataPointIndex =
y / 2;
171 timing_offsets[
x][
y] = (full_firing_cycle * dataBlockIndex) + (single_firing * dataPointIndex);
191 ROS_WARN(
"NO TIMING OFFSETS CALCULATED. ARE YOU USING A SUPPORTED VELODYNE SENSOR?");
279 float time_diff_start_to_this_packet = (pkt.stamp - scan_start_time).toSec();
298 const uint8_t laser_number = j + bank_origin;
326 data.
addPoint(nanf(
""), nanf(
""), nanf(
""), corrections.laser_ring, raw->
blocks[i].
rotation, nanf(
""), nanf(
""), time);
331 distance += corrections.dist_correction;
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;
340 float cos_rot_angle =
343 float sin_rot_angle =
347 float horiz_offset = corrections.horiz_offset_correction;
348 float vert_offset = corrections.vert_offset_correction;
355 float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
358 float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
360 float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
367 float distance_corr_x = 0;
368 float distance_corr_y = 0;
369 if (corrections.two_pt_correction_available) {
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;
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;
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;
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;
405 z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
414 float min_intensity = corrections.min_intensity;
415 float max_intensity = corrections.max_intensity;
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;
428 data.
addPoint(x_coord, y_coord, z_coord, corrections.laser_ring, raw->
blocks[i].
rotation, distance, intensity, time);
444 int raw_azimuth_diff;
445 float last_azimuth_diff=0;
446 float azimuth_corrected_f;
447 int azimuth_corrected;
451 float time_diff_start_to_this_packet = (pkt.stamp - scan_start_time).toSec();
462 << block <<
" header value is " 469 if (block < (BLOCKS_PER_PACKET-1)){
471 azimuth_diff = (float)((36000 + raw_azimuth_diff)%36000);
473 if(raw_azimuth_diff < 0)
477 if(last_azimuth_diff > 0){
478 azimuth_diff = last_azimuth_diff;
486 last_azimuth_diff = azimuth_diff;
488 azimuth_diff = last_azimuth_diff;
502 azimuth_corrected = ((int)round(azimuth_corrected_f)) % 36000;
524 float cos_rot_angle =
527 float sin_rot_angle =
539 float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
542 float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
544 float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
551 float distance_corr_x = 0;
552 float distance_corr_y = 0;
556 * (xx - 2.4) / (25.04 - 2.4)
561 * (yy - 1.93) / (25.04 - 1.93)
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;
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;
588 z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
604 intensity += focal_slope * (std::abs(focal_offset - 256 *
606 intensity = (intensity < min_intensity) ? min_intensity : intensity;
607 intensity = (intensity > max_intensity) ? max_intensity : intensity;
611 time =
timing_offsets[block][firing * 16 + dsr] + time_diff_start_to_this_packet;
613 data.
addPoint(x_coord, y_coord, z_coord, corrections.
laser_ring, azimuth_corrected, distance, intensity, time);
int scansPerPacket() const
Interfaces for interpreting raw packets from the Velodyne 3D LIDAR.
float cos_rot_table_[ROTATION_MAX_UNITS]
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 ...
float vert_offset_correction
std::string calibrationFile
calibration file name
std::vector< std::vector< float > > timing_offsets
static const int SCANS_PER_BLOCK
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)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void unpack_vlp16(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw VLP16 packet to point cloud
float sin_vert_correction
sine of vert_correction
static const float ROTATION_RESOLUTION
static const uint16_t UPPER_BANK
static const int RAW_SCAN_SIZE
static const float VLP16_FIRING_TOFFSET
std::vector< LaserCorrection > laser_corrections
int max_angle
maximum angle to publish
static const uint16_t ROTATION_MAX_UNITS
raw_block_t blocks[BLOCKS_PER_PACKET]
static double from_degrees(double degrees)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
static const uint16_t LOWER_BANK
static const float VLP16_DSR_TOFFSET
#define ROS_DEBUG_STREAM(args)
uint16_t rotation
0-35999, divide by 100 to get degrees
float distance_resolution_m
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
static const float VLP16_BLOCK_TDURATION
int min_angle
minimum angle to publish
#define ROS_INFO_STREAM(args)
double min_range
minimum range to publish
double max_range
maximum range to publish
float sin_rot_correction
sine of rot_correction
static const int BLOCKS_PER_PACKET
static const int VLP16_SCANS_PER_FIRING
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
float sin_rot_table_[ROTATION_MAX_UNITS]
float horiz_offset_correction
int laser_ring
ring number for this laser
uint8_t data[BLOCK_DATA_SIZE]
float cos_rot_correction
cosine of rot_correction
bool buildTimings()
setup per-point timing offsets
#define ROS_ERROR_STREAM(args)
bool two_pt_correction_available
uint16_t header
UPPER_BANK or LOWER_BANK.
void read(const std::string &calibration_file)
float cos_vert_correction
cosine of vert_correction
static const int VLP16_FIRINGS_PER_BLOCK
velodyne_pointcloud::Calibration calibration_
boost::optional< velodyne_pointcloud::Calibration > setup(ros::NodeHandle private_nh)
Set up for data processing.