00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #include <laser3D_pointcloud/laser3D_pointcloud.h>
00028 #include <algorithm>
00029 #include <ros/assert.h>
00030
00039 void las3D_PointCloud::accumulate_cloud(pcl::PointCloud<pcl::PointXYZ>* pc_in)
00040 {
00041 pc_accumulated +=*pc_in;
00042 pc_accumulated.header.frame_id = pc_in->header.frame_id;
00043 if (pointcloud_stamp)
00044 pc_accumulated.header.stamp = pc_in->header.stamp;
00045 cloud_size=pc_in->points.size ();
00046
00047 #if defined _USE_DEBUG_
00048 ROS_INFO("pc_transformed has %d points", (int)pc_transformed.size());
00049 ROS_INFO("pc_accumulated now has %d points", (int)pc_accumulated.size());
00050 #endif
00051 }
00052
00053 const boost::numeric::ublas::matrix<double>& las3D_PointCloud::getUnitVectors_(double angle_min, double angle_max, double angle_increment, unsigned int length)
00054 {
00055 boost::mutex::scoped_lock guv_lock(this->guv_mutex_);
00056
00057
00058 std::stringstream anglestring;
00059 anglestring <<angle_min<<","<<angle_max<<","<<angle_increment<<","<<length;
00060 std::map<std::string, boost::numeric::ublas::matrix<double>* >::iterator it;
00061 it = unit_vector_map_.find(anglestring.str());
00062
00063 if (it != unit_vector_map_.end())
00064 return *((*it).second);
00065
00066 boost::numeric::ublas::matrix<double> * tempPtr = new boost::numeric::ublas::matrix<double>(2,length);
00067 for (unsigned int index = 0;index < length; index++)
00068 {
00069 (*tempPtr)(0,index) = cos(angle_min + (double) index * angle_increment);
00070 (*tempPtr)(1,index) = sin(angle_min + (double) index * angle_increment);
00071 }
00072
00073 unit_vector_map_[anglestring.str()] = tempPtr;
00074
00075 return *tempPtr;
00076 };
00077
00078
00079 las3D_PointCloud::~las3D_PointCloud()
00080 {
00081 std::map<std::string, boost::numeric::ublas::matrix<double>*>::iterator it;
00082 it = unit_vector_map_.begin();
00083 while (it != unit_vector_map_.end())
00084 {
00085 delete (*it).second;
00086 it++;
00087 }
00088 };
00089
00090 void las3D_PointCloud::las3D_projectLaser_ (const sensor_msgs::LaserScan& scan_in,
00091 sensor_msgs::PointCloud2 &cloud_out,
00092 double range_cutoff,
00093 int channel_options)
00094 {
00095 size_t n_pts = scan_in.ranges.size ();
00096 Eigen::ArrayXXd output (n_pts, 2);
00097 angle_min_ = scan_in.angle_min;
00098 angle_max_ = scan_in.angle_max;
00099
00100
00101 for (size_t i = 0; i < n_pts; ++i)
00102 {
00103 output (i,0) = scan_in.ranges[i] * cos (scan_in.angle_min + (double) i * scan_in.angle_increment);
00104 output (i,1) = scan_in.ranges[i] * sin (scan_in.angle_min + (double) i * scan_in.angle_increment);
00105 }
00106
00107
00108 cloud_out.header = scan_in.header;
00109 cloud_out.height = 1;
00110 cloud_out.width = scan_in.ranges.size ();
00111 cloud_out.fields.resize (3);
00112 cloud_out.fields[0].name = "x";
00113 cloud_out.fields[0].offset = 0;
00114 cloud_out.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00115 cloud_out.fields[0].count = 1;
00116 cloud_out.fields[1].name = "y";
00117 cloud_out.fields[1].offset = 4;
00118 cloud_out.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00119 cloud_out.fields[1].count = 1;
00120 cloud_out.fields[2].name = "z";
00121 cloud_out.fields[2].offset = 8;
00122 cloud_out.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00123 cloud_out.fields[2].count = 1;
00124
00125
00126 int idx_intensity = -1, idx_index = -1, idx_distance = -1, idx_timestamp = -1, idx_vpx = -1, idx_vpy = -1, idx_vpz = -1;
00127
00128
00129 int offset = 12;
00130 if ((channel_options & channel_option::Intensity) && scan_in.intensities.size() > 0)
00131 {
00132 int field_size = cloud_out.fields.size();
00133 cloud_out.fields.resize(field_size + 1);
00134 cloud_out.fields[field_size].name = "intensity";
00135 cloud_out.fields[field_size].datatype = sensor_msgs::PointField::FLOAT32;
00136 cloud_out.fields[field_size].offset = offset;
00137 cloud_out.fields[field_size].count = 1;
00138 offset += 4;
00139 idx_intensity = field_size;
00140 }
00141
00142 if ((channel_options & channel_option::Index))
00143 {
00144 int field_size = cloud_out.fields.size();
00145 cloud_out.fields.resize(field_size + 1);
00146 cloud_out.fields[field_size].name = "index";
00147 cloud_out.fields[field_size].datatype = sensor_msgs::PointField::INT32;
00148 cloud_out.fields[field_size].offset = offset;
00149 cloud_out.fields[field_size].count = 1;
00150 offset += 4;
00151 idx_index = field_size;
00152 }
00153
00154 if ((channel_options & channel_option::Distance))
00155 {
00156 int field_size = cloud_out.fields.size();
00157 cloud_out.fields.resize(field_size + 1);
00158 cloud_out.fields[field_size].name = "distances";
00159 cloud_out.fields[field_size].datatype = sensor_msgs::PointField::FLOAT32;
00160 cloud_out.fields[field_size].offset = offset;
00161 cloud_out.fields[field_size].count = 1;
00162 offset += 4;
00163 idx_distance = field_size;
00164 }
00165
00166 if ((channel_options & channel_option::Timestamp))
00167 {
00168 int field_size = cloud_out.fields.size();
00169 cloud_out.fields.resize(field_size + 1);
00170 cloud_out.fields[field_size].name = "stamps";
00171 cloud_out.fields[field_size].datatype = sensor_msgs::PointField::FLOAT32;
00172 cloud_out.fields[field_size].offset = offset;
00173 cloud_out.fields[field_size].count = 1;
00174 offset += 4;
00175 idx_timestamp = field_size;
00176 }
00177
00178 if ((channel_options & channel_option::Viewpoint))
00179 {
00180 int field_size = cloud_out.fields.size();
00181 cloud_out.fields.resize(field_size + 3);
00182
00183 cloud_out.fields[field_size].name = "vp_x";
00184 cloud_out.fields[field_size].datatype = sensor_msgs::PointField::FLOAT32;
00185 cloud_out.fields[field_size].offset = offset;
00186 cloud_out.fields[field_size].count = 1;
00187 offset += 4;
00188
00189 cloud_out.fields[field_size + 1].name = "vp_y";
00190 cloud_out.fields[field_size + 1].datatype = sensor_msgs::PointField::FLOAT32;
00191 cloud_out.fields[field_size + 1].offset = offset;
00192 cloud_out.fields[field_size + 1].count = 1;
00193 offset += 4;
00194
00195 cloud_out.fields[field_size + 2].name = "vp_z";
00196 cloud_out.fields[field_size + 2].datatype = sensor_msgs::PointField::FLOAT32;
00197 cloud_out.fields[field_size + 2].offset = offset;
00198 cloud_out.fields[field_size + 2].count = 1;
00199 offset += 4;
00200
00201 idx_vpx = field_size;
00202 idx_vpy = field_size + 1;
00203 idx_vpz = field_size + 2;
00204 }
00205
00206 cloud_out.point_step = offset;
00207 cloud_out.row_step = cloud_out.point_step * cloud_out.width;
00208 cloud_out.data.resize (cloud_out.row_step * cloud_out.height);
00209 cloud_out.is_dense = false;
00210
00211
00212
00213
00214 if (range_cutoff < 0)
00215 range_cutoff = scan_in.range_max;
00216 else
00217 range_cutoff = std::min(range_cutoff, (double)scan_in.range_max);
00218
00219 unsigned int count = 0;
00220 for (size_t i = 0; i < n_pts; ++i)
00221 {
00222
00223 if (scan_in.ranges[i] <= range_cutoff && scan_in.ranges[i] >= scan_in.range_min)
00224 {
00225 float *pstep = (float*)&cloud_out.data[count * cloud_out.point_step];
00226
00227
00228 pstep[0] = output (i, 0);
00229 pstep[1] = output (i, 1);
00230 pstep[2] = 0;
00231
00232
00233 if(idx_intensity != -1)
00234 pstep[idx_intensity] = scan_in.intensities[i];
00235
00236
00237 if(idx_index != -1)
00238 ((int*)(pstep))[idx_index] = i;
00239
00240
00241 if(idx_distance != -1)
00242 pstep[idx_distance] = scan_in.ranges[i];
00243
00244
00245 if(idx_timestamp != -1)
00246 pstep[idx_timestamp] = i * scan_in.time_increment;
00247
00248
00249 if(idx_vpx != -1 && idx_vpy != -1 && idx_vpz != -1)
00250 {
00251 pstep[idx_vpx] = 0;
00252 pstep[idx_vpy] = 0;
00253 pstep[idx_vpz] = 0;
00254 }
00255
00256
00257 ++count;
00258 }
00259
00260
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276
00277
00278
00279
00280
00281
00282
00283
00284
00285
00286
00287
00288
00289
00290 }
00291
00292
00293 cloud_out.width = count;
00294 cloud_out.row_step = cloud_out.point_step * cloud_out.width;
00295 cloud_out.data.resize (cloud_out.row_step * cloud_out.height);
00296
00297 }
00298
00299
00300
00301 int las3D_PointCloud::las3D_transformLaserScanToPointCloud_ (const std::string &target_frame,
00302 const sensor_msgs::LaserScan &scan_in,
00303 sensor_msgs::PointCloud2 &cloud_out,
00304 tf::Transformer &tf,
00305 double range_cutoff,
00306 int channel_options)
00307 {
00308
00309
00310 bool requested_index = false;
00311 if ((channel_options & channel_option::Index))
00312 requested_index = true;
00313
00314
00315
00316 channel_options |= channel_option::Index;
00317
00318 las3D_projectLaser_(scan_in, cloud_out, -1.0, channel_options);
00319
00320
00321 bool has_viewpoint = false;
00322 uint32_t vp_x_offset = 0;
00323
00324
00325
00326
00327
00328
00329 uint32_t index_offset = 0;
00330 for(unsigned int i = 0; i < cloud_out.fields.size(); ++i)
00331 {
00332 if(cloud_out.fields[i].name == "index")
00333 {
00334 index_offset = cloud_out.fields[i].offset;
00335 }
00336
00337
00338
00339
00340 if(cloud_out.fields[i].name == "vp_x")
00341 {
00342 has_viewpoint = true;
00343 vp_x_offset = cloud_out.fields[i].offset;
00344 }
00345 }
00346
00347 ROS_ASSERT(index_offset > 0);
00348
00349 cloud_out.header.frame_id = target_frame;
00350
00351
00352 ros::Time start_time = scan_in.header.stamp;
00353 ros::Time end_time = scan_in.header.stamp + ros::Duration ().fromSec (scan_in.ranges.size () * scan_in.time_increment);
00354
00355
00356 tf::StampedTransform start_transform, end_transform, cur_transform ;
00357
00358
00359 int error=0;
00360 tf.waitForTransform(target_frame, scan_in.header.frame_id,start_time, ros::Duration(0.5));
00361 try
00362 {
00363 tf.lookupTransform (target_frame, scan_in.header.frame_id, start_time, start_transform);
00364 }
00365 catch (tf::TransformException ex)
00366 {
00367 ROS_ERROR("%s",ex.what());
00368 error=1;
00369 }
00370 if (error)
00371 {
00372 ROS_INFO("Scan ignored");
00373 return 1;
00374 }
00375
00376 tf.waitForTransform(target_frame, scan_in.header.frame_id,end_time, ros::Duration(0.5));
00377 try
00378 {
00379 tf.lookupTransform (target_frame, scan_in.header.frame_id, end_time, end_transform);
00380 }
00381 catch (tf::TransformException ex)
00382 {
00383 ROS_ERROR("%s",ex.what());
00384 error=1;
00385 }
00386 if (error)
00387 {
00388 ROS_INFO("Scan ignored");
00389 return 1;
00390 }
00391
00392 double ranges_norm=0;
00393 if (accumulation_mode!=3)
00394 ranges_norm = 1 / ((double) scan_in.ranges.size () - 1.0);
00395
00396
00397 for(size_t i = 0; i < cloud_out.width; ++i)
00398 {
00399
00400 float *pstep = (float*)&cloud_out.data[i * cloud_out.point_step + 0];
00401
00402
00403 uint32_t pt_index;
00404 memcpy(&pt_index, &cloud_out.data[i * cloud_out.point_step + index_offset], sizeof(uint32_t));
00405
00406
00407 #if ROS_VERSION_MINIMUM(1, 8, 0)
00408 tfScalar ratio = pt_index * ranges_norm;
00409 tf::Vector3 v (0, 0, 0);
00410 tf::Quaternion q1, q2;
00411 #else
00412 btScalar ratio = pt_index * ranges_norm ;
00413 btVector3 v (0, 0, 0);
00414 btQuaternion q1, q2 ;
00415 #endif
00416
00418
00419 v.setInterpolate3 (start_transform.getOrigin (), end_transform.getOrigin (), ratio);
00420 cur_transform.setOrigin (v);
00421
00422
00423 start_transform.getBasis ().getRotation (q1);
00424 end_transform.getBasis ().getRotation (q2);
00425
00426
00427 cur_transform.setRotation (slerp (q1, q2 , ratio));
00428
00429 #if ROS_VERSION_MINIMUM(1, 8, 0)
00430 tf::Vector3 point_in (pstep[0], pstep[1], pstep[2]);
00431 tf::Vector3 point_out = cur_transform * point_in;
00432 #else
00433 btVector3 point_in (pstep[0], pstep[1], pstep[2]);
00434 btVector3 point_out = cur_transform * point_in;
00435 #endif
00436
00437
00438 pstep[0] = point_out.x ();
00439 pstep[1] = point_out.y ();
00440 pstep[2] = point_out.z ();
00441
00442
00443 if(has_viewpoint)
00444 {
00445 float *vpstep = (float*)&cloud_out.data[i * cloud_out.point_step + vp_x_offset];
00446 #if ROS_VERSION_MINIMUM(1, 8, 0)
00447 point_in = tf::Vector3 (vpstep[0], vpstep[1], vpstep[2]);
00448 #else
00449 point_in = btVector3 (vpstep[0], vpstep[1], vpstep[2]);
00450 #endif
00451 point_out = cur_transform * point_in;
00452
00453
00454 vpstep[0] = point_out.x ();
00455 vpstep[1] = point_out.y ();
00456 vpstep[2] = point_out.z ();
00457 }
00458 }
00459
00460
00461 if(!requested_index)
00462 {
00463 sensor_msgs::PointCloud2 cloud_without_index;
00464
00465
00466 cloud_without_index.header = cloud_out.header;
00467 cloud_without_index.width = cloud_out.width;
00468 cloud_without_index.height = cloud_out.height;
00469 cloud_without_index.is_bigendian = cloud_out.is_bigendian;
00470 cloud_without_index.is_dense = cloud_out.is_dense;
00471
00472
00473 cloud_without_index.fields.resize(cloud_out.fields.size());
00474 unsigned int field_count = 0;
00475 unsigned int offset_shift = 0;
00476 for(unsigned int i = 0; i < cloud_out.fields.size(); ++i)
00477 {
00478 if(cloud_out.fields[i].name != "index")
00479 {
00480 cloud_without_index.fields[field_count] = cloud_out.fields[i];
00481 cloud_without_index.fields[field_count].offset -= offset_shift;
00482 ++field_count;
00483 }
00484 else
00485 {
00486
00487 offset_shift = 4;
00488 }
00489 }
00490
00491
00492 cloud_without_index.fields.resize(field_count);
00493
00494
00495 cloud_without_index.point_step = cloud_out.point_step - offset_shift;
00496 cloud_without_index.row_step = cloud_without_index.point_step * cloud_without_index.width;
00497 cloud_without_index.data.resize (cloud_without_index.row_step * cloud_without_index.height);
00498
00499 uint32_t i = 0;
00500 uint32_t j = 0;
00501
00502 while (i < cloud_out.data.size())
00503 {
00504 if((i % cloud_out.point_step) < index_offset || (i % cloud_out.point_step) >= (index_offset + 4))
00505 {
00506 cloud_without_index.data[j++] = cloud_out.data[i];
00507 }
00508 i++;
00509 }
00510
00511
00512 cloud_out = cloud_without_index;
00513 }
00514
00515 return 0;
00516 }
00517
00518
00519 int las3D_PointCloud::las3D_transformLaserScanToPointCloud_ (const std::string &target_frame,
00520 const sensor_msgs::LaserScan &scan_in,
00521 sensor_msgs::PointCloud2 &cloud_out,
00522 const sensor_msgs::JointState &state_start,
00523 const sensor_msgs::JointState &state_end,
00524 tf::Transformer &tf,
00525 double range_cutoff,
00526 int channel_options)
00527 {
00528
00529
00530 bool requested_index = false;
00531 if ((channel_options & channel_option::Index))
00532 requested_index = true;
00533
00534
00535
00536 channel_options |= channel_option::Index;
00537
00538 las3D_projectLaser_(scan_in, cloud_out, -1.0, channel_options);
00539
00540
00541 bool has_viewpoint = false;
00542 uint32_t vp_x_offset = 0;
00543
00544
00545
00546
00547
00548
00549 uint32_t index_offset = 0;
00550 for(unsigned int i = 0; i < cloud_out.fields.size(); ++i)
00551 {
00552 if(cloud_out.fields[i].name == "index")
00553 {
00554 index_offset = cloud_out.fields[i].offset;
00555 }
00556
00557
00558
00559
00560 if(cloud_out.fields[i].name == "vp_x")
00561 {
00562 has_viewpoint = true;
00563 vp_x_offset = cloud_out.fields[i].offset;
00564 }
00565 }
00566
00567 ROS_ASSERT(index_offset > 0);
00568
00569 cloud_out.header.frame_id = target_frame;
00570
00571
00572 ros::Time start_time = state_start.header.stamp;
00573 ros::Time end_time = state_end.header.stamp;
00574
00575 tf::StampedTransform start_transform, end_transform, cur_transform ;
00576
00577
00578 int error=0;
00579 tf.waitForTransform(target_frame, scan_in.header.frame_id,start_time, ros::Duration(0.5));
00580 try
00581 {
00582 tf.lookupTransform (target_frame, scan_in.header.frame_id, start_time, start_transform);
00583 }
00584 catch (tf::TransformException ex)
00585 {
00586 ROS_ERROR("%s",ex.what());
00587 error=1;
00588 }
00589 if (error)
00590 {
00591 ROS_INFO("Scan ignored");
00592 return 1;
00593 }
00594
00595 tf.waitForTransform(target_frame, scan_in.header.frame_id,end_time, ros::Duration(0.5));
00596 try
00597 {
00598 tf.lookupTransform (target_frame, scan_in.header.frame_id, end_time, end_transform);
00599 }
00600 catch (tf::TransformException ex)
00601 {
00602 ROS_ERROR("%s",ex.what());
00603 error=1;
00604 }
00605 if (error)
00606 {
00607 ROS_INFO("Scan ignored");
00608 return 1;
00609 }
00610
00611 double ranges_norm=0;
00612 if (accumulation_mode!=2)
00613 ranges_norm = 1 / ((double) scan_in.ranges.size () - 1.0);
00614
00615
00616 for(size_t i = 0; i < cloud_out.width; ++i)
00617 {
00618
00619 float *pstep = (float*)&cloud_out.data[i * cloud_out.point_step + 0];
00620
00621
00622 uint32_t pt_index;
00623 memcpy(&pt_index, &cloud_out.data[i * cloud_out.point_step + index_offset], sizeof(uint32_t));
00624
00625
00626 #if ROS_VERSION_MINIMUM(1, 8, 0)
00627 tfScalar ratio = pt_index * ranges_norm;
00628 tf::Vector3 v (0, 0, 0);
00629 tf::Quaternion q1, q2;
00630 #else
00631 btScalar ratio = pt_index * ranges_norm ;
00632 btVector3 v (0, 0, 0);
00633 btQuaternion q1, q2 ;
00634 #endif
00635
00637
00638 v.setInterpolate3 (start_transform.getOrigin (), end_transform.getOrigin (), ratio);
00639 cur_transform.setOrigin (v);
00640
00641
00642 start_transform.getBasis ().getRotation (q1);
00643 end_transform.getBasis ().getRotation (q2);
00644
00645
00646 cur_transform.setRotation (slerp (q1, q2 , ratio));
00647
00648 #if ROS_VERSION_MINIMUM(1, 8, 0)
00649 tf::Vector3 point_in (pstep[0], pstep[1], pstep[2]);
00650 tf::Vector3 point_out = cur_transform * point_in;
00651 #else
00652 btVector3 point_in (pstep[0], pstep[1], pstep[2]);
00653 btVector3 point_out = cur_transform * point_in;
00654 #endif
00655
00656
00657 pstep[0] = point_out.x ();
00658 pstep[1] = point_out.y ();
00659 pstep[2] = point_out.z ();
00660
00661
00662 if(has_viewpoint)
00663 {
00664 float *vpstep = (float*)&cloud_out.data[i * cloud_out.point_step + vp_x_offset];
00665 #if ROS_VERSION_MINIMUM(1, 8, 0)
00666 point_in = tf::Vector3 (vpstep[0], vpstep[1], vpstep[2]);
00667 #else
00668 point_in = btVector3 (vpstep[0], vpstep[1], vpstep[2]);
00669 #endif
00670 point_out = cur_transform * point_in;
00671
00672
00673 vpstep[0] = point_out.x ();
00674 vpstep[1] = point_out.y ();
00675 vpstep[2] = point_out.z ();
00676 }
00677 }
00678
00679
00680 if(!requested_index)
00681 {
00682 sensor_msgs::PointCloud2 cloud_without_index;
00683
00684
00685 cloud_without_index.header = cloud_out.header;
00686 cloud_without_index.width = cloud_out.width;
00687 cloud_without_index.height = cloud_out.height;
00688 cloud_without_index.is_bigendian = cloud_out.is_bigendian;
00689 cloud_without_index.is_dense = cloud_out.is_dense;
00690
00691
00692 cloud_without_index.fields.resize(cloud_out.fields.size());
00693 unsigned int field_count = 0;
00694 unsigned int offset_shift = 0;
00695 for(unsigned int i = 0; i < cloud_out.fields.size(); ++i)
00696 {
00697 if(cloud_out.fields[i].name != "index")
00698 {
00699 cloud_without_index.fields[field_count] = cloud_out.fields[i];
00700 cloud_without_index.fields[field_count].offset -= offset_shift;
00701 ++field_count;
00702 }
00703 else
00704 {
00705
00706 offset_shift = 4;
00707 }
00708 }
00709
00710
00711 cloud_without_index.fields.resize(field_count);
00712
00713
00714 cloud_without_index.point_step = cloud_out.point_step - offset_shift;
00715 cloud_without_index.row_step = cloud_without_index.point_step * cloud_without_index.width;
00716 cloud_without_index.data.resize (cloud_without_index.row_step * cloud_without_index.height);
00717
00718 uint32_t i = 0;
00719 uint32_t j = 0;
00720
00721 while (i < cloud_out.data.size())
00722 {
00723 if((i % cloud_out.point_step) < index_offset || (i % cloud_out.point_step) >= (index_offset + 4))
00724 {
00725 cloud_without_index.data[j++] = cloud_out.data[i];
00726 }
00727 i++;
00728 }
00729
00730
00731 cloud_out = cloud_without_index;
00732 }
00733
00734 return 0;
00735 }
00736