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 #include <pcl/impl/instantiate.hpp>
00039 #include <pcl/point_types.h>
00040 #include <pcl/filters/passthrough.h>
00041 #include <pcl/filters/impl/passthrough.hpp>
00042
00044 void
00045 pcl::PassThrough<sensor_msgs::PointCloud2>::applyFilter (PointCloud2 &output)
00046 {
00047 if (!input_)
00048 {
00049 PCL_ERROR ("[pcl::%s::applyFilter] Input dataset not given!\n", getClassName ().c_str ());
00050 output.width = output.height = 0;
00051 output.data.clear ();
00052 return;
00053 }
00054
00055
00056 if (x_idx_ == -1 || y_idx_ == -1 || z_idx_ == -1)
00057 {
00058 PCL_ERROR ("[pcl::%s::applyFilter] Input dataset doesn't have x-y-z coordinates!\n", getClassName ().c_str ());
00059 output.width = output.height = 0;
00060 output.data.clear ();
00061 return;
00062 }
00063
00064 int nr_points = input_->width * input_->height;
00065
00066
00067 if (keep_organized_)
00068 {
00069 if (filter_field_name_.empty ())
00070 {
00071
00072
00073 output = *input_;
00074 return;
00075 }
00076
00077 output.width = input_->width;
00078 output.height = input_->height;
00079
00080 if (!pcl_isfinite (user_filter_value_))
00081 output.is_dense = false;
00082 else
00083 output.is_dense = input_->is_dense;
00084 }
00085 else
00086 {
00087
00088 output.height = 1;
00089
00090 output.is_dense = true;
00091 }
00092 output.row_step = input_->row_step;
00093 output.point_step = input_->point_step;
00094 output.is_bigendian = input_->is_bigendian;
00095 output.data.resize (input_->data.size ());
00096
00097 removed_indices_->resize (input_->data.size ());
00098
00099 int nr_p = 0;
00100 int nr_removed_p = 0;
00101
00102 Eigen::Array4i xyz_offset (input_->fields[x_idx_].offset, input_->fields[y_idx_].offset,
00103 input_->fields[z_idx_].offset, 0);
00104
00105 Eigen::Vector4f pt = Eigen::Vector4f::Zero ();
00106
00107 if (!filter_field_name_.empty ())
00108 {
00109
00110 int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_);
00111 if (distance_idx == -1)
00112 {
00113 PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx);
00114 output.width = output.height = 0;
00115 output.data.clear ();
00116 return;
00117 }
00118
00119
00120 if (input_->fields[distance_idx].datatype != sensor_msgs::PointField::FLOAT32)
00121 {
00122 PCL_ERROR ("[pcl::%s::downsample] Distance filtering requested, but distances are not float/double in the dataset! Only FLOAT32/FLOAT64 distances are supported right now.\n", getClassName ().c_str ());
00123 output.width = output.height = 0;
00124 output.data.clear ();
00125 return;
00126 }
00127
00128 float badpt = std::numeric_limits<float>::quiet_NaN ();
00129
00130 if (keep_organized_)
00131 {
00132 float distance_value = 0;
00133
00134 for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
00135 {
00136
00137 memcpy (&output.data[cp * output.point_step], &input_->data[cp * output.point_step], output.point_step);
00138
00139
00140 memcpy (&distance_value, &input_->data[cp * input_->point_step + input_->fields[distance_idx].offset],
00141 sizeof(float));
00142
00143 if (filter_limit_negative_)
00144 {
00145
00146 if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_))
00147 {
00148
00149 memcpy (&output.data[xyz_offset[0]], &badpt, sizeof(float));
00150 memcpy (&output.data[xyz_offset[1]], &badpt, sizeof(float));
00151 memcpy (&output.data[xyz_offset[2]], &badpt, sizeof(float));
00152 continue;
00153 }
00154 else
00155 {
00156 if (extract_removed_indices_)
00157 {
00158 (*removed_indices_)[nr_removed_p] = cp;
00159 nr_removed_p++;
00160 }
00161 }
00162 }
00163 else
00164 {
00165
00166 if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_))
00167 {
00168
00169 memcpy (&output.data[xyz_offset[0]], &badpt, sizeof(float));
00170 memcpy (&output.data[xyz_offset[1]], &badpt, sizeof(float));
00171 memcpy (&output.data[xyz_offset[2]], &badpt, sizeof(float));
00172 continue;
00173 }
00174 else
00175 {
00176 if (extract_removed_indices_)
00177 {
00178 (*removed_indices_)[nr_removed_p] = cp;
00179 nr_removed_p++;
00180 }
00181 }
00182 }
00183 }
00184 }
00185
00186 else
00187 {
00188
00189 float distance_value = 0;
00190 for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
00191 {
00192
00193 memcpy (&distance_value, &input_->data[cp * input_->point_step + input_->fields[distance_idx].offset],
00194 sizeof(float));
00195
00196 if (filter_limit_negative_)
00197 {
00198
00199 if (distance_value < filter_limit_max_ && distance_value > filter_limit_min_)
00200 {
00201 if (extract_removed_indices_)
00202 {
00203 (*removed_indices_)[nr_removed_p] = cp;
00204 nr_removed_p++;
00205 }
00206 continue;
00207 }
00208 }
00209 else
00210 {
00211
00212 if (distance_value > filter_limit_max_ || distance_value < filter_limit_min_)
00213 {
00214 if (extract_removed_indices_)
00215 {
00216 (*removed_indices_)[nr_removed_p] = cp;
00217 nr_removed_p++;
00218 }
00219 continue;
00220 }
00221 }
00222
00223
00224 memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float));
00225 memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof(float));
00226 memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof(float));
00227
00228
00229 if (!pcl_isfinite (pt[0]) || !pcl_isfinite (pt[1]) || !pcl_isfinite (pt[2]))
00230 {
00231 if (extract_removed_indices_)
00232 {
00233 (*removed_indices_)[nr_removed_p] = cp;
00234 nr_removed_p++;
00235 }
00236 continue;
00237 }
00238
00239
00240 memcpy (&output.data[nr_p * output.point_step], &input_->data[cp * output.point_step], output.point_step);
00241 nr_p++;
00242 }
00243 output.width = nr_p;
00244 }
00245 }
00246
00247 else
00248 {
00249 for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
00250 {
00251
00252 memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float));
00253 memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof(float));
00254 memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof(float));
00255
00256
00257 if (!pcl_isfinite (pt[0]) || !pcl_isfinite (pt[1]) || !pcl_isfinite (pt[2]))
00258 {
00259 if (extract_removed_indices_)
00260 {
00261 (*removed_indices_)[nr_removed_p] = cp;
00262 nr_removed_p++;
00263 }
00264 continue;
00265 }
00266
00267
00268 memcpy (&output.data[nr_p * output.point_step], &input_->data[cp * output.point_step], output.point_step);
00269 nr_p++;
00270 }
00271 output.width = nr_p;
00272 }
00273
00274 output.row_step = output.point_step * output.width;
00275 output.data.resize (output.width * output.height * output.point_step);
00276
00277 removed_indices_->resize (nr_removed_p);
00278 }
00279
00280 PCL_INSTANTIATE(PassThrough, PCL_XYZ_POINT_TYPES)
00281