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
00040 #include <iostream>
00041 using std::cout;
00042 using std::cerr;
00043
00044 #include "pcl/features/narf_descriptor.h"
00045 #include "pcl/features/narf.h"
00046 #include <pcl/range_image/range_image.h>
00047
00048 namespace pcl {
00049
00050 NarfDescriptor::NarfDescriptor(const RangeImage* range_image, const std::vector<int>* indices) : BaseClass()
00051 {
00052 setRangeImage(range_image, indices);
00053 }
00054
00055 NarfDescriptor::~NarfDescriptor()
00056 {
00057 }
00058
00059 void NarfDescriptor::setRangeImage(const RangeImage* range_image, const std::vector<int>* indices)
00060 {
00061 range_image_ = range_image;
00062 if (indices != NULL)
00063 setIndices(boost::make_shared<std::vector<int> >(*indices));
00064 }
00065
00066 void NarfDescriptor::computeFeature(NarfDescriptor::PointCloudOut& output)
00067 {
00068
00069
00070 output.points.clear();
00071
00072 if (range_image_==NULL)
00073 {
00074 std::cerr << __PRETTY_FUNCTION__
00075 << ": RangeImage is not set. Sorry, the NARF descriptor calculation works on range images, not on normal point clouds."
00076 << " Use setRangeImage(...).\n\n";
00077 output.width = output.height = 0;
00078 output.points.clear ();
00079 return;
00080 }
00081 if (parameters_.support_size <= 0.0f)
00082 {
00083 std::cerr << __PRETTY_FUNCTION__
00084 << ": support size is not set. Use getParameters().support_size = ...\n\n";
00085 output.width = output.height = 0;
00086 output.points.clear ();
00087 return;
00088 }
00089 std::vector<Narf*> feature_list;
00090 if (indices_)
00091 {
00092 for (size_t indices_idx=0; indices_idx<indices_->size(); ++indices_idx)
00093 {
00094 int point_index = (*indices_)[indices_idx];
00095 int y=point_index/range_image_->width, x=point_index - y*range_image_->width;
00096 Narf::extractFromRangeImageAndAddToList(*range_image_, x, y, 36, parameters_.support_size,
00097 parameters_.rotation_invariant, feature_list);
00098 }
00099 }
00100 else
00101 {
00102 for (unsigned int y=0; y<range_image_->height; ++y)
00103 {
00104 for (unsigned int x=0; x<range_image_->width; ++x)
00105 {
00106 Narf::extractFromRangeImageAndAddToList(*range_image_, x, y, 36, parameters_.support_size,
00107 parameters_.rotation_invariant, feature_list);
00108 }
00109 }
00110 }
00111
00112
00113 output.points.resize(feature_list.size());
00114 for (unsigned int i=0; i<feature_list.size(); ++i)
00115 {
00116 feature_list[i]->copyToNarf36(output.points[i]);
00117 }
00118
00119
00120 for (size_t i=0; i<feature_list.size(); ++i)
00121 delete feature_list[i];
00122 }
00123
00124 void NarfDescriptor::compute(NarfDescriptor::PointCloudOut& output)
00125 {
00126 computeFeature(output);
00127 }
00128
00129 }