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
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082 #ifndef SHAPE_RECONSTRUCTION_PCL_FILTERS_IMPL_PASSTHROUGH_HPP_
00083 #define SHAPE_RECONSTRUCTION_PCL_FILTERS_IMPL_PASSTHROUGH_HPP_
00084
00085 #include <shape_reconstruction/Passthrough.h>
00086 #include <pcl/common/io.h>
00087 #include <vector>
00088 #include <iterator>
00089
00090 using namespace pcl;
00091
00092 namespace shape_reconstruction{
00093
00095 template <typename PointT> void
00096 shape_reconstruction::PassThrough<PointT>::applyFilter (PointCloud &output)
00097 {
00098 std::vector<int> indices;
00099 if (keep_organized_)
00100 {
00101 bool temp = extract_removed_indices_;
00102 extract_removed_indices_ = true;
00103 applyFilterIndices (indices);
00104 extract_removed_indices_ = temp;
00105
00106 output = *input_;
00107 for (int rii = 0; rii < static_cast<int> (removed_indices_->size ()); ++rii)
00108 output.points[(*removed_indices_)[rii]].x = output.points[(*removed_indices_)[rii]].y = output.points[(*removed_indices_)[rii]].z = user_filter_value_;
00109 if (!pcl_isfinite (user_filter_value_))
00110 output.is_dense = false;
00111 }
00112 else
00113 {
00114 output.is_dense = true;
00115 applyFilterIndices (indices);
00116 copyPointCloud (*input_, indices, output);
00117 }
00118 }
00119
00121 template <typename PointT> void
00122 shape_reconstruction::PassThrough<PointT>::applyFilterIndices (std::vector<int> &indices)
00123 {
00124
00125 indices.resize (indices_->size ());
00126 removed_indices_->resize (indices_->size ());
00127 int oii = 0, rii = 0;
00128
00129
00130 if (filter_field_name_.empty ())
00131 {
00132
00133 for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)
00134 {
00135
00136 if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) ||
00137 !pcl_isfinite (input_->points[(*indices_)[iii]].y) ||
00138 !pcl_isfinite (input_->points[(*indices_)[iii]].z))
00139 {
00140 if (extract_removed_indices_)
00141 (*removed_indices_)[rii++] = (*indices_)[iii];
00142 continue;
00143 }
00144 indices[oii++] = (*indices_)[iii];
00145 }
00146 }
00147 else
00148 {
00149
00150 std::vector<pcl::PCLPointField> fields;
00151 int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
00152 if (distance_idx == -1)
00153 {
00154 PCL_WARN ("[pcl::%s::applyFilter] Unable to find field name in point type.\n", getClassName ().c_str ());
00155 indices.clear ();
00156 removed_indices_->clear ();
00157 return;
00158 }
00159
00160 if(labels_.size()==0)
00161 {
00162
00163
00164
00165 for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)
00166 {
00167
00168 if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) ||
00169 !pcl_isfinite (input_->points[(*indices_)[iii]].y) ||
00170 !pcl_isfinite (input_->points[(*indices_)[iii]].z))
00171 {
00172 if (extract_removed_indices_)
00173 (*removed_indices_)[rii++] = (*indices_)[iii];
00174 continue;
00175 }
00176
00177
00178 const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&input_->points[(*indices_)[iii]]);
00179 float field_value = 0;
00180 memcpy (&field_value, pt_data + fields[distance_idx].offset, sizeof (float));
00181
00182
00183 if (!pcl_isfinite (field_value))
00184 {
00185 if (extract_removed_indices_)
00186 (*removed_indices_)[rii++] = (*indices_)[iii];
00187 continue;
00188 }
00189
00190
00191 if (!negative_ && (field_value < filter_limit_min_ || field_value > filter_limit_max_))
00192 {
00193 if (extract_removed_indices_)
00194 (*removed_indices_)[rii++] = (*indices_)[iii];
00195 continue;
00196 }
00197
00198
00199 if (negative_ && field_value >= filter_limit_min_ && field_value <= filter_limit_max_)
00200 {
00201 if (extract_removed_indices_)
00202 (*removed_indices_)[rii++] = (*indices_)[iii];
00203 continue;
00204 }
00205
00206
00207 indices[oii++] = (*indices_)[iii];
00208 }
00209
00210 }else{
00211
00212
00213 for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)
00214 {
00215
00216 if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) ||
00217 !pcl_isfinite (input_->points[(*indices_)[iii]].y) ||
00218 !pcl_isfinite (input_->points[(*indices_)[iii]].z))
00219 {
00220 if (extract_removed_indices_)
00221 (*removed_indices_)[rii++] = (*indices_)[iii];
00222 continue;
00223 }
00224
00225
00226 const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&input_->points[(*indices_)[iii]]);
00227 uint32_t field_value = 0;
00228 memcpy (&field_value, pt_data + fields[distance_idx].offset, sizeof (uint32_t));
00229
00230
00231 if (!pcl_isfinite (field_value))
00232 {
00233 if (extract_removed_indices_)
00234 (*removed_indices_)[rii++] = (*indices_)[iii];
00235 continue;
00236 }
00237
00238 std::vector<unsigned int>::iterator find_result = std::find(std::begin(labels_), std::end(labels_), (unsigned int)field_value);
00239
00240
00241 if (!negative_ && find_result == labels_.end())
00242 {
00243 if (extract_removed_indices_)
00244 (*removed_indices_)[rii++] = (*indices_)[iii];
00245 continue;
00246 }
00247
00248
00249 if (negative_ && find_result != labels_.end())
00250 {
00251 if (extract_removed_indices_)
00252 (*removed_indices_)[rii++] = (*indices_)[iii];
00253 continue;
00254 }
00255
00256
00257 indices[oii++] = (*indices_)[iii];
00258 }
00259 }
00260 }
00261
00262
00263 indices.resize (oii);
00264 removed_indices_->resize (rii);
00265 }
00266 }
00267
00268 #endif // PCL_FILTERS_IMPL_PASSTHROUGH_HPP_