Go to the documentation of this file.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 #include <ias_descriptors_3d/shared/spectral_analysis.h>
00036
00037 using namespace std;
00038
00039
00040
00041
00042 SpectralAnalysis::SpectralAnalysis(double support_radius)
00043 {
00044 support_radius_ = support_radius;
00045 spectral_computed_ = false;
00046 }
00047
00048
00049
00050
00051 SpectralAnalysis::~SpectralAnalysis()
00052 {
00053 clearSpectral();
00054 }
00055
00056
00057
00058
00059 void SpectralAnalysis::clearSpectral()
00060 {
00061 unsigned int nbr_data = normals_.size();
00062 for (unsigned int i = 0 ; i < nbr_data ; i++)
00063 {
00064 if (normals_[i] != NULL)
00065 {
00066 delete normals_[i];
00067 delete middle_eig_vecs_[i];
00068 delete tangents_[i];
00069 delete eigenvalues_[i];
00070 }
00071 }
00072 normals_.clear();
00073 middle_eig_vecs_.clear();
00074 tangents_.clear();
00075 eigenvalues_.clear();
00076 spectral_computed_ = false;
00077 }
00078
00079
00080
00081
00082 int SpectralAnalysis::analyzeInterestPoints(const sensor_msgs::PointCloud& data,
00083 cloud_kdtree::KdTree& data_kdtree,
00084 const std::vector<const geometry_msgs::Point32*>& interest_pts)
00085 {
00086 if (spectral_computed_)
00087 {
00088 ROS_ERROR("SpectralAnalysis::analyzeInterestPoints() spectral info already exists");
00089 return -1;
00090 }
00091
00092
00093
00094 unsigned int nbr_interest_pts = interest_pts.size();
00095
00096
00097
00098 if (support_radius_ < 1e-6)
00099 {
00100 ROS_ERROR("SpectralAnalysis::analyzeInterestPoints() support radius must be set to a positive value");
00101 return -1;
00102 }
00103
00104
00105
00106 normals_.assign(nbr_interest_pts, NULL);
00107 middle_eig_vecs_.assign(nbr_interest_pts, NULL);
00108 tangents_.assign(nbr_interest_pts, NULL);
00109 eigenvalues_.assign(nbr_interest_pts, NULL);
00110
00111
00112
00113 int int_nbr_interest_pts = static_cast<int> (nbr_interest_pts);
00114 #pragma omp parallel for schedule(dynamic)
00115 for (int i = 0 ; i < int_nbr_interest_pts ; i++)
00116 {
00117
00118
00119 const geometry_msgs::Point32* curr_interest_pt = interest_pts[static_cast<size_t> (i)];
00120 if (curr_interest_pt == NULL)
00121 {
00122 ROS_WARN("SpectralAnalysis::analyzeInterestPoints() passed NULL interest point");
00123 }
00124 else
00125 {
00126
00127
00128 vector<int> neighbor_indices;
00129 vector<float> neighbor_distances;
00130
00131 data_kdtree.radiusSearch(*curr_interest_pt, support_radius_, neighbor_indices, neighbor_distances);
00132
00133
00134
00135 computeSpectralInfo(data, neighbor_indices, static_cast<size_t> (i));
00136 }
00137 }
00138
00139 spectral_computed_ = true;
00140 return 0;
00141 }
00142
00143
00144
00145
00146 int SpectralAnalysis::analyzeInterestRegions(const sensor_msgs::PointCloud& data,
00147 cloud_kdtree::KdTree& data_kdtree,
00148 const std::vector<const vector<int>*>& interest_region_indices)
00149 {
00150 if (spectral_computed_)
00151 {
00152 ROS_ERROR("SpectralAnalysis::analyzeInterestRegions() spectral info already exists");
00153 return -1;
00154 }
00155
00156
00157
00158 unsigned int nbr_regions = interest_region_indices.size();
00159
00160
00161
00162 normals_.assign(nbr_regions, NULL);
00163 middle_eig_vecs_.assign(nbr_regions, NULL);
00164 tangents_.assign(nbr_regions, NULL);
00165 eigenvalues_.assign(nbr_regions, NULL);
00166
00167
00168
00169
00170
00171 int int_nbr_regions = static_cast<int> (nbr_regions);
00172 #pragma omp parallel for schedule(dynamic)
00173 for (int i = 0 ; i < int_nbr_regions ; i++)
00174 {
00175
00176
00177
00178 const vector<int>* curr_interest_region = interest_region_indices[static_cast<size_t> (i)];
00179 if (curr_interest_region == NULL)
00180 {
00181 ROS_WARN("SpectralAnalysis::analyzeInterestRegions() passed NULL interest region");
00182 }
00183 else
00184 {
00185
00186 vector<int> neighbor_indices;
00187 if (support_radius_ > 1e-6)
00188 {
00189
00190 geometry_msgs::Point32 region_centroid;
00191 cloud_geometry::nearest::computeCentroid(data, *curr_interest_region, region_centroid);
00192
00193 vector<float> neighbor_distances;
00194
00195 data_kdtree.radiusSearch(region_centroid, support_radius_, neighbor_indices, neighbor_distances);
00196
00197
00198 curr_interest_region = &neighbor_indices;
00199 }
00200
00201
00202
00203 computeSpectralInfo(data, *curr_interest_region, static_cast<size_t> (i));
00204 }
00205 }
00206
00207
00208 spectral_computed_ = true;
00209 return 0;
00210 }
00211
00212
00213
00214
00215 void SpectralAnalysis::computeSpectralInfo(const sensor_msgs::PointCloud& data,
00216 const vector<int>& support_volume_indices,
00217 const size_t idx)
00218 {
00219
00220
00221 if (support_volume_indices.size() < 3)
00222 {
00223 ROS_DEBUG("SpectralAnalysis::computeSpectralInfo() not enough neighbors for interest sample %u", idx);
00224 return;
00225 }
00226
00227
00228
00229 Eigen3::Vector3d* new_normal = new Eigen3::Vector3d();
00230 Eigen3::Vector3d* new_middle_eigvec = new Eigen3::Vector3d();
00231 Eigen3::Vector3d* new_tangent = new Eigen3::Vector3d();
00232 Eigen3::Vector3d* new_eig_vals = new Eigen3::Vector3d();
00233
00234
00235
00236
00237 geometry_msgs::Point32 centroid;
00238 Eigen3::Matrix3d eigen_vectors;
00239 cloud_geometry::nearest::computePatchEigenNormalized(data, support_volume_indices, eigen_vectors,
00240 *(new_eig_vals), centroid);
00241
00242
00243
00244 for (unsigned int j = 0 ; j < 3 ; j++)
00245 {
00246 (*(new_normal))[j] = eigen_vectors(j, 0);
00247 (*(new_middle_eigvec))[j] = eigen_vectors(j, 1);
00248 (*(new_tangent))[j] = eigen_vectors(j, 2);
00249 }
00250
00251
00252 new_normal->normalize();
00253 new_middle_eigvec->normalize();
00254 new_tangent->normalize();
00255
00256 normals_[idx] = new_normal;
00257 middle_eig_vecs_[idx] = new_middle_eigvec;
00258 tangents_[idx] = new_tangent;
00259 eigenvalues_[idx] = new_eig_vals;
00260
00261 }
00262