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 #include <pcl/impl/instantiate.hpp>
00039 #include <pcl/point_types.h>
00040 #include <pcl/filters/crop_box.h>
00041 #include <pcl/filters/impl/crop_box.hpp>
00042
00043
00045 void
00046 pcl::CropBox<sensor_msgs::PointCloud2>::applyFilter (PointCloud2 &output)
00047 {
00048
00049 output.data.resize (input_->data.size ());
00050
00051
00052 output.fields = input_->fields;
00053 output.is_bigendian = input_->is_bigendian;
00054 output.row_step = input_->row_step;
00055 output.point_step = input_->point_step;
00056 output.height = 1;
00057
00058 int indice_count = 0;
00059
00060 Eigen::Affine3f transform = Eigen::Affine3f::Identity();
00061 Eigen::Affine3f inverse_transform = Eigen::Affine3f::Identity();
00062
00063 if (rotation_ != Eigen::Vector3f::Zero ())
00064 {
00065 pcl::getTransformation (0, 0, 0,
00066 rotation_ (0), rotation_ (1), rotation_ (2),
00067 transform);
00068 inverse_transform = transform.inverse();
00069 }
00070
00071
00072 Eigen::Vector3f local_pt (Eigen::Vector3f::Zero ());
00073
00074 for (size_t index = 0; index < indices_->size (); ++index)
00075 {
00076
00077 int point_offset = ((*indices_)[index] * input_->point_step);
00078 int offset = point_offset + input_->fields[x_idx_].offset;
00079 memcpy (&local_pt, &input_->data[offset], sizeof (float)*3);
00080
00081
00082 if (!pcl_isfinite (local_pt.x ()) ||
00083 !pcl_isfinite (local_pt.y ()) ||
00084 !pcl_isfinite (local_pt.z ()))
00085 continue;
00086
00087
00088 if (!(transform_.matrix().isIdentity()))
00089 local_pt = transform_ * local_pt;
00090
00091 if (translation_ != Eigen::Vector3f::Zero ())
00092 {
00093 local_pt.x () = local_pt.x () - translation_ (0);
00094 local_pt.y () = local_pt.y () - translation_ (1);
00095 local_pt.z () = local_pt.z () - translation_ (2);
00096 }
00097
00098
00099 if (!(inverse_transform.matrix ().isIdentity ()))
00100 local_pt = inverse_transform * local_pt;
00101
00102 if (local_pt.x () < min_pt_[0] || local_pt.y () < min_pt_[1] || local_pt.z () < min_pt_[2])
00103 continue;
00104 if (local_pt.x () > max_pt_[0] || local_pt.y () > max_pt_[1] || local_pt.z () > max_pt_[2])
00105 continue;
00106
00107 memcpy (&output.data[indice_count++ * output.point_step],
00108 &input_->data[index * output.point_step], output.point_step);
00109 }
00110
00111 output.width = indice_count;
00112 output.row_step = output.point_step * output.width;
00113 output.data.resize (output.width * output.height * output.point_step);
00114 }
00115
00117 void
00118 pcl::CropBox<sensor_msgs::PointCloud2>::applyFilter (std::vector<int> &indices)
00119 {
00120 indices.resize (input_->width * input_->height);
00121 int indice_count = 0;
00122
00123 Eigen::Affine3f transform = Eigen::Affine3f::Identity();
00124 Eigen::Affine3f inverse_transform = Eigen::Affine3f::Identity();
00125
00126 if (rotation_ != Eigen::Vector3f::Zero ())
00127 {
00128 pcl::getTransformation (0, 0, 0,
00129 rotation_ (0), rotation_ (1), rotation_ (2),
00130 transform);
00131 inverse_transform = transform.inverse();
00132 }
00133
00134
00135 Eigen::Vector3f local_pt (Eigen::Vector3f::Zero ());
00136
00137 for (size_t index = 0; index < indices_->size (); index++)
00138 {
00139
00140 int point_offset = ((*indices_)[index] * input_->point_step);
00141 int offset = point_offset + input_->fields[x_idx_].offset;
00142 memcpy (&local_pt, &input_->data[offset], sizeof (float)*3);
00143
00144
00145 if (!(transform_.matrix().isIdentity()))
00146 local_pt = transform_ * local_pt;
00147
00148 if (translation_ != Eigen::Vector3f::Zero ())
00149 {
00150 local_pt.x () -= translation_ (0);
00151 local_pt.y () -= translation_ (1);
00152 local_pt.z () -= translation_ (2);
00153 }
00154
00155
00156 if (!(inverse_transform.matrix().isIdentity()))
00157 local_pt = inverse_transform * local_pt;
00158
00159 if (local_pt.x () < min_pt_[0] || local_pt.y () < min_pt_[1] || local_pt.z () < min_pt_[2])
00160 continue;
00161 if (local_pt.x () > max_pt_[0] || local_pt.y () > max_pt_[1] || local_pt.z () > max_pt_[2])
00162 continue;
00163
00164 indices[indice_count++] = (*indices_)[index];
00165 }
00166
00167 indices.resize (indice_count);
00168 }
00169
00170 PCL_INSTANTIATE(CropBox, PCL_XYZ_POINT_TYPES)