laser_geometry.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  * 
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  * 
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  * 
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "laser_geometry/laser_geometry.h"
00031 #include <algorithm>
00032 #include <ros/assert.h>
00033 
00034 namespace laser_geometry
00035 {
00036 
00037   void
00038     LaserProjection::projectLaser_ (const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud & cloud_out, double range_cutoff, 
00039                                    bool preservative, int mask)
00040   {
00041     boost::numeric::ublas::matrix<double> ranges(2, scan_in.ranges.size());
00042 
00043     // Fill the ranges matrix
00044     for (unsigned int index = 0; index < scan_in.ranges.size(); index++)
00045       {
00046         ranges(0,index) = (double) scan_in.ranges[index];
00047         ranges(1,index) = (double) scan_in.ranges[index];
00048       }
00049     
00050 
00051     //Do the projection
00052     //    NEWMAT::Matrix output = NEWMAT::SP(ranges, getUnitVectors(scan_in.angle_min, scan_in.angle_max, scan_in.angle_increment));
00053     boost::numeric::ublas::matrix<double> output = element_prod(ranges, getUnitVectors_(scan_in.angle_min, scan_in.angle_max, scan_in.angle_increment, scan_in.ranges.size()));
00054 
00055     //Stuff the output cloud
00056     cloud_out.header = scan_in.header;
00057     cloud_out.points.resize (scan_in.ranges.size());
00058 
00059     // Define 4 indices in the channel array for each possible value type
00060     int idx_intensity = -1, idx_index = -1, idx_distance = -1, idx_timestamp = -1;
00061 
00062     cloud_out.channels.resize(0);    
00063 
00064     // Check if the intensity bit is set
00065     if ((mask & channel_option::Intensity) && scan_in.intensities.size() > 0)
00066     {
00067       int chan_size = cloud_out.channels.size();
00068       cloud_out.channels.resize (chan_size + 1);
00069       cloud_out.channels[0].name = "intensities";
00070       cloud_out.channels[0].values.resize (scan_in.intensities.size());
00071       idx_intensity = 0;
00072     }
00073     
00074     // Check if the index bit is set
00075     if (mask & channel_option::Index)
00076     {
00077       int chan_size = cloud_out.channels.size();
00078       cloud_out.channels.resize (chan_size +1);
00079       cloud_out.channels[chan_size].name = "index";
00080       cloud_out.channels[chan_size].values.resize (scan_in.ranges.size());
00081       idx_index = chan_size;
00082     }
00083 
00084     // Check if the distance bit is set
00085     if (mask & channel_option::Distance)
00086     {
00087       int chan_size = cloud_out.channels.size();
00088       cloud_out.channels.resize (chan_size + 1);
00089       cloud_out.channels[chan_size].name = "distances";
00090       cloud_out.channels[chan_size].values.resize (scan_in.ranges.size());
00091       idx_distance = chan_size;
00092     }
00093 
00094     if (mask & channel_option::Timestamp)
00095     {
00096       int chan_size = cloud_out.channels.size();
00097       cloud_out.channels.resize (chan_size + 1);
00098       cloud_out.channels[chan_size].name = "stamps";
00099       cloud_out.channels[chan_size].values.resize (scan_in.ranges.size());
00100       idx_timestamp = chan_size;
00101     }
00102 
00103     if (range_cutoff < 0)
00104       range_cutoff = scan_in.range_max;
00105     else
00106       range_cutoff = std::min(range_cutoff, (double)scan_in.range_max); 
00107     
00108     unsigned int count = 0;
00109     for (unsigned int index = 0; index< scan_in.ranges.size(); index++)
00110     {
00111       if (preservative || ((ranges(0,index) < range_cutoff) && (ranges(0,index) >= scan_in.range_min))) //if valid or preservative
00112       {
00113           
00114         cloud_out.points[count].x = output(0,index);
00115         cloud_out.points[count].y = output(1,index);
00116         cloud_out.points[count].z = 0.0;
00117           
00118         //double x = cloud_out.points[count].x;
00119         //double y = cloud_out.points[count].y;
00120         //if(x*x + y*y < scan_in.range_min * scan_in.range_min){
00121         //  ROS_INFO("(%.2f, %.2f)", cloud_out.points[count].x, cloud_out.points[count].y);
00122         //}
00123 
00124         // Save the original point index
00125         if (idx_index != -1)
00126           cloud_out.channels[idx_index].values[count] = index;
00127 
00128         // Save the original point distance
00129         if (idx_distance != -1)
00130           cloud_out.channels[idx_distance].values[count] = ranges (0, index);
00131 
00132         // Save intensities channel
00133         if (scan_in.intensities.size() >= index)
00134         { 
00135           if (idx_intensity != -1)
00136             cloud_out.channels[idx_intensity].values[count] = scan_in.intensities[index];
00137         }
00138 
00139         // Save timestamps to seperate channel if asked for
00140         if( idx_timestamp != -1)
00141                   cloud_out.channels[idx_timestamp].values[count] = (float)index*scan_in.time_increment;
00142 
00143         count++;
00144       }
00145     }
00146    
00147 
00148     //downsize if necessary
00149     cloud_out.points.resize (count);
00150     for (unsigned int d = 0; d < cloud_out.channels.size(); d++)
00151       cloud_out.channels[d].values.resize(count);
00152   };
00153 
00154 const boost::numeric::ublas::matrix<double>& LaserProjection::getUnitVectors_(double angle_min, double angle_max, double angle_increment, unsigned int length)
00155   {
00156     boost::mutex::scoped_lock guv_lock(this->guv_mutex_);
00157 
00158     //construct string for lookup in the map
00159     std::stringstream anglestring;
00160     anglestring <<angle_min<<","<<angle_max<<","<<angle_increment<<","<<length;
00161     std::map<std::string, boost::numeric::ublas::matrix<double>* >::iterator it;
00162     it = unit_vector_map_.find(anglestring.str());
00163     //check the map for presense
00164     if (it != unit_vector_map_.end())
00165       return *((*it).second);     //if present return
00166 
00167     boost::numeric::ublas::matrix<double> * tempPtr = new boost::numeric::ublas::matrix<double>(2,length);
00168     for (unsigned int index = 0;index < length; index++)
00169       {
00170         (*tempPtr)(0,index) = cos(angle_min + (double) index * angle_increment);
00171         (*tempPtr)(1,index) = sin(angle_min + (double) index * angle_increment);
00172       }
00173     //store 
00174     unit_vector_map_[anglestring.str()] = tempPtr;
00175     //and return
00176     return *tempPtr;
00177   };
00178 
00179 
00180   LaserProjection::~LaserProjection()
00181   {
00182     std::map<std::string, boost::numeric::ublas::matrix<double>*>::iterator it;
00183     it = unit_vector_map_.begin();
00184     while (it != unit_vector_map_.end())
00185       {
00186         delete (*it).second;
00187         it++;
00188       }
00189   };
00190 
00191   void
00192     LaserProjection::transformLaserScanToPointCloud_ (const std::string &target_frame, sensor_msgs::PointCloud &cloud_out, const sensor_msgs::LaserScan &scan_in,
00193                                                      tf::Transformer& tf, double range_cutoff, int mask)
00194   {
00195     cloud_out.header = scan_in.header;
00196 
00197     tf::Stamped<tf::Point> pointIn;
00198     tf::Stamped<tf::Point> pointOut;
00199 
00200     //check if the user has requested the index field
00201     bool requested_index = false;
00202     if ((mask & channel_option::Index))
00203       requested_index = true;
00204 
00205     //we need to make sure that we include the index in our mask
00206     //in order to guarantee that we get our timestamps right
00207     mask |= channel_option::Index;
00208 
00209     pointIn.frame_id_ = scan_in.header.frame_id;
00210 
00211     projectLaser_ (scan_in, cloud_out, range_cutoff, false, mask);
00212 
00213     cloud_out.header.frame_id = target_frame;
00214 
00215     // Extract transforms for the beginning and end of the laser scan
00216     ros::Time start_time = scan_in.header.stamp ;
00217     ros::Time end_time   = scan_in.header.stamp + ros::Duration().fromSec(scan_in.ranges.size()*scan_in.time_increment) ;
00218 
00219     tf::StampedTransform start_transform ;
00220     tf::StampedTransform end_transform ;
00221     tf::StampedTransform cur_transform ;
00222 
00223     tf.lookupTransform(target_frame, scan_in.header.frame_id, start_time, start_transform) ;
00224     tf.lookupTransform(target_frame, scan_in.header.frame_id, end_time, end_transform) ;
00225 
00226     //we need to find the index of the index channel
00227     int index_channel_idx = -1;
00228     for(unsigned int i = 0; i < cloud_out.channels.size(); ++i)
00229     {
00230       if(cloud_out.channels[i].name == "index")
00231       {
00232         index_channel_idx = i;
00233         break;
00234       }
00235     }
00236 
00237     //check just in case
00238     ROS_ASSERT(index_channel_idx >= 0);
00239 
00240     for(unsigned int i = 0; i < cloud_out.points.size(); ++i)
00241     {
00242       //get the index for this point
00243       uint32_t pt_index = cloud_out.channels[index_channel_idx].values[i];
00244 
00245       // Instead, assume constant motion during the laser-scan, and use slerp to compute intermediate transforms
00246       tfScalar ratio = pt_index / ( (double) scan_in.ranges.size() - 1.0) ;
00247 
00249 
00250       //Interpolate translation
00251       tf::Vector3 v (0, 0, 0);
00252       v.setInterpolate3(start_transform.getOrigin(), end_transform.getOrigin(), ratio) ;
00253       cur_transform.setOrigin(v) ;
00254 
00255       //Interpolate rotation
00256       tf::Quaternion q1, q2 ;
00257       start_transform.getBasis().getRotation(q1) ;
00258       end_transform.getBasis().getRotation(q2) ;
00259 
00260       // Compute the slerp-ed rotation
00261       cur_transform.setRotation( slerp( q1, q2 , ratio) ) ;
00262 
00263       // Apply the transform to the current point
00264       tf::Vector3 pointIn(cloud_out.points[i].x, cloud_out.points[i].y, cloud_out.points[i].z) ;
00265       tf::Vector3 pointOut = cur_transform * pointIn ;
00266 
00267       // Copy transformed point into cloud
00268       cloud_out.points[i].x  = pointOut.x();
00269       cloud_out.points[i].y  = pointOut.y();
00270       cloud_out.points[i].z  = pointOut.z();
00271     }
00272 
00273     //if the user didn't request the index, we want to remove it from the channels
00274     if(!requested_index)
00275       cloud_out.channels.erase(cloud_out.channels.begin() + index_channel_idx);
00276   }
00277 
00278   void LaserProjection::projectLaser_ (const sensor_msgs::LaserScan& scan_in, 
00279                                       sensor_msgs::PointCloud2 &cloud_out,
00280                                       double range_cutoff,
00281                                       int channel_options)
00282   {
00283     size_t n_pts = scan_in.ranges.size ();
00284     Eigen::ArrayXXd ranges (n_pts, 2);
00285     Eigen::ArrayXXd output (n_pts, 2);
00286 
00287     // Get the ranges into Eigen format
00288     for (size_t i = 0; i < n_pts; ++i)
00289     {
00290       ranges (i, 0) = (double) scan_in.ranges[i];
00291       ranges (i, 1) = (double) scan_in.ranges[i];
00292     }
00293 
00294     // Check if our existing co_sine_map is valid
00295     if (co_sine_map_.rows () != (int)n_pts || angle_min_ != scan_in.angle_min || angle_max_ != scan_in.angle_max )
00296     {
00297       ROS_DEBUG ("[projectLaser] No precomputed map given. Computing one.");
00298       co_sine_map_ = Eigen::ArrayXXd (n_pts, 2);
00299       angle_min_ = scan_in.angle_min;
00300       angle_max_ = scan_in.angle_max;
00301       // Spherical->Cartesian projection
00302       for (size_t i = 0; i < n_pts; ++i)
00303       {
00304         co_sine_map_ (i, 0) = cos (scan_in.angle_min + (double) i * scan_in.angle_increment);
00305         co_sine_map_ (i, 1) = sin (scan_in.angle_min + (double) i * scan_in.angle_increment);
00306       }
00307     }
00308 
00309     output = ranges * co_sine_map_;
00310 
00311     // Set the output cloud accordingly
00312     cloud_out.header = scan_in.header;
00313     cloud_out.height = 1;
00314     cloud_out.width  = scan_in.ranges.size ();
00315     cloud_out.fields.resize (3);
00316     cloud_out.fields[0].name = "x";
00317     cloud_out.fields[0].offset = 0;
00318     cloud_out.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00319     cloud_out.fields[1].name = "y";
00320     cloud_out.fields[1].offset = 4;
00321     cloud_out.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00322     cloud_out.fields[2].name = "z";
00323     cloud_out.fields[2].offset = 8;
00324     cloud_out.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00325 
00326     // Define 4 indices in the channel array for each possible value type
00327     int idx_intensity = -1, idx_index = -1, idx_distance = -1, idx_timestamp = -1, idx_vpx = -1, idx_vpy = -1, idx_vpz = -1;
00328 
00329     //now, we need to check what fields we need to store
00330     int offset = 12;
00331     if ((channel_options & channel_option::Intensity) && scan_in.intensities.size() > 0)
00332     {
00333       int field_size = cloud_out.fields.size();
00334       cloud_out.fields.resize(field_size + 1);
00335       cloud_out.fields[field_size].name = "intensity";
00336       cloud_out.fields[field_size].datatype = sensor_msgs::PointField::FLOAT32;
00337       cloud_out.fields[field_size].offset = offset;
00338       offset += 4;
00339       idx_intensity = field_size;
00340     }
00341 
00342     if ((channel_options & channel_option::Index))
00343     {
00344       int field_size = cloud_out.fields.size();
00345       cloud_out.fields.resize(field_size + 1);
00346       cloud_out.fields[field_size].name = "index";
00347       cloud_out.fields[field_size].datatype = sensor_msgs::PointField::INT32;
00348       cloud_out.fields[field_size].offset = offset;
00349       offset += 4;
00350       idx_index = field_size;
00351     }
00352 
00353     if ((channel_options & channel_option::Distance))
00354     {
00355       int field_size = cloud_out.fields.size();
00356       cloud_out.fields.resize(field_size + 1);
00357       cloud_out.fields[field_size].name = "distances";
00358       cloud_out.fields[field_size].datatype = sensor_msgs::PointField::FLOAT32;
00359       cloud_out.fields[field_size].offset = offset;
00360       offset += 4;
00361       idx_distance = field_size;
00362     }
00363 
00364     if ((channel_options & channel_option::Timestamp))
00365     {
00366       int field_size = cloud_out.fields.size();
00367       cloud_out.fields.resize(field_size + 1);
00368       cloud_out.fields[field_size].name = "stamps";
00369       cloud_out.fields[field_size].datatype = sensor_msgs::PointField::FLOAT32;
00370       cloud_out.fields[field_size].offset = offset;
00371       offset += 4;
00372       idx_timestamp = field_size;
00373     }
00374 
00375     if ((channel_options & channel_option::Viewpoint))
00376     {
00377       int field_size = cloud_out.fields.size();
00378       cloud_out.fields.resize(field_size + 3);
00379 
00380       cloud_out.fields[field_size].name = "vp_x";
00381       cloud_out.fields[field_size].datatype = sensor_msgs::PointField::FLOAT32;
00382       cloud_out.fields[field_size].offset = offset;
00383       offset += 4;
00384 
00385       cloud_out.fields[field_size + 1].name = "vp_y";
00386       cloud_out.fields[field_size + 1].datatype = sensor_msgs::PointField::FLOAT32;
00387       cloud_out.fields[field_size + 1].offset = offset;
00388       offset += 4;
00389 
00390       cloud_out.fields[field_size + 2].name = "vp_z";
00391       cloud_out.fields[field_size + 2].datatype = sensor_msgs::PointField::FLOAT32;
00392       cloud_out.fields[field_size + 2].offset = offset;
00393       offset += 4;
00394 
00395       idx_vpx = field_size;
00396       idx_vpy = field_size + 1;
00397       idx_vpz = field_size + 2;
00398     }
00399 
00400     cloud_out.point_step = offset;
00401     cloud_out.row_step   = cloud_out.point_step * cloud_out.width;
00402     cloud_out.data.resize (cloud_out.row_step   * cloud_out.height);
00403     cloud_out.is_dense = false;
00404 
00405     //TODO: Find out why this was needed
00406     //float bad_point = std::numeric_limits<float>::quiet_NaN ();
00407 
00408     if (range_cutoff < 0)
00409       range_cutoff = scan_in.range_max;
00410     else
00411       range_cutoff = std::min(range_cutoff, (double)scan_in.range_max); 
00412 
00413     unsigned int count = 0;
00414     for (size_t i = 0; i < n_pts; ++i)
00415     {
00416       //check to see if we want to keep the point
00417       if (scan_in.ranges[i] <= range_cutoff && scan_in.ranges[i] >= scan_in.range_min)
00418       {
00419         float *pstep = (float*)&cloud_out.data[count * cloud_out.point_step];
00420 
00421         // Copy XYZ
00422         pstep[0] = output (i, 0);
00423         pstep[1] = output (i, 1);
00424         pstep[2] = 0;
00425 
00426         // Copy intensity
00427         if(idx_intensity != -1)
00428           pstep[idx_intensity] = scan_in.intensities[i];
00429 
00430         //Copy index
00431         if(idx_index != -1)
00432           ((int*)(pstep))[idx_index] = i;
00433 
00434         // Copy distance
00435         if(idx_distance != -1)
00436           pstep[idx_distance] = scan_in.ranges[i];
00437 
00438         // Copy timestamp
00439         if(idx_timestamp != -1)
00440           pstep[idx_timestamp] = i * scan_in.time_increment;
00441 
00442         // Copy viewpoint (0, 0, 0)
00443         if(idx_vpx != -1 && idx_vpy != -1 && idx_vpz != -1)
00444         {
00445           pstep[idx_vpx] = 0;
00446           pstep[idx_vpy] = 0;
00447           pstep[idx_vpz] = 0;
00448         }
00449 
00450         //make sure to increment count
00451         ++count;
00452       }
00453 
00454       /* 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
00455        * why can't you just leave them out?
00456        *
00457       // Invalid measurement?
00458       if (scan_in.ranges[i] >= range_cutoff || scan_in.ranges[i] <= scan_in.range_min)
00459       {
00460         if (scan_in.ranges[i] != LASER_SCAN_MAX_RANGE)
00461         {
00462           for (size_t s = 0; s < cloud_out.fields.size (); ++s)
00463             pstep[s] = bad_point;
00464         }
00465         else
00466         {
00467           // Kind of nasty thing:
00468           //   We keep the oringinal point information for max ranges but set x to NAN to mark the point as invalid.
00469           //   Since we still might need the x value we store it in the distance field
00470           pstep[0] = bad_point;           // X -> NAN to mark a bad point
00471           pstep[1] = co_sine_map (i, 1);  // Y
00472           pstep[2] = 0;                   // Z
00473 
00474           if (store_intensity)
00475           {
00476             pstep[3] = bad_point;           // Intensity -> NAN to mark a bad point
00477             pstep[4] = co_sine_map (i, 0);  // Distance -> Misused to store the originnal X
00478           }
00479           else
00480             pstep[3] = co_sine_map (i, 0);  // Distance -> Misused to store the originnal X
00481         }
00482       }
00483       */
00484     }
00485 
00486     //resize if necessary
00487     cloud_out.width = count;
00488     cloud_out.row_step   = cloud_out.point_step * cloud_out.width;
00489     cloud_out.data.resize (cloud_out.row_step   * cloud_out.height);
00490   }
00491 
00492   void LaserProjection::transformLaserScanToPointCloud_ (const std::string &target_frame, 
00493                                                         const sensor_msgs::LaserScan &scan_in,
00494                                                         sensor_msgs::PointCloud2 &cloud_out, 
00495                                                         tf::Transformer &tf, 
00496                                                         double range_cutoff,
00497                                                         int channel_options)
00498   {
00499     //check if the user has requested the index field
00500     bool requested_index = false;
00501     if ((channel_options & channel_option::Index))
00502       requested_index = true;
00503 
00504     //we'll enforce that we get index values for the laser scan so that we
00505     //ensure that we use the correct timestamps
00506     channel_options |= channel_option::Index;
00507 
00508     projectLaser_(scan_in, cloud_out, -1.0, channel_options);
00509 
00510     //we'll assume no associated viewpoint by default
00511     bool has_viewpoint = false;
00512     uint32_t vp_x_offset = 0;
00513 
00514     //we need to find the offset of the intensity field in the point cloud
00515     //we also know that the index field is guaranteed to exist since we 
00516     //set the channel option above. To be really safe, it might be worth
00517     //putting in a check at some point, but I'm just going to put in an
00518     //assert for now
00519     uint32_t index_offset = 0;
00520     for(unsigned int i = 0; i < cloud_out.fields.size(); ++i)
00521     {
00522       if(cloud_out.fields[i].name == "index")
00523       {
00524         index_offset = cloud_out.fields[i].offset;
00525       }
00526 
00527       //we want to check if the cloud has a viewpoint associated with it
00528       //checking vp_x should be sufficient since vp_x, vp_y, and vp_z all
00529       //get put in together
00530       if(cloud_out.fields[i].name == "vp_x")
00531       {
00532         has_viewpoint = true;
00533         vp_x_offset = cloud_out.fields[i].offset;
00534       }
00535     }
00536 
00537     ROS_ASSERT(index_offset > 0);
00538 
00539     cloud_out.header.frame_id = target_frame;
00540 
00541     // Extract transforms for the beginning and end of the laser scan
00542     ros::Time start_time = scan_in.header.stamp;
00543     ros::Time end_time   = scan_in.header.stamp + ros::Duration ().fromSec (scan_in.ranges.size () * scan_in.time_increment);
00544 
00545     tf::StampedTransform start_transform, end_transform, cur_transform ;
00546 
00547     tf.lookupTransform (target_frame, scan_in.header.frame_id, start_time, start_transform);
00548     tf.lookupTransform (target_frame, scan_in.header.frame_id, end_time, end_transform);
00549 
00550     double ranges_norm = 1 / ((double) scan_in.ranges.size () - 1.0);
00551 
00552     //we want to loop through all the points in the cloud
00553     for(size_t i = 0; i < cloud_out.width; ++i)
00554     {
00555       // Apply the transform to the current point
00556       float *pstep = (float*)&cloud_out.data[i * cloud_out.point_step + 0];
00557 
00558       //find the index of the point
00559       uint32_t pt_index;
00560       memcpy(&pt_index, &cloud_out.data[i * cloud_out.point_step + index_offset], sizeof(uint32_t));
00561       
00562       // Assume constant motion during the laser-scan, and use slerp to compute intermediate transforms
00563       tfScalar ratio = pt_index * ranges_norm;
00564 
00566       // Interpolate translation
00567       tf::Vector3 v (0, 0, 0);
00568       v.setInterpolate3 (start_transform.getOrigin (), end_transform.getOrigin (), ratio);
00569       cur_transform.setOrigin (v);
00570 
00571       // Interpolate rotation
00572       tf::Quaternion q1, q2;
00573       start_transform.getBasis ().getRotation (q1);
00574       end_transform.getBasis ().getRotation (q2);
00575 
00576       // Compute the slerp-ed rotation
00577       cur_transform.setRotation (slerp (q1, q2 , ratio));
00578 
00579       tf::Vector3 point_in (pstep[0], pstep[1], pstep[2]);
00580       tf::Vector3 point_out = cur_transform * point_in;
00581 
00582       // Copy transformed point into cloud
00583       pstep[0] = point_out.x ();
00584       pstep[1] = point_out.y ();
00585       pstep[2] = point_out.z ();
00586 
00587       // Convert the viewpoint as well
00588       if(has_viewpoint)
00589       {
00590         float *vpstep = (float*)&cloud_out.data[i * cloud_out.point_step + vp_x_offset];
00591         point_in = tf::Vector3 (vpstep[0], vpstep[1], vpstep[2]);
00592         point_out = cur_transform * point_in;
00593 
00594         // Copy transformed point into cloud
00595         vpstep[0] = point_out.x ();
00596         vpstep[1] = point_out.y ();
00597         vpstep[2] = point_out.z ();
00598       }
00599     }
00600 
00601     //if the user didn't request the index field, then we need to copy the PointCloud and drop it
00602     if(!requested_index)
00603     {
00604       sensor_msgs::PointCloud2 cloud_without_index;
00605 
00606       //copy basic meta data
00607       cloud_without_index.header = cloud_out.header;
00608       cloud_without_index.width = cloud_out.width;
00609       cloud_without_index.height = cloud_out.height;
00610       cloud_without_index.is_bigendian = cloud_out.is_bigendian;
00611       cloud_without_index.is_dense = cloud_out.is_dense;
00612 
00613       //copy the fields
00614       cloud_without_index.fields.resize(cloud_out.fields.size());
00615       unsigned int field_count = 0;
00616       unsigned int offset_shift = 0;
00617       for(unsigned int i = 0; i < cloud_out.fields.size(); ++i)
00618       {
00619         if(cloud_out.fields[i].name != "index")
00620         {
00621           cloud_without_index.fields[field_count] = cloud_out.fields[i];
00622           cloud_without_index.fields[field_count].offset -= offset_shift;
00623           ++field_count;
00624         }
00625         else
00626         {
00627           //once we hit the index, we'll set the shift
00628           offset_shift = 4;
00629         }
00630       }
00631 
00632       //resize the fields
00633       cloud_without_index.fields.resize(field_count);
00634 
00635       //compute the size of the new data
00636       cloud_without_index.point_step = cloud_out.point_step - offset_shift;
00637       cloud_without_index.row_step   = cloud_without_index.point_step * cloud_without_index.width;
00638       cloud_without_index.data.resize (cloud_without_index.row_step   * cloud_without_index.height);
00639 
00640       uint32_t i = 0;
00641       uint32_t j = 0;
00642       //copy over the data from one cloud to the other
00643       while (i < cloud_out.data.size())
00644       {
00645         if((i % cloud_out.point_step) < index_offset || (i % cloud_out.point_step) >= (index_offset + 4))
00646         {
00647           cloud_without_index.data[j++] = cloud_out.data[i];
00648         }
00649         i++;
00650       }
00651 
00652       //make sure to actually set the output
00653       cloud_out = cloud_without_index;
00654     }
00655   }
00656 
00657 
00658 } //laser_geometry


laser_geometry
Author(s): Tully Foote, Radu Bogdan Rusu
autogenerated on Fri Jan 3 2014 11:27:34