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