Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00028 #include <fstream>
00029 #include <math.h>
00030
00031 #include <ros/ros.h>
00032 #include <ros/package.h>
00033 #include <angles/angles.h>
00034
00035 #include <velodyne_pointcloud/rawdata.h>
00036
00037 namespace velodyne_rawdata
00038 {
00039 inline float SQR(float val) { return val*val; }
00040
00042
00043
00044
00046
00047 RawData::RawData() {}
00048
00050 void RawData::setParameters(double min_range,
00051 double max_range,
00052 double view_direction,
00053 double view_width)
00054 {
00055 config_.min_range = min_range;
00056 config_.max_range = max_range;
00057
00058
00059 config_.tmp_min_angle = view_direction + view_width/2;
00060 config_.tmp_max_angle = view_direction - view_width/2;
00061
00062
00063 config_.tmp_min_angle = fmod(fmod(config_.tmp_min_angle,2*M_PI) + 2*M_PI,2*M_PI);
00064 config_.tmp_max_angle = fmod(fmod(config_.tmp_max_angle,2*M_PI) + 2*M_PI,2*M_PI);
00065
00066
00067
00068 config_.min_angle = 100 * (2*M_PI - config_.tmp_min_angle) * 180 / M_PI + 0.5;
00069 config_.max_angle = 100 * (2*M_PI - config_.tmp_max_angle) * 180 / M_PI + 0.5;
00070 if (config_.min_angle == config_.max_angle)
00071 {
00072
00073 config_.min_angle = 0;
00074 config_.max_angle = 36000;
00075 }
00076 }
00077
00078 int RawData::scansPerPacket() const
00079 {
00080 if( calibration_.num_lasers == 16)
00081 {
00082 return BLOCKS_PER_PACKET * VLP16_FIRINGS_PER_BLOCK *
00083 VLP16_SCANS_PER_FIRING;
00084 }
00085 else{
00086 return BLOCKS_PER_PACKET * SCANS_PER_BLOCK;
00087 }
00088 }
00089
00091 boost::optional<velodyne_pointcloud::Calibration> RawData::setup(ros::NodeHandle private_nh)
00092 {
00093
00094 if (!private_nh.getParam("calibration", config_.calibrationFile))
00095 {
00096 ROS_ERROR_STREAM("No calibration angles specified! Using test values!");
00097
00098
00099 std::string pkgPath = ros::package::getPath("velodyne_pointcloud");
00100 config_.calibrationFile = pkgPath + "/params/64e_utexas.yaml";
00101 }
00102
00103 ROS_INFO_STREAM("correction angles: " << config_.calibrationFile);
00104
00105 calibration_.read(config_.calibrationFile);
00106 if (!calibration_.initialized) {
00107 ROS_ERROR_STREAM("Unable to open calibration file: " <<
00108 config_.calibrationFile);
00109 return boost::none;
00110 }
00111
00112 ROS_INFO_STREAM("Number of lasers: " << calibration_.num_lasers << ".");
00113
00114
00115 for (uint16_t rot_index = 0; rot_index < ROTATION_MAX_UNITS; ++rot_index) {
00116 float rotation = angles::from_degrees(ROTATION_RESOLUTION * rot_index);
00117 cos_rot_table_[rot_index] = cosf(rotation);
00118 sin_rot_table_[rot_index] = sinf(rotation);
00119 }
00120 return calibration_;
00121 }
00122
00123
00125 int RawData::setupOffline(std::string calibration_file, double max_range_, double min_range_)
00126 {
00127
00128 config_.max_range = max_range_;
00129 config_.min_range = min_range_;
00130 ROS_INFO_STREAM("data ranges to publish: ["
00131 << config_.min_range << ", "
00132 << config_.max_range << "]");
00133
00134 config_.calibrationFile = calibration_file;
00135
00136 ROS_INFO_STREAM("correction angles: " << config_.calibrationFile);
00137
00138 calibration_.read(config_.calibrationFile);
00139 if (!calibration_.initialized) {
00140 ROS_ERROR_STREAM("Unable to open calibration file: " <<
00141 config_.calibrationFile);
00142 return -1;
00143 }
00144
00145
00146 for (uint16_t rot_index = 0; rot_index < ROTATION_MAX_UNITS; ++rot_index) {
00147 float rotation = angles::from_degrees(ROTATION_RESOLUTION * rot_index);
00148 cos_rot_table_[rot_index] = cosf(rotation);
00149 sin_rot_table_[rot_index] = sinf(rotation);
00150 }
00151 return 0;
00152 }
00153
00154
00160 void RawData::unpack(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase& data)
00161 {
00162 using velodyne_pointcloud::LaserCorrection;
00163 ROS_DEBUG_STREAM("Received packet, time: " << pkt.stamp);
00164
00166 if (calibration_.num_lasers == 16)
00167 {
00168 unpack_vlp16(pkt, data);
00169 return;
00170 }
00171
00172 const raw_packet_t *raw = (const raw_packet_t *) &pkt.data[0];
00173
00174 for (int i = 0; i < BLOCKS_PER_PACKET; i++) {
00175
00176
00177
00178
00179 int bank_origin = 0;
00180 if (raw->blocks[i].header == LOWER_BANK) {
00181
00182 bank_origin = 32;
00183 }
00184
00185 for (int j = 0, k = 0; j < SCANS_PER_BLOCK; j++, k += RAW_SCAN_SIZE) {
00186
00187 float x, y, z;
00188 float intensity;
00189 const uint8_t laser_number = j + bank_origin;
00190
00191 const LaserCorrection &corrections = calibration_.laser_corrections[laser_number];
00192
00194 const raw_block_t &block = raw->blocks[i];
00195 union two_bytes tmp;
00196 tmp.bytes[0] = block.data[k];
00197 tmp.bytes[1] = block.data[k+1];
00198 if (tmp.bytes[0]==0 &&tmp.bytes[1]==0 )
00199 {
00200 continue;
00201 }
00202
00203
00204
00205 if ((block.rotation >= config_.min_angle
00206 && block.rotation <= config_.max_angle
00207 && config_.min_angle < config_.max_angle)
00208 ||(config_.min_angle > config_.max_angle
00209 && (raw->blocks[i].rotation <= config_.max_angle
00210 || raw->blocks[i].rotation >= config_.min_angle))){
00211 float distance = tmp.uint * calibration_.distance_resolution_m;
00212 distance += corrections.dist_correction;
00213
00214 float cos_vert_angle = corrections.cos_vert_correction;
00215 float sin_vert_angle = corrections.sin_vert_correction;
00216 float cos_rot_correction = corrections.cos_rot_correction;
00217 float sin_rot_correction = corrections.sin_rot_correction;
00218
00219
00220
00221 float cos_rot_angle =
00222 cos_rot_table_[block.rotation] * cos_rot_correction +
00223 sin_rot_table_[block.rotation] * sin_rot_correction;
00224 float sin_rot_angle =
00225 sin_rot_table_[block.rotation] * cos_rot_correction -
00226 cos_rot_table_[block.rotation] * sin_rot_correction;
00227
00228 float horiz_offset = corrections.horiz_offset_correction;
00229 float vert_offset = corrections.vert_offset_correction;
00230
00231
00236 float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
00237
00238
00239 float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
00240
00241 float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
00242 if (xx < 0) xx=-xx;
00243 if (yy < 0) yy=-yy;
00244
00245
00246
00247
00248 float distance_corr_x = 0;
00249 float distance_corr_y = 0;
00250 if (corrections.two_pt_correction_available) {
00251 distance_corr_x =
00252 (corrections.dist_correction - corrections.dist_correction_x)
00253 * (xx - 2.4) / (25.04 - 2.4)
00254 + corrections.dist_correction_x;
00255 distance_corr_x -= corrections.dist_correction;
00256 distance_corr_y =
00257 (corrections.dist_correction - corrections.dist_correction_y)
00258 * (yy - 1.93) / (25.04 - 1.93)
00259 + corrections.dist_correction_y;
00260 distance_corr_y -= corrections.dist_correction;
00261 }
00262
00263 float distance_x = distance + distance_corr_x;
00268 xy_distance = distance_x * cos_vert_angle - vert_offset * sin_vert_angle ;
00270 x = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
00271
00272 float distance_y = distance + distance_corr_y;
00273 xy_distance = distance_y * cos_vert_angle - vert_offset * sin_vert_angle ;
00278 y = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
00279
00280
00281
00286 z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
00287
00289 float x_coord = y;
00290 float y_coord = -x;
00291 float z_coord = z;
00292
00295 float min_intensity = corrections.min_intensity;
00296 float max_intensity = corrections.max_intensity;
00297
00298 intensity = raw->blocks[i].data[k+2];
00299
00300 float focal_offset = 256
00301 * (1 - corrections.focal_distance / 13100)
00302 * (1 - corrections.focal_distance / 13100);
00303 float focal_slope = corrections.focal_slope;
00304 intensity += focal_slope * (std::abs(focal_offset - 256 *
00305 SQR(1 - static_cast<float>(tmp.uint)/65535)));
00306 intensity = (intensity < min_intensity) ? min_intensity : intensity;
00307 intensity = (intensity > max_intensity) ? max_intensity : intensity;
00308
00309 data.addPoint(x_coord, y_coord, z_coord, corrections.laser_ring, raw->blocks[i].rotation, distance, intensity);
00310 }
00311 }
00312 data.newLine();
00313 }
00314 }
00315
00321 void RawData::unpack_vlp16(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase& data)
00322 {
00323 float azimuth;
00324 float azimuth_diff;
00325 int raw_azimuth_diff;
00326 float last_azimuth_diff=0;
00327 float azimuth_corrected_f;
00328 int azimuth_corrected;
00329 float x, y, z;
00330 float intensity;
00331
00332 const raw_packet_t *raw = (const raw_packet_t *) &pkt.data[0];
00333
00334 for (int block = 0; block < BLOCKS_PER_PACKET; block++) {
00335
00336
00337 if (UPPER_BANK != raw->blocks[block].header) {
00338
00339
00340 ROS_WARN_STREAM_THROTTLE(60, "skipping invalid VLP-16 packet: block "
00341 << block << " header value is "
00342 << raw->blocks[block].header);
00343 return;
00344 }
00345
00346
00347 azimuth = (float)(raw->blocks[block].rotation);
00348 if (block < (BLOCKS_PER_PACKET-1)){
00349 raw_azimuth_diff = raw->blocks[block+1].rotation - raw->blocks[block].rotation;
00350 azimuth_diff = (float)((36000 + raw_azimuth_diff)%36000);
00351
00352 if(raw_azimuth_diff < 0)
00353 {
00354 ROS_WARN_STREAM_THROTTLE(60, "Packet containing angle overflow, first angle: " << raw->blocks[block].rotation << " second angle: " << raw->blocks[block+1].rotation);
00355
00356 if(last_azimuth_diff > 0){
00357 azimuth_diff = last_azimuth_diff;
00358 }
00359
00360
00361 else{
00362 continue;
00363 }
00364 }
00365 last_azimuth_diff = azimuth_diff;
00366 }else{
00367 azimuth_diff = last_azimuth_diff;
00368 }
00369
00370 for (int firing=0, k=0; firing < VLP16_FIRINGS_PER_BLOCK; firing++){
00371 for (int dsr=0; dsr < VLP16_SCANS_PER_FIRING; dsr++, k+=RAW_SCAN_SIZE){
00372 velodyne_pointcloud::LaserCorrection &corrections = calibration_.laser_corrections[dsr];
00373
00375 union two_bytes tmp;
00376 tmp.bytes[0] = raw->blocks[block].data[k];
00377 tmp.bytes[1] = raw->blocks[block].data[k+1];
00378
00380 azimuth_corrected_f = azimuth + (azimuth_diff * ((dsr*VLP16_DSR_TOFFSET) + (firing*VLP16_FIRING_TOFFSET)) / VLP16_BLOCK_TDURATION);
00381 azimuth_corrected = ((int)round(azimuth_corrected_f)) % 36000;
00382
00383
00384
00385 if ((azimuth_corrected >= config_.min_angle
00386 && azimuth_corrected <= config_.max_angle
00387 && config_.min_angle < config_.max_angle)
00388 ||(config_.min_angle > config_.max_angle
00389 && (azimuth_corrected <= config_.max_angle
00390 || azimuth_corrected >= config_.min_angle))){
00391
00392
00393 float distance = tmp.uint * calibration_.distance_resolution_m;
00394 distance += corrections.dist_correction;
00395
00396 float cos_vert_angle = corrections.cos_vert_correction;
00397 float sin_vert_angle = corrections.sin_vert_correction;
00398 float cos_rot_correction = corrections.cos_rot_correction;
00399 float sin_rot_correction = corrections.sin_rot_correction;
00400
00401
00402
00403 float cos_rot_angle =
00404 cos_rot_table_[azimuth_corrected] * cos_rot_correction +
00405 sin_rot_table_[azimuth_corrected] * sin_rot_correction;
00406 float sin_rot_angle =
00407 sin_rot_table_[azimuth_corrected] * cos_rot_correction -
00408 cos_rot_table_[azimuth_corrected] * sin_rot_correction;
00409
00410 float horiz_offset = corrections.horiz_offset_correction;
00411 float vert_offset = corrections.vert_offset_correction;
00412
00413
00418 float xy_distance = distance * cos_vert_angle - vert_offset * sin_vert_angle;
00419
00420
00421 float xx = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
00422
00423 float yy = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
00424 if (xx < 0) xx=-xx;
00425 if (yy < 0) yy=-yy;
00426
00427
00428
00429
00430 float distance_corr_x = 0;
00431 float distance_corr_y = 0;
00432 if (corrections.two_pt_correction_available) {
00433 distance_corr_x =
00434 (corrections.dist_correction - corrections.dist_correction_x)
00435 * (xx - 2.4) / (25.04 - 2.4)
00436 + corrections.dist_correction_x;
00437 distance_corr_x -= corrections.dist_correction;
00438 distance_corr_y =
00439 (corrections.dist_correction - corrections.dist_correction_y)
00440 * (yy - 1.93) / (25.04 - 1.93)
00441 + corrections.dist_correction_y;
00442 distance_corr_y -= corrections.dist_correction;
00443 }
00444
00445 float distance_x = distance + distance_corr_x;
00450 xy_distance = distance_x * cos_vert_angle - vert_offset * sin_vert_angle ;
00451 x = xy_distance * sin_rot_angle - horiz_offset * cos_rot_angle;
00452
00453 float distance_y = distance + distance_corr_y;
00458 xy_distance = distance_y * cos_vert_angle - vert_offset * sin_vert_angle ;
00459 y = xy_distance * cos_rot_angle + horiz_offset * sin_rot_angle;
00460
00461
00462
00467 z = distance_y * sin_vert_angle + vert_offset*cos_vert_angle;
00468
00469
00471 float x_coord = y;
00472 float y_coord = -x;
00473 float z_coord = z;
00474
00476 float min_intensity = corrections.min_intensity;
00477 float max_intensity = corrections.max_intensity;
00478
00479 intensity = raw->blocks[block].data[k+2];
00480
00481 float focal_offset = 256 * SQR(1 - corrections.focal_distance / 13100);
00482 float focal_slope = corrections.focal_slope;
00483 intensity += focal_slope * (std::abs(focal_offset - 256 *
00484 SQR(1 - tmp.uint/65535)));
00485 intensity = (intensity < min_intensity) ? min_intensity : intensity;
00486 intensity = (intensity > max_intensity) ? max_intensity : intensity;
00487
00488 data.addPoint(x_coord, y_coord, z_coord, corrections.laser_ring, azimuth_corrected, distance, intensity);
00489 }
00490 }
00491 data.newLine();
00492 }
00493 }
00494 }
00495 }