laser_3d_pointcloud.cpp
Go to the documentation of this file.
00001 /**************************************************************************************************
00002  Software License Agreement (BSD License)
00003 
00004  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
00005  All rights reserved.
00006 
00007  Redistribution and use in source and binary forms, with or without modification, are permitted
00008  provided that the following conditions are met:
00009 
00010   *Redistributions of source code must retain the above copyright notice, this list of
00011    conditions and the following disclaimer.
00012   *Redistributions in binary form must reproduce the above copyright notice, this list of
00013    conditions and the following disclaimer in the documentation and/or other materials provided
00014    with the distribution.
00015   *Neither the name of the University of Aveiro nor the names of its contributors may be used to
00016    endorse or promote products derived from this software without specific prior written permission.
00017  
00018  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
00019  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
00020  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
00021  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00022  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00023  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
00024  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
00025  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 ***************************************************************************************************/
00027 #include <laser_3d_pointcloud/laser_3d_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     //construct string for lookup in the map
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     //check the map for presense
00063     if (it != unit_vector_map_.end())
00064       return *((*it).second);     //if present return
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     //store 
00073     unit_vector_map_[anglestring.str()] = tempPtr;
00074     //and return
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         // Get the ranges into Eigen format
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         // Set the output cloud accordingly
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     // Define 4 indices in the channel array for each possible value type
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     //now, we need to check what fields we need to store
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     //TODO: Find out why this was needed
00212     //float bad_point = std::numeric_limits<float>::quiet_NaN ();
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       //check to see if we want to keep the point
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         // Copy XYZ
00228         pstep[0] = output (i, 0);
00229         pstep[1] = output (i, 1);
00230                 pstep[2] = 0;
00231 
00232         // Copy intensity
00233         if(idx_intensity != -1)
00234           pstep[idx_intensity] = scan_in.intensities[i];
00235 
00236         //Copy index
00237         if(idx_index != -1)
00238           ((int*)(pstep))[idx_index] = i;
00239 
00240         // Copy distance
00241         if(idx_distance != -1)
00242           pstep[idx_distance] = scan_in.ranges[i];
00243 
00244         // Copy timestamp
00245         if(idx_timestamp != -1)
00246           pstep[idx_timestamp] = i * scan_in.time_increment;
00247 
00248         // Copy viewpoint (0, 0, 0)
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         //make sure to increment count
00257         ++count;
00258       }
00259 
00260       /* TODO: Why was this done in this way, I don't get this at all, you end up with a ton of points with NaN values
00261        * why can't you just leave them out?
00262        *
00263       // Invalid measurement?
00264       if (scan_in.ranges[i] >= range_cutoff || scan_in.ranges[i] <= scan_in.range_min)
00265       {
00266         if (scan_in.ranges[i] != LASER_SCAN_MAX_RANGE)
00267         {
00268           for (size_t s = 0; s < cloud_out.fields.size (); ++s)
00269             pstep[s] = bad_point;
00270         }
00271         else
00272         {
00273           // Kind of nasty thing:
00274           //   We keep the oringinal point information for max ranges but set x to NAN to mark the point as invalid.
00275           //   Since we still might need the x value we store it in the distance field
00276           pstep[0] = bad_point;           // X -> NAN to mark a bad point
00277           pstep[1] = co_sine_map (i, 1);  // Y
00278           pstep[2] = 0;                   // Z
00279 
00280           if (store_intensity)
00281           {
00282             pstep[3] = bad_point;           // Intensity -> NAN to mark a bad point
00283             pstep[4] = co_sine_map (i, 0);  // Distance -> Misused to store the originnal X
00284           }
00285           else
00286             pstep[3] = co_sine_map (i, 0);  // Distance -> Misused to store the originnal X
00287         }
00288       }
00289       */
00290     }
00291 
00292     //resize if necessary
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      //check if the user has requested the index field
00310     bool requested_index = false;
00311     if ((channel_options & channel_option::Index))
00312       requested_index = true;
00313 
00314     //we'll enforce that we get index values for the laser scan so that we
00315     //ensure that we use the correct timestamps
00316     channel_options |= channel_option::Index;
00317 
00318     las3D_projectLaser_(scan_in, cloud_out, -1.0, channel_options);
00319 
00320     //we'll assume no associated viewpoint by default
00321     bool has_viewpoint = false;
00322     uint32_t vp_x_offset = 0;
00323 
00324     //we need to find the offset of the intensity field in the point cloud
00325     //we also know that the index field is guaranteed to exist since we 
00326     //set the channel option above. To be really safe, it might be worth
00327     //putting in a check at some point, but I'm just going to put in an
00328     //assert for now
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       //we want to check if the cloud has a viewpoint associated with it
00338       //checking vp_x should be sufficient since vp_x, vp_y, and vp_z all
00339       //get put in together
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     // Extract transforms for the beginning and end of the laser scan
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         //cenas minhas
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     //we want to loop through all the points in the cloud
00397     for(size_t i = 0; i < cloud_out.width; ++i)
00398     {
00399       // Apply the transform to the current point
00400       float *pstep = (float*)&cloud_out.data[i * cloud_out.point_step + 0];
00401 
00402       //find the index of the point
00403       uint32_t pt_index;
00404       memcpy(&pt_index, &cloud_out.data[i * cloud_out.point_step + index_offset], sizeof(uint32_t));
00405       
00406             // Assume constant motion during the laser-scan, and use slerp to compute intermediate transforms
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                 // Interpolate translation
00419                 v.setInterpolate3 (start_transform.getOrigin (), end_transform.getOrigin (), ratio);
00420                 cur_transform.setOrigin (v);
00421 
00422                 // Interpolate rotation
00423                 start_transform.getBasis ().getRotation (q1);
00424                 end_transform.getBasis ().getRotation (q2);
00425 
00426                 // Compute the slerp-ed rotation
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                 // Copy transformed point into cloud
00438                 pstep[0] = point_out.x ();
00439                 pstep[1] = point_out.y ();
00440                 pstep[2] = point_out.z ();
00441 
00442       // Convert the viewpoint as well
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         // Copy transformed point into cloud
00454         vpstep[0] = point_out.x ();
00455         vpstep[1] = point_out.y ();
00456         vpstep[2] = point_out.z ();
00457       }
00458     }
00459 
00460     //if the user didn't request the index field, then we need to copy the PointCloud and drop it
00461     if(!requested_index)
00462     {
00463       sensor_msgs::PointCloud2 cloud_without_index;
00464 
00465       //copy basic meta data
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       //copy the fields
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           //once we hit the index, we'll set the shift
00487           offset_shift = 4;
00488         }
00489       }
00490 
00491       //resize the fields
00492       cloud_without_index.fields.resize(field_count);
00493 
00494       //compute the size of the new data
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       //copy over the data from one cloud to the other
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       //make sure to actually set the output
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         //check if the user has requested the index field
00530         bool requested_index = false;
00531         if ((channel_options & channel_option::Index))
00532                 requested_index = true;
00533 
00534         //we'll enforce that we get index values for the laser scan so that we
00535         //ensure that we use the correct timestamps
00536         channel_options |= channel_option::Index;
00537 
00538         las3D_projectLaser_(scan_in, cloud_out, -1.0, channel_options);
00539 
00540         //we'll assume no associated viewpoint by default
00541         bool has_viewpoint = false;
00542         uint32_t vp_x_offset = 0;
00543 
00544         //we need to find the offset of the intensity field in the point cloud
00545         //we also know that the index field is guaranteed to exist since we 
00546         //set the channel option above. To be really safe, it might be worth
00547         //putting in a check at some point, but I'm just going to put in an
00548         //assert for now
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                 //we want to check if the cloud has a viewpoint associated with it
00558                 //checking vp_x should be sufficient since vp_x, vp_y, and vp_z all
00559                 //get put in together
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         // Extract transforms for the beginning and end of the laser scan
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         //cenas minhas
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         //we want to loop through all the points in the cloud
00616         for(size_t i = 0; i < cloud_out.width; ++i)
00617         {
00618                 // Apply the transform to the current point
00619                 float *pstep = (float*)&cloud_out.data[i * cloud_out.point_step + 0];
00620 
00621                 //find the index of the point
00622                 uint32_t pt_index;
00623                 memcpy(&pt_index, &cloud_out.data[i * cloud_out.point_step + index_offset], sizeof(uint32_t));
00624                 
00625                         // Assume constant motion during the laser-scan, and use slerp to compute intermediate transforms
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                 // Interpolate translation
00638                 v.setInterpolate3 (start_transform.getOrigin (), end_transform.getOrigin (), ratio);
00639                 cur_transform.setOrigin (v);
00640 
00641                 // Interpolate rotation
00642                 start_transform.getBasis ().getRotation (q1);
00643                 end_transform.getBasis ().getRotation (q2);
00644 
00645                 // Compute the slerp-ed rotation
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                 // Copy transformed point into cloud
00657                 pstep[0] = point_out.x ();
00658                 pstep[1] = point_out.y ();
00659                 pstep[2] = point_out.z ();
00660 
00661                 // Convert the viewpoint as well
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                 // Copy transformed point into cloud
00673                 vpstep[0] = point_out.x ();
00674                 vpstep[1] = point_out.y ();
00675                 vpstep[2] = point_out.z ();
00676                 }
00677         }
00678 
00679         //if the user didn't request the index field, then we need to copy the PointCloud and drop it
00680         if(!requested_index)
00681         {
00682                 sensor_msgs::PointCloud2 cloud_without_index;
00683 
00684                 //copy basic meta data
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                 //copy the fields
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                         //once we hit the index, we'll set the shift
00706                         offset_shift = 4;
00707                 }
00708                 }
00709 
00710                 //resize the fields
00711                 cloud_without_index.fields.resize(field_count);
00712 
00713                 //compute the size of the new data
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                 //copy over the data from one cloud to the other
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                 //make sure to actually set the output
00731                 cloud_out = cloud_without_index;
00732         }
00733 
00734         return 0;
00735 }
00736   


laser_3d_pointcloud
Author(s): Diogo Matos
autogenerated on Thu Nov 20 2014 11:35:41