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 #include <pcl/filters/impl/crop_box.hpp>
00040
00042 void
00043 pcl::CropBox<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
00044 {
00045
00046 output.data.resize (input_->data.size ());
00047 removed_indices_->resize (input_->data.size ());
00048
00049
00050 output.fields = input_->fields;
00051 output.is_bigendian = input_->is_bigendian;
00052 output.row_step = input_->row_step;
00053 output.point_step = input_->point_step;
00054 output.height = 1;
00055
00056 int indices_count = 0;
00057 int removed_indices_count = 0;
00058
00059 Eigen::Affine3f transform = Eigen::Affine3f::Identity();
00060 Eigen::Affine3f inverse_transform = Eigen::Affine3f::Identity();
00061
00062 if (rotation_ != Eigen::Vector3f::Zero ())
00063 {
00064 pcl::getTransformation (0, 0, 0,
00065 rotation_ (0), rotation_ (1), rotation_ (2),
00066 transform);
00067 inverse_transform = transform.inverse();
00068 }
00069
00070
00071 Eigen::Vector3f local_pt (Eigen::Vector3f::Zero ());
00072
00073 for (size_t index = 0; index < indices_->size (); ++index)
00074 {
00075
00076 int point_offset = ((*indices_)[index] * input_->point_step);
00077 int offset = point_offset + input_->fields[x_idx_].offset;
00078 memcpy (&local_pt, &input_->data[offset], sizeof (float)*3);
00079
00080
00081 if (!pcl_isfinite (local_pt.x ()) ||
00082 !pcl_isfinite (local_pt.y ()) ||
00083 !pcl_isfinite (local_pt.z ()))
00084 continue;
00085
00086
00087 if (!(transform_.matrix().isIdentity()))
00088 local_pt = transform_ * local_pt;
00089
00090 if (translation_ != Eigen::Vector3f::Zero ())
00091 {
00092 local_pt.x () = local_pt.x () - translation_ (0);
00093 local_pt.y () = local_pt.y () - translation_ (1);
00094 local_pt.z () = local_pt.z () - translation_ (2);
00095 }
00096
00097
00098 if (!(inverse_transform.matrix ().isIdentity ()))
00099 local_pt = inverse_transform * local_pt;
00100
00101
00102 if ( (local_pt.x () < min_pt_[0] || local_pt.y () < min_pt_[1] || local_pt.z () < min_pt_[2]) ||
00103 (local_pt.x () > max_pt_[0] || local_pt.y () > max_pt_[1] || local_pt.z () > max_pt_[2]))
00104 {
00105 if (negative_)
00106 {
00107 memcpy (&output.data[indices_count++ * output.point_step],
00108 &input_->data[index * output.point_step], output.point_step);
00109 }
00110 else if (extract_removed_indices_)
00111 {
00112 (*removed_indices_)[removed_indices_count++] = static_cast<int> (index);
00113 }
00114 }
00115
00116 else
00117 {
00118 if (negative_ && extract_removed_indices_)
00119 {
00120 (*removed_indices_)[removed_indices_count++] = static_cast<int> (index);
00121 }
00122 else if (!negative_) {
00123 memcpy (&output.data[indices_count++ * output.point_step],
00124 &input_->data[index * output.point_step], output.point_step);
00125 }
00126 }
00127 }
00128 output.width = indices_count;
00129 output.row_step = output.point_step * output.width;
00130 output.data.resize (output.width * output.height * output.point_step);
00131
00132 removed_indices_->resize (removed_indices_count);
00133 }
00134
00136 void
00137 pcl::CropBox<pcl::PCLPointCloud2>::applyFilter (std::vector<int> &indices)
00138 {
00139 indices.resize (input_->width * input_->height);
00140 removed_indices_->resize (input_->width * input_->height);
00141
00142 int indices_count = 0;
00143 int removed_indices_count = 0;
00144
00145 Eigen::Affine3f transform = Eigen::Affine3f::Identity();
00146 Eigen::Affine3f inverse_transform = Eigen::Affine3f::Identity();
00147
00148 if (rotation_ != Eigen::Vector3f::Zero ())
00149 {
00150 pcl::getTransformation (0, 0, 0,
00151 rotation_ (0), rotation_ (1), rotation_ (2),
00152 transform);
00153 inverse_transform = transform.inverse();
00154 }
00155
00156
00157 Eigen::Vector3f local_pt (Eigen::Vector3f::Zero ());
00158
00159 for (size_t index = 0; index < indices_->size (); index++)
00160 {
00161
00162 int point_offset = ((*indices_)[index] * input_->point_step);
00163 int offset = point_offset + input_->fields[x_idx_].offset;
00164 memcpy (&local_pt, &input_->data[offset], sizeof (float)*3);
00165
00166
00167 if (!(transform_.matrix().isIdentity()))
00168 local_pt = transform_ * local_pt;
00169
00170 if (translation_ != Eigen::Vector3f::Zero ())
00171 {
00172 local_pt.x () -= translation_ (0);
00173 local_pt.y () -= translation_ (1);
00174 local_pt.z () -= translation_ (2);
00175 }
00176
00177
00178 if (!(inverse_transform.matrix().isIdentity()))
00179 local_pt = inverse_transform * local_pt;
00180
00181
00182 if ( (local_pt.x () < min_pt_[0] || local_pt.y () < min_pt_[1] || local_pt.z () < min_pt_[2]) ||
00183 (local_pt.x () > max_pt_[0] || local_pt.y () > max_pt_[1] || local_pt.z () > max_pt_[2]))
00184 {
00185 if (negative_)
00186 {
00187 indices[indices_count++] = (*indices_)[index];
00188 }
00189 else if (extract_removed_indices_)
00190 {
00191 (*removed_indices_)[removed_indices_count++] = static_cast<int> (index);
00192 }
00193 }
00194
00195 else
00196 {
00197 if (negative_ && extract_removed_indices_)
00198 {
00199 (*removed_indices_)[removed_indices_count++] = static_cast<int> (index);
00200 }
00201 else if (!negative_) {
00202 indices[indices_count++] = (*indices_)[index];
00203 }
00204 }
00205 }
00206
00207 indices.resize (indices_count);
00208 removed_indices_->resize (removed_indices_count);
00209 }
00210
00211 #ifndef PCL_NO_PRECOMPILE
00212 #include <pcl/impl/instantiate.hpp>
00213 #include <pcl/point_types.h>
00214
00215 PCL_INSTANTIATE(CropBox, PCL_XYZ_POINT_TYPES)
00216
00217 #endif // PCL_NO_PRECOMPILE
00218