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
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <pcl/features/narf.h>
00039 #include <pcl/features/narf_descriptor.h>
00040
00041 #include <iostream>
00042 #include <fstream>
00043 #include <cmath>
00044 using std::cout;
00045 using std::cerr;
00046 using std::vector;
00047
00048 using Eigen::Vector3f;
00049
00050 #include <pcl/range_image/range_image.h>
00051 #include <pcl/common/vector_average.h>
00052 #include <pcl/common/common_headers.h>
00053
00054 namespace pcl
00055 {
00056 int Narf::max_no_of_threads = 1;
00057
00059 Narf::Narf() :
00060 position_ (), transformation_ (), surface_patch_ (NULL),
00061 surface_patch_pixel_size_ (0), surface_patch_world_size_ (),
00062 surface_patch_rotation_ (), descriptor_ (NULL), descriptor_size_ (0)
00063 {
00064 reset();
00065 }
00066
00068 Narf::~Narf()
00069 {
00070 reset();
00071 }
00072
00074 Narf::Narf (const Narf& other) :
00075 position_ (), transformation_ (), surface_patch_ (NULL),
00076 surface_patch_pixel_size_ (0), surface_patch_world_size_ (),
00077 surface_patch_rotation_ (), descriptor_ (NULL), descriptor_size_ (0)
00078 {
00079 deepCopy (other);
00080 }
00081
00083 const Narf&
00084 Narf::operator= (const Narf& other)
00085 {
00086 deepCopy (other);
00087 return (*this);
00088 }
00089
00091 void
00092 Narf::reset ()
00093 {
00094 delete[] descriptor_;
00095 descriptor_ = NULL;
00096 descriptor_size_ = 0;
00097 delete[] surface_patch_;
00098 surface_patch_ = NULL;
00099 surface_patch_pixel_size_ = 0;
00100 surface_patch_world_size_ = 0.0f;
00101 surface_patch_rotation_ = 0.0f;
00102 }
00103
00105 void
00106 Narf::deepCopy (const Narf& other)
00107 {
00108
00109 if (&other == this)
00110 return;
00111
00112 position_ = other.position_;
00113 transformation_ = other.transformation_;
00114
00115 if (surface_patch_pixel_size_ != other.surface_patch_pixel_size_)
00116 {
00117 surface_patch_pixel_size_ = other.surface_patch_pixel_size_;
00118 delete[] surface_patch_;
00119 surface_patch_ = new float[surface_patch_pixel_size_*surface_patch_pixel_size_];
00120 }
00121 memcpy(surface_patch_, other.surface_patch_, sizeof(*surface_patch_)*surface_patch_pixel_size_*surface_patch_pixel_size_);
00122 surface_patch_world_size_ = other.surface_patch_world_size_;
00123 surface_patch_rotation_ = other.surface_patch_rotation_;
00124
00125 if (descriptor_size_ != other.descriptor_size_)
00126 {
00127 descriptor_size_ = other.descriptor_size_;
00128 delete[] descriptor_;
00129 descriptor_ = new float[descriptor_size_];
00130 }
00131 memcpy(descriptor_, other.descriptor_, sizeof(*descriptor_)*descriptor_size_);
00132 }
00133
00135 bool
00136 Narf::extractDescriptor (int descriptor_size)
00137 {
00138 float weight_for_first_point = 2.0f;
00139 int no_of_beam_points = getNoOfBeamPoints();
00140 float weight_factor = -2.0f*(weight_for_first_point-1.0f) / ((weight_for_first_point+1.0f)*float(no_of_beam_points-1)),
00141 weight_offset = 2.0f*weight_for_first_point / (weight_for_first_point+1.0f);
00142
00143 if (descriptor_size != descriptor_size_)
00144 {
00145 descriptor_size_ = descriptor_size;
00146 delete descriptor_;
00147 descriptor_ = new float[descriptor_size_];
00148 }
00149 float angle_step_size = deg2rad (360.0f) / static_cast<float> (descriptor_size_);
00150
00151
00152 float cell_size = surface_patch_world_size_/float(surface_patch_pixel_size_),
00153 cell_factor = 1.0f/cell_size,
00154 cell_offset = 0.5f*(surface_patch_world_size_ - cell_size),
00155 max_dist = 0.5f*surface_patch_world_size_,
00156 beam_point_factor = (max_dist-0.5f*cell_size) / static_cast<float> (no_of_beam_points);
00157
00158 for (int descriptor_value_idx=0; descriptor_value_idx<descriptor_size_; ++descriptor_value_idx)
00159 {
00160 float& descriptor_value = descriptor_[descriptor_value_idx];
00161 descriptor_value = 0.0f;
00162 float angle = static_cast<float> (descriptor_value_idx) * angle_step_size + surface_patch_rotation_,
00163 beam_point_factor_x = sinf(angle) * beam_point_factor,
00164 beam_point_factor_y = -cosf (angle) * beam_point_factor;
00165
00166 std::vector<float> beam_values (no_of_beam_points + 1);
00167 float current_cell = 0.0f;
00168 for (int beam_point_idx=0; beam_point_idx<=no_of_beam_points; ++beam_point_idx)
00169 {
00170 float& beam_value = beam_values[beam_point_idx];
00171
00172 float beam_point_x = beam_point_factor_x * static_cast<float> (beam_point_idx),
00173 beam_point_y = beam_point_factor_y * static_cast<float> (beam_point_idx);
00174 float beam_point_cell_x = cell_factor * (beam_point_x + cell_offset),
00175 beam_point_cell_y = cell_factor * (beam_point_y + cell_offset);
00176
00177 int cell_x = static_cast<int> (pcl_lrint (beam_point_cell_x)), cell_y = static_cast<int> (pcl_lrint (beam_point_cell_y));
00178 beam_value = surface_patch_[cell_y*surface_patch_pixel_size_ + cell_x];
00179 if (!pcl_isfinite(beam_value))
00180 {
00181 if (beam_value > 0.0f)
00182 beam_value = max_dist;
00183 else
00184 beam_value = -std::numeric_limits<float>::infinity ();
00185 }
00186 }
00187 for (int beam_value_idx=0; beam_value_idx<no_of_beam_points; ++beam_value_idx)
00188 {
00189 float beam_value1=beam_values[beam_value_idx],
00190 beam_value2=beam_values[beam_value_idx+1];
00191
00192 float current_weight = weight_factor*float(beam_value_idx) + weight_offset;
00193 float diff = beam_value2-beam_value1;
00194 current_cell += current_weight * diff;
00195 }
00196
00197 current_cell = atan2f (current_cell, max_dist) / deg2rad(180.0f);
00198 descriptor_value = current_cell;
00199 }
00200 return true;
00201 }
00202
00204 bool
00205 Narf::extractFromRangeImage (const RangeImage& range_image, const Eigen::Affine3f& pose, int descriptor_size,
00206 float support_size, int surface_patch_pixel_size)
00207 {
00208 reset();
00209 transformation_ = pose;
00210 position_ = pose.inverse (Eigen::Isometry).translation ();
00211 surface_patch_world_size_ = support_size;
00212 surface_patch_pixel_size_ = surface_patch_pixel_size;
00213 surface_patch_rotation_ = 0.0f;
00214 surface_patch_ = range_image.getInterpolatedSurfaceProjection(pose, surface_patch_pixel_size_, surface_patch_world_size_);
00215 int new_pixel_size = 2*surface_patch_pixel_size_;
00216 int blur_radius = 1;
00217 float* new_surface_patch = getBlurredSurfacePatch(new_pixel_size, blur_radius);
00218 delete[] surface_patch_;
00219 surface_patch_pixel_size_ = new_pixel_size;
00220 surface_patch_ = new_surface_patch;
00221 extractDescriptor(descriptor_size);
00222 return true;
00223 }
00224
00226 bool
00227 Narf::extractFromRangeImage (const RangeImage& range_image, float x, float y, int descriptor_size, float support_size)
00228 {
00229 if (!range_image.isValid (static_cast<int> (pcl_lrint (x)), static_cast<int> (pcl_lrint (y))))
00230 return (false);
00231 Eigen::Vector3f feature_pos;
00232 range_image.calculate3DPoint(x, y, feature_pos);
00233
00234 return (extractFromRangeImage (range_image, feature_pos, descriptor_size, support_size));
00235 }
00236
00238 bool
00239 Narf::extractFromRangeImage (const RangeImage& range_image, const InterestPoint& interest_point, int descriptor_size, float support_size)
00240 {
00241 return extractFromRangeImage(range_image, Eigen::Vector3f(interest_point.x, interest_point.y, interest_point.z), descriptor_size, support_size);
00242 }
00243
00245 bool
00246 Narf::extractFromRangeImage (const RangeImage& range_image, const Eigen::Vector3f& interest_point, int descriptor_size, float support_size)
00247 {
00248 if (!range_image.getNormalBasedUprightTransformation(interest_point, 0.5f*support_size, transformation_))
00249 return false;
00250 return extractFromRangeImage(range_image, transformation_, descriptor_size, support_size);
00251 }
00252
00254 bool
00255 Narf::extractFromRangeImageWithBestRotation (const RangeImage& range_image, const Eigen::Vector3f& interest_point,
00256 int descriptor_size, float support_size)
00257 {
00258 extractFromRangeImage(range_image, interest_point, descriptor_size, support_size);
00259 vector<float> rotations, strengths;
00260 getRotations(rotations, strengths);
00261 if (rotations.empty())
00262 return false;
00263 float best_rotation=rotations[0], best_strength=strengths[0];
00264 for (unsigned int i=1; i<rotations.size(); ++i)
00265 {
00266 if (strengths[i] > best_strength)
00267 {
00268 best_rotation = rotations[i];
00269 best_strength = strengths[i];
00270 }
00271 }
00272
00273 transformation_ = Eigen::AngleAxisf(-best_rotation, Eigen::Vector3f(0.0f, 0.0f, 1.0f))*transformation_;
00274 surface_patch_rotation_ = best_rotation;
00275 return extractDescriptor(descriptor_size_);
00276 }
00277
00279 float*
00280 Narf::getBlurredSurfacePatch (int new_pixel_size, int blur_radius) const
00281 {
00282 float new_to_old_factor = float(surface_patch_pixel_size_)/float(new_pixel_size);
00283 int new_size = new_pixel_size*new_pixel_size;
00284
00285 float* integral_image = new float[new_size];
00286 float* integral_image_ptr = integral_image;
00287 for (int y=0; y<new_pixel_size; ++y)
00288 {
00289 for (int x=0; x<new_pixel_size; ++x)
00290 {
00291 float& integral_pixel = *(integral_image_ptr++);
00292 int old_x = static_cast<int> (pcl_lrint (floor (new_to_old_factor * float (x)))),
00293 old_y = static_cast<int> (pcl_lrint (floor (new_to_old_factor * float (y))));
00294 integral_pixel = surface_patch_[old_y*surface_patch_pixel_size_ + old_x];
00295 if (pcl_isinf(integral_pixel))
00296 integral_pixel = 0.5f*surface_patch_world_size_;
00297 float left_value=0, top_left_value=0, top_value=0;
00298 if (x>0)
00299 {
00300 left_value = integral_image[y*new_pixel_size+x-1];
00301 if (y>0)
00302 top_left_value = integral_image[(y-1)*new_pixel_size+x-1];
00303 }
00304 if (y>0)
00305 top_value = integral_image[(y-1)*new_pixel_size+x];
00306
00307 integral_pixel += left_value + top_value - top_left_value;
00308
00309 }
00310 }
00311
00312 float* new_surface_patch = new float[new_size];
00313 float* new_surface_patch_ptr = new_surface_patch;
00314 for (int y=0; y<new_pixel_size; ++y)
00315 {
00316 for (int x=0; x<new_pixel_size; ++x)
00317 {
00318 float& new_value = *(new_surface_patch_ptr++);
00319
00320 int top = (std::max) (-1, y-blur_radius-1), right=(std::min) (new_pixel_size-1, x+blur_radius), bottom = (std::min) (new_pixel_size-1, y+blur_radius), left=(std::max) (-1, x-blur_radius-1),
00321 pixelSum = (right-left)*(bottom-top);
00322 float normalizationFactor = 1.0f / static_cast<float> (pixelSum);
00323
00324 float top_left_value=0, top_right_value=0, bottom_right_value=integral_image[bottom*new_pixel_size+right], bottom_left_value=0;
00325 if (left>=0)
00326 {
00327 bottom_left_value = integral_image[bottom*new_pixel_size+left];
00328 if (top>=0)
00329 top_left_value = integral_image[top*new_pixel_size+left];
00330 }
00331 if (top>=0)
00332 top_right_value = integral_image[top*new_pixel_size+right];
00333 new_value = normalizationFactor * (bottom_right_value + top_left_value - bottom_left_value - top_right_value);
00334 }
00335 }
00336 delete[] integral_image;
00337 return new_surface_patch;
00338 }
00339
00341 void
00342 Narf::extractFromRangeImageAndAddToList (const RangeImage& range_image, const Eigen::Vector3f& interest_point, int descriptor_size,
00343 float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list)
00344 {
00345 Narf* feature = new Narf;
00346 if (!feature->extractFromRangeImage(range_image, interest_point, descriptor_size, support_size))
00347 {
00348 delete feature;
00349 return;
00350 }
00351 if (!rotation_invariant)
00352 {
00353 feature_list.push_back(feature);
00354 return;
00355 }
00356 vector<float> rotations, strengths;
00357 feature->getRotations(rotations, strengths);
00358 feature->getRotatedVersions(range_image, rotations, feature_list);
00359 delete feature;
00360 }
00361
00363 void
00364 Narf::extractFromRangeImageAndAddToList (const RangeImage& range_image, float image_x, float image_y, int descriptor_size,
00365 float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list)
00366 {
00367 if (!range_image.isValid (static_cast<int> (pcl_lrint (image_x)), static_cast<int> (pcl_lrint (image_y))))
00368 return;
00369 Eigen::Vector3f feature_pos;
00370 range_image.calculate3DPoint(image_x, image_y, feature_pos);
00371 extractFromRangeImageAndAddToList(range_image, feature_pos, descriptor_size, support_size, rotation_invariant, feature_list);
00372 }
00373
00375 void
00376 Narf::extractForInterestPoints (const RangeImage& range_image, const PointCloud<InterestPoint>& interest_points,
00377 int descriptor_size, float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list)
00378 {
00379 # pragma omp parallel for num_threads(max_no_of_threads) default(shared) schedule(dynamic, 10)
00380
00381 for (int interest_point_idx = 0; interest_point_idx < int (interest_points.points.size ()); ++interest_point_idx)
00382 {
00383 Vector3fMapConst point = interest_points.points[interest_point_idx].getVector3fMap ();
00384
00385 Narf* feature = new Narf;
00386 if (!feature->extractFromRangeImage(range_image, point, descriptor_size, support_size))
00387 {
00388 delete feature;
00389 }
00390 else {
00391 if (!rotation_invariant)
00392 {
00393 # pragma omp critical
00394 {
00395 feature_list.push_back(feature);
00396 }
00397 }
00398 else {
00399 vector<float> rotations, strengths;
00400 feature->getRotations(rotations, strengths);
00401 {
00402
00403 for (unsigned int i=0; i<rotations.size(); ++i)
00404 {
00405 float rotation = rotations[i];
00406 Narf* feature2 = new Narf(*feature);
00407 feature2->transformation_ = Eigen::AngleAxisf(-rotation, Eigen::Vector3f(0.0f, 0.0f, 1.0f))*feature2->transformation_;
00408 feature2->surface_patch_rotation_ = rotation;
00409 if (!feature2->extractDescriptor(feature2->descriptor_size_))
00410 {
00411 delete feature2;
00412 continue;
00413 }
00414 # pragma omp critical
00415 {
00416 feature_list.push_back(feature2);
00417 }
00418 }
00419 }
00420 delete feature;
00421 }
00422 }
00423 }
00424 }
00425
00427 void
00428 Narf::extractForEveryRangeImagePointAndAddToList (const RangeImage& range_image, int descriptor_size, float support_size,
00429 bool rotation_invariant, std::vector<Narf*>& feature_list)
00430 {
00431 for (unsigned int y=0; y<range_image.height; ++y)
00432 {
00433 for (unsigned int x=0; x<range_image.width; ++x)
00434 {
00435 extractFromRangeImageAndAddToList(range_image, static_cast<float> (x), static_cast<float> (y), descriptor_size, support_size,
00436 rotation_invariant, feature_list);
00437 }
00438 }
00439 }
00440
00442 void
00443 Narf::getRotations (std::vector<float>& rotations, std::vector<float>& strengths) const
00444 {
00445 int angle_steps_no = (std::max) (descriptor_size_, 36);
00446 float min_angle_dist_between_rotations = deg2rad(70.0f);
00447 float angle_step_size1 = deg2rad (360.0f) / static_cast<float> (angle_steps_no);
00448 float angle_step_size2 = deg2rad (360.0f) / static_cast<float> (descriptor_size_);
00449
00450 float score_normalization = 1.0f / static_cast<float> (descriptor_size_);
00451
00452 std::multimap<float, float> scored_orientations;
00453 for (int step=0; step<angle_steps_no; ++step)
00454 {
00455 float angle = static_cast<float> (step) * angle_step_size1;
00456 float score = 0.0f;
00457
00458 for (int descriptor_value_idx=0; descriptor_value_idx<descriptor_size_; ++descriptor_value_idx)
00459 {
00460 float value = descriptor_[descriptor_value_idx];
00461 float angle2 = static_cast<float> (descriptor_value_idx) * angle_step_size2;
00462 float distance_weight = powf (1.0f - fabsf (normAngle (angle - angle2)) / deg2rad (180.0f), 2.0f);
00463
00464 score += value * distance_weight;
00465 }
00466 score = score_normalization*score + 0.5f;
00467 scored_orientations.insert(std::make_pair(score, angle));
00468 }
00469
00470
00471
00472
00473 float min_score = scored_orientations.begin()->first,
00474 max_score = scored_orientations.rbegin()->first;
00475
00476 float min_score_for_remaining_rotations = max_score - 0.2f*(max_score-min_score);
00477 scored_orientations.erase(scored_orientations.begin(), scored_orientations.upper_bound(min_score_for_remaining_rotations));
00478
00479
00480 while (!scored_orientations.empty())
00481 {
00482 std::multimap<float, float>::iterator best_remaining_orientation_it = scored_orientations.end();
00483 --best_remaining_orientation_it;
00484 rotations.push_back(best_remaining_orientation_it->second);
00485 strengths.push_back(best_remaining_orientation_it->first);
00486 scored_orientations.erase(best_remaining_orientation_it);
00487 for (std::multimap<float, float>::iterator it = scored_orientations.begin(); it!=scored_orientations.end();)
00488 {
00489 std::multimap<float, float>::iterator current_it = it++;
00490 if (normAngle(current_it->second - rotations.back()) < min_angle_dist_between_rotations)
00491 scored_orientations.erase(current_it);
00492 }
00493 }
00494 }
00495
00497 void
00498 Narf::getRotatedVersions (const RangeImage&, const std::vector<float>& rotations, std::vector<Narf*>& features) const
00499 {
00500 for (unsigned int i=0; i<rotations.size(); ++i)
00501 {
00502 float rotation = rotations[i];
00503
00504 Narf* feature = new Narf(*this);
00505 feature->transformation_ = Eigen::AngleAxisf(-rotation, Eigen::Vector3f(0.0f, 0.0f, 1.0f))*feature->transformation_;
00506 feature->surface_patch_rotation_ = rotation;
00507 if (!feature->extractDescriptor(feature->descriptor_size_))
00508 {
00509 delete feature;
00510 continue;
00511 }
00512 features.push_back(feature);
00513 }
00514 }
00515
00517 void
00518 Narf::saveHeader (std::ostream& file) const
00519 {
00520 file << "\n"<<getHeaderKeyword()<<" "<<Narf::VERSION<<" ";
00521 }
00522
00524 void
00525 Narf::saveBinary (std::ostream& file) const
00526 {
00527 saveHeader(file);
00528 pcl::saveBinary(position_.matrix(), file);
00529 pcl::saveBinary(transformation_.matrix(), file);
00530 file.write(reinterpret_cast<const char*>(&surface_patch_pixel_size_), sizeof(surface_patch_pixel_size_));
00531 file.write(reinterpret_cast<const char*>(surface_patch_),
00532 surface_patch_pixel_size_*surface_patch_pixel_size_*sizeof(*surface_patch_));
00533 file.write(reinterpret_cast<const char*>(&surface_patch_world_size_), sizeof(surface_patch_world_size_));
00534 file.write(reinterpret_cast<const char*>(&surface_patch_rotation_), sizeof(surface_patch_rotation_));
00535 file.write(reinterpret_cast<const char*>(&descriptor_size_), sizeof(descriptor_size_));
00536 file.write(reinterpret_cast<const char*>(descriptor_), descriptor_size_*sizeof(*descriptor_));
00537 }
00538
00540 void
00541 Narf::saveBinary (const std::string& filename) const
00542 {
00543 std::ofstream file;
00544 file.open(filename.c_str());
00545 saveBinary(file);
00546 file.close();
00547 }
00548
00550 int
00551 Narf::loadHeader(std::istream& file) const
00552 {
00553 size_t pos_in_file = static_cast<size_t> (file.tellg ());
00554 file.width (getHeaderKeyword ().size()+10);
00555 std::string header;
00556 file >> header;
00557 file.width(0);
00558 if (header != getHeaderKeyword())
00559 {
00560 file.seekg(pos_in_file);
00561 return -1;
00562 }
00563 int version;
00564 file >> version;
00565 file.ignore (1);
00566
00567 return (version);
00568 }
00569
00571 void
00572 Narf::loadBinary (std::istream& file)
00573 {
00574 reset();
00575 int version = loadHeader(file);
00576 if (version<0)
00577 {
00578 std::cerr << __PRETTY_FUNCTION__ << "Incorrect header!\n";
00579 return;
00580 }
00581 pcl::loadBinary(position_.matrix(), file);
00582 pcl::loadBinary(transformation_.matrix(), file);
00583 file.read(reinterpret_cast<char*>(&surface_patch_pixel_size_), sizeof(surface_patch_pixel_size_));
00584 surface_patch_ = new float[surface_patch_pixel_size_*surface_patch_pixel_size_];
00585 file.read(reinterpret_cast<char*>(surface_patch_),
00586 surface_patch_pixel_size_*surface_patch_pixel_size_*sizeof(*surface_patch_));
00587 file.read(reinterpret_cast<char*>(&surface_patch_world_size_), sizeof(surface_patch_world_size_));
00588 file.read(reinterpret_cast<char*>(&surface_patch_rotation_), sizeof(surface_patch_rotation_));
00589 file.read(reinterpret_cast<char*>(&descriptor_size_), sizeof(descriptor_size_));
00590 descriptor_ = new float[descriptor_size_];
00591 if (file.eof())
00592 cout << ":-(\n";
00593 file.read (reinterpret_cast<char*>(descriptor_), descriptor_size_*sizeof(*descriptor_));
00594 }
00595
00597 void
00598 Narf::loadBinary (const std::string& filename)
00599 {
00600 std::ifstream file;
00601 file.open (filename.c_str ());
00602 loadBinary (file);
00603 file.close ();
00604 }
00605
00609 NarfDescriptor::NarfDescriptor (const RangeImage* range_image, const std::vector<int>* indices) :
00610 BaseClass (), range_image_ (), parameters_ ()
00611 {
00612 setRangeImage (range_image, indices);
00613 }
00614
00616 NarfDescriptor::~NarfDescriptor ()
00617 {
00618 }
00619
00621 void
00622 NarfDescriptor::setRangeImage (const RangeImage* range_image, const std::vector<int>* indices)
00623 {
00624 range_image_ = range_image;
00625 if (indices != NULL)
00626 {
00627 IndicesPtr indicesptr (new std::vector<int> (*indices));
00628 setIndices (indicesptr);
00629 }
00630 }
00631
00633 void
00634 NarfDescriptor::computeFeature(NarfDescriptor::PointCloudOut& output)
00635 {
00636
00637
00638 output.points.clear();
00639
00640 if (range_image_==NULL)
00641 {
00642 std::cerr << __PRETTY_FUNCTION__
00643 << ": RangeImage is not set. Sorry, the NARF descriptor calculation works on range images, not on normal point clouds."
00644 << " Use setRangeImage(...).\n\n";
00645 output.width = output.height = 0;
00646 output.points.clear ();
00647 return;
00648 }
00649 if (parameters_.support_size <= 0.0f)
00650 {
00651 std::cerr << __PRETTY_FUNCTION__
00652 << ": support size is not set. Use getParameters().support_size = ...\n\n";
00653 output.width = output.height = 0;
00654 output.points.clear ();
00655 return;
00656 }
00657 std::vector<Narf*> feature_list;
00658 if (indices_)
00659 {
00660 for (size_t indices_idx=0; indices_idx<indices_->size(); ++indices_idx)
00661 {
00662 int point_index = (*indices_)[indices_idx];
00663 int y=point_index/range_image_->width, x=point_index - y*range_image_->width;
00664 Narf::extractFromRangeImageAndAddToList(*range_image_, static_cast<float> (x), static_cast<float> (y), 36, parameters_.support_size,
00665 parameters_.rotation_invariant, feature_list);
00666 }
00667 }
00668 else
00669 {
00670 for (unsigned int y=0; y<range_image_->height; ++y)
00671 {
00672 for (unsigned int x=0; x<range_image_->width; ++x)
00673 {
00674 Narf::extractFromRangeImageAndAddToList(*range_image_, static_cast<float> (x), static_cast<float> (y), 36, parameters_.support_size,
00675 parameters_.rotation_invariant, feature_list);
00676 }
00677 }
00678 }
00679
00680
00681 output.points.resize(feature_list.size());
00682 for (unsigned int i=0; i<feature_list.size(); ++i)
00683 {
00684 feature_list[i]->copyToNarf36(output.points[i]);
00685 }
00686
00687
00688 for (size_t i=0; i<feature_list.size(); ++i)
00689 delete feature_list[i];
00690 }
00691
00693 void
00694 NarfDescriptor::compute(NarfDescriptor::PointCloudOut& output)
00695 {
00696 computeFeature(output);
00697 }
00698 }
00699