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 ROS_ERROR ("[pcl::%s::applyFilter] Input dataset not given!", 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 ROS_ERROR ("[pcl::%s::applyFilter] Input dataset doesn't have x-y-z coordinates!", 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 int nr_p = 0;
00098
00099 Eigen::Array4i xyz_offset (input_->fields[x_idx_].offset,
00100 input_->fields[y_idx_].offset,
00101 input_->fields[z_idx_].offset,
00102 0);
00103
00104 Eigen::Vector4f pt = Eigen::Vector4f::Zero ();
00105
00106 if (!filter_field_name_.empty ())
00107 {
00108
00109 int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_);
00110 if (distance_idx == -1)
00111 {
00112 ROS_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.", getClassName ().c_str (), distance_idx);
00113 output.width = output.height = 0;
00114 output.data.clear ();
00115 return;
00116 }
00117
00118
00119 if (input_->fields[distance_idx].datatype != sensor_msgs::PointField::FLOAT32)
00120 {
00121 ROS_ERROR ("[pcl::%s::downsample] Distance filtering requested, but distances are not float/double in the dataset! Only FLOAT32/FLOAT64 distances are supported right now.", getClassName ().c_str ());
00122 output.width = output.height = 0;
00123 output.data.clear ();
00124 return;
00125 }
00126
00127 float badpt = std::numeric_limits<float>::quiet_NaN ();
00128
00129 if (keep_organized_)
00130 {
00131 float distance_value = 0;
00132
00133 for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
00134 {
00135
00136 memcpy (&output.data[cp * output.point_step], &input_->data[cp * output.point_step], output.point_step);
00137
00138
00139 memcpy (&distance_value, &input_->data[cp * input_->point_step + input_->fields[distance_idx].offset], sizeof (float));
00140
00141 if (filter_limit_negative_)
00142 {
00143
00144 if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_))
00145 {
00146
00147 memcpy (&output.data[xyz_offset[0]], &badpt, sizeof (float));
00148 memcpy (&output.data[xyz_offset[1]], &badpt, sizeof (float));
00149 memcpy (&output.data[xyz_offset[2]], &badpt, sizeof (float));
00150 continue;
00151 }
00152 }
00153 else
00154 {
00155
00156 if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_))
00157 {
00158
00159 memcpy (&output.data[xyz_offset[0]], &badpt, sizeof (float));
00160 memcpy (&output.data[xyz_offset[1]], &badpt, sizeof (float));
00161 memcpy (&output.data[xyz_offset[2]], &badpt, sizeof (float));
00162 continue;
00163 }
00164 }
00165 }
00166 }
00167
00168 else
00169 {
00170
00171 float distance_value = 0;
00172 for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
00173 {
00174
00175 memcpy (&distance_value, &input_->data[cp * input_->point_step + input_->fields[distance_idx].offset], sizeof (float));
00176
00177 if (filter_limit_negative_)
00178 {
00179
00180 if (distance_value < filter_limit_max_ && distance_value > filter_limit_min_)
00181 continue;
00182 }
00183 else
00184 {
00185
00186 if (distance_value > filter_limit_max_ || distance_value < filter_limit_min_)
00187 continue;
00188 }
00189
00190
00191
00192 memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof (float));
00193 memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof (float));
00194 memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof (float));
00195
00196
00197 if (!pcl_isfinite (pt[0]) || !pcl_isfinite (pt[1]) || !pcl_isfinite (pt[2]))
00198 continue;
00199
00200
00201 memcpy (&output.data[nr_p * output.point_step], &input_->data[cp * output.point_step], output.point_step);
00202 nr_p++;
00203 }
00204 output.width = nr_p;
00205 }
00206 }
00207
00208 else
00209 {
00210 for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
00211 {
00212
00213 memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof (float));
00214 memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof (float));
00215 memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof (float));
00216
00217
00218 if (!pcl_isfinite (pt[0]) || !pcl_isfinite (pt[1]) || !pcl_isfinite (pt[2]))
00219 continue;
00220
00221
00222 memcpy (&output.data[nr_p * output.point_step], &input_->data[cp * output.point_step], output.point_step);
00223 nr_p++;
00224 }
00225 output.width = nr_p;
00226 }
00227
00228 output.row_step = output.point_step * output.width;
00229 output.data.resize (output.width * output.point_step);
00230 }
00231
00232
00233 PCL_INSTANTIATE(PassThrough, PCL_XYZ_POINT_TYPES);
00234