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 #ifndef PCL_FILTERS_IMPL_PASSTHROUGH_HPP_
00041 #define PCL_FILTERS_IMPL_PASSTHROUGH_HPP_
00042
00043 #include <pcl/filters/passthrough.h>
00044 #include <pcl/common/io.h>
00045
00047 template <typename PointT> void
00048 pcl::PassThrough<PointT>::applyFilter (PointCloud &output)
00049 {
00050 std::vector<int> indices;
00051 if (keep_organized_)
00052 {
00053 bool temp = extract_removed_indices_;
00054 extract_removed_indices_ = true;
00055 applyFilterIndices (indices);
00056 extract_removed_indices_ = temp;
00057
00058 output = *input_;
00059 for (int rii = 0; rii < static_cast<int> (removed_indices_->size ()); ++rii)
00060 output.points[(*removed_indices_)[rii]].x = output.points[(*removed_indices_)[rii]].y = output.points[(*removed_indices_)[rii]].z = user_filter_value_;
00061 if (!pcl_isfinite (user_filter_value_))
00062 output.is_dense = false;
00063 }
00064 else
00065 {
00066 applyFilterIndices (indices);
00067 copyPointCloud (*input_, indices, output);
00068 }
00069 }
00070
00072 template <typename PointT> void
00073 pcl::PassThrough<PointT>::applyFilterIndices (std::vector<int> &indices)
00074 {
00075
00076 indices.resize (indices_->size ());
00077 removed_indices_->resize (indices_->size ());
00078 int oii = 0, rii = 0;
00079
00080
00081 if (filter_field_name_.empty ())
00082 {
00083
00084 for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)
00085 {
00086
00087 if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) ||
00088 !pcl_isfinite (input_->points[(*indices_)[iii]].y) ||
00089 !pcl_isfinite (input_->points[(*indices_)[iii]].z))
00090 {
00091 if (extract_removed_indices_)
00092 (*removed_indices_)[rii++] = (*indices_)[iii];
00093 continue;
00094 }
00095 indices[oii++] = (*indices_)[iii];
00096 }
00097 }
00098 else
00099 {
00100
00101 std::vector<sensor_msgs::PointField> fields;
00102 int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
00103 if (distance_idx == -1)
00104 {
00105 PCL_WARN ("[pcl::%s::applyFilter] Unable to find field name in point type.\n", getClassName ().c_str ());
00106 indices.clear ();
00107 removed_indices_->clear ();
00108 return;
00109 }
00110
00111
00112 for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)
00113 {
00114
00115 if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) ||
00116 !pcl_isfinite (input_->points[(*indices_)[iii]].y) ||
00117 !pcl_isfinite (input_->points[(*indices_)[iii]].z))
00118 {
00119 if (extract_removed_indices_)
00120 (*removed_indices_)[rii++] = (*indices_)[iii];
00121 continue;
00122 }
00123
00124
00125 const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&input_->points[(*indices_)[iii]]);
00126 float field_value = 0;
00127 memcpy (&field_value, pt_data + fields[distance_idx].offset, sizeof (float));
00128
00129
00130 if (!negative_ && (field_value < filter_limit_min_ || field_value > filter_limit_max_))
00131 {
00132 if (extract_removed_indices_)
00133 (*removed_indices_)[rii++] = (*indices_)[iii];
00134 continue;
00135 }
00136
00137
00138 if (negative_ && field_value > filter_limit_min_ && field_value < filter_limit_max_)
00139 {
00140 if (extract_removed_indices_)
00141 (*removed_indices_)[rii++] = (*indices_)[iii];
00142 continue;
00143 }
00144
00145
00146 indices[oii++] = (*indices_)[iii];
00147 }
00148 }
00149
00150
00151 indices.resize (oii);
00152 removed_indices_->resize (rii);
00153 }
00154
00155 #define PCL_INSTANTIATE_PassThrough(T) template class PCL_EXPORTS pcl::PassThrough<T>;
00156
00157 #endif // PCL_FILTERS_IMPL_PASSTHROUGH_HPP_
00158