39 inline float SQR(
float val) {
return val*val; }
52 double view_direction,
189 const uint8_t laser_number = j + bank_origin;
212 distance += corrections.dist_correction;
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;
221 float cos_rot_angle =
224 float sin_rot_angle =
228 float horiz_offset = corrections.horiz_offset_correction;
229 float vert_offset = corrections.vert_offset_correction;
236 float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
239 float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
241 float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
248 float distance_corr_x = 0;
249 float distance_corr_y = 0;
250 if (corrections.two_pt_correction_available) {
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;
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;
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;
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;
286 z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
295 float min_intensity = corrections.min_intensity;
296 float max_intensity = corrections.max_intensity;
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;
309 data.
addPoint(x_coord, y_coord, z_coord, corrections.laser_ring, raw->
blocks[i].
rotation, distance, intensity);
325 int raw_azimuth_diff;
326 float last_azimuth_diff=0;
327 float azimuth_corrected_f;
328 int azimuth_corrected;
341 << block <<
" header value is " 348 if (block < (BLOCKS_PER_PACKET-1)){
350 azimuth_diff = (float)((36000 + raw_azimuth_diff)%36000);
352 if(raw_azimuth_diff < 0)
356 if(last_azimuth_diff > 0){
357 azimuth_diff = last_azimuth_diff;
365 last_azimuth_diff = azimuth_diff;
367 azimuth_diff = last_azimuth_diff;
381 azimuth_corrected = ((int)round(azimuth_corrected_f)) % 36000;
403 float cos_rot_angle =
406 float sin_rot_angle =
418 float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
421 float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
423 float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
430 float distance_corr_x = 0;
431 float distance_corr_y = 0;
435 * (xx - 2.4) / (25.04 - 2.4)
440 * (yy - 1.93) / (25.04 - 1.93)
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;
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;
467 z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
483 intensity += focal_slope * (std::abs(focal_offset - 256 *
485 intensity = (intensity < min_intensity) ? min_intensity : intensity;
486 intensity = (intensity > max_intensity) ? max_intensity : intensity;
488 data.
addPoint(x_coord, y_coord, z_coord, corrections.
laser_ring, azimuth_corrected, distance, intensity);
int scansPerPacket() const
Interfaces for interpreting raw packets from the Velodyne 3D LIDAR.
float cos_rot_table_[ROTATION_MAX_UNITS]
#define ROS_WARN_STREAM_THROTTLE(period, args)
void unpack_vlp16(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data)
convert raw VLP16 packet to point cloud
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
static const int SCANS_PER_BLOCK
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(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data)
convert raw 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)
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
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
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
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
#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.