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 #ifndef PCL_FILTERS_IMPL_PASSTHROUGH_H_
00039 #define PCL_FILTERS_IMPL_PASSTHROUGH_H_
00040
00041 #include "pcl/filters/passthrough.h"
00042 #include "pcl/io/io.h"
00043
00045 template <typename PointT> void
00046 pcl::PassThrough<PointT>::applyFilter (PointCloud &output)
00047 {
00048
00049 if (!input_)
00050 {
00051 ROS_WARN ("[pcl::%s::applyFilter] No input dataset given!", getClassName ().c_str ());
00052 output.width = output.height = 0;
00053 output.points.clear ();
00054 return;
00055 }
00056
00057
00058 if (keep_organized_)
00059 {
00060 if (filter_field_name_.empty ())
00061 {
00062
00063
00064 output = *input_;
00065 return;
00066 }
00067
00068 output.width = input_->width;
00069 output.height = input_->height;
00070
00071 if (!pcl_isfinite (user_filter_value_))
00072 output.is_dense = false;
00073 else
00074 output.is_dense = input_->is_dense;
00075 }
00076 else
00077 {
00078 output.height = 1;
00079
00080 output.is_dense = true;
00081 }
00082 output.points.resize (input_->points.size ());
00083
00084 int nr_p = 0;
00085
00086 if (!filter_field_name_.empty ())
00087 {
00088
00089 std::vector<sensor_msgs::PointField> fields;
00090 int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
00091 if (distance_idx == -1)
00092 {
00093 ROS_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.", getClassName ().c_str (), distance_idx);
00094 output.width = output.height = 0;
00095 output.points.clear ();
00096 return;
00097 }
00098
00099 if (keep_organized_)
00100 {
00101 for (size_t cp = 0; cp < input_->points.size (); ++cp)
00102 {
00103
00104 pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointT, PointT> (input_->points[cp], output.points[cp]));
00105
00106
00107 uint8_t* pt_data = (uint8_t*)&input_->points[cp];
00108 float distance_value = 0;
00109 memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float));
00110
00111 if (filter_limit_negative_)
00112 {
00113
00114 if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_))
00115 {
00116 output.points[cp].x = output.points[cp].y = output.points[cp].z = user_filter_value_;
00117 continue;
00118 }
00119 }
00120 else
00121 {
00122
00123 if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_))
00124 {
00125 output.points[cp].x = output.points[cp].y = output.points[cp].z = user_filter_value_;
00126 continue;
00127 }
00128 }
00129 }
00130 nr_p = input_->points.size ();
00131 }
00132
00133 else
00134 {
00135
00136 for (size_t cp = 0; cp < input_->points.size (); ++cp)
00137 {
00138
00139 if (!pcl_isfinite (input_->points[cp].x) || !pcl_isfinite (input_->points[cp].y) || !pcl_isfinite (input_->points[cp].z))
00140 continue;
00141
00142
00143 uint8_t* pt_data = (uint8_t*)&input_->points[cp];
00144 float distance_value = 0;
00145 memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float));
00146
00147 if (filter_limit_negative_)
00148 {
00149
00150 if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_))
00151 continue;
00152 }
00153 else
00154 {
00155
00156 if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_))
00157 continue;
00158 }
00159
00160 pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointT, PointT> (input_->points[cp], output.points[nr_p]));
00161 nr_p++;
00162 }
00163 output.width = nr_p;
00164 }
00165 }
00166
00167 else
00168 {
00169
00170 for (size_t cp = 0; cp < input_->points.size (); ++cp)
00171 {
00172
00173 if (!pcl_isfinite (input_->points[cp].x) || !pcl_isfinite (input_->points[cp].y) || !pcl_isfinite (input_->points[cp].z))
00174 continue;
00175
00176 pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointT, PointT> (input_->points[cp], output.points[nr_p]));
00177 nr_p++;
00178 }
00179 output.width = nr_p;
00180 }
00181
00182 output.points.resize (output.width * output.height);
00183 }
00184
00185 #define PCL_INSTANTIATE_PassThrough(T) template class pcl::PassThrough<T>;
00186
00187 #endif // PCL_FILTERS_IMPL_PASSTHROUGH_H_
00188