pcdfilter_pa.cpp
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * pcdfilter_pa.cpp *
4 * ================ *
5 * *
6 *******************************************************************************
7 * *
8 * github repository *
9 * https://github.com/TUC-ProAut/ros_pcdfilter *
10 * *
11 * Chair of Automation Technology, Technische Universität Chemnitz *
12 * https://www.tu-chemnitz.de/etit/proaut *
13 * *
14 *******************************************************************************
15 * *
16 * New BSD License *
17 * *
18 * Copyright (c) 2015-2018, Peter Weissig, Technische Universität Chemnitz *
19 * All rights reserved. *
20 * *
21 * Redistribution and use in source and binary forms, with or without *
22 * modification, are permitted provided that the following conditions are met: *
23 * * Redistributions of source code must retain the above copyright *
24 * notice, this list of conditions and the following disclaimer. *
25 * * Redistributions in binary form must reproduce the above copyright *
26 * notice, this list of conditions and the following disclaimer in the *
27 * documentation and/or other materials provided with the distribution. *
28 * * Neither the name of the Technische Universität Chemnitz nor the *
29 * names of its contributors may be used to endorse or promote products *
30 * derived from this software without specific prior written permission. *
31 * *
32 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" *
33 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE *
34 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE *
35 * ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY *
36 * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
37 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR *
38 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER *
39 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT *
40 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY *
41 * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH *
42 * DAMAGE. *
43 * *
44 ******************************************************************************/
45 
46 // local headers
48 
49 // additional libraries
50 #include "opencv2/calib3d/calib3d.hpp"
51 #include "opencv2/photo/photo.hpp"
52 
53 // standard headers
54 #include <string>
55 #include <math.h>
56 
57 //**************************[cPcdFilterPa]*************************************
59 }
60 
61 //**************************[~cPcdFilterPa]************************************
63 }
64 
65 //**************************[pointcloudFilter]*********************************
66 std::vector<int> cPcdFilterPa::pointcloudFilter(const cv::Mat &pointcloud,
67  std::vector<bool> &mask) const {
68 
69  std::vector <int> count(params_.filters_.size(), 0);
70  mask.resize(pointcloud.rows, true);
71 
72  for (int i_point = pointcloud.rows - 1; i_point >= 0; i_point--) {
73  for (int i_filter = params_.filters_.size() - 1; i_filter >= 0;
74  i_filter--) {
75  if (params_.filters_[i_filter].type_ ==
77  continue;
78  }
79  cv::Vec3f v((float*) pointcloud.ptr(i_point));
80  v = params_.filters_[i_filter].rotation_ * v +
81  params_.filters_[i_filter].translation_;
82 
83  bool check = false;
84  switch (params_.filters_[i_filter].type_) {
86  if (std::fabs(v[0]) >
87  params_.filters_[i_filter].parameter_[0]) {
88  check = true; break;
89  }
90  if (std::fabs(v[1]) >
91  params_.filters_[i_filter].parameter_[0]) {
92  check = true; break;
93  }
94  if (std::fabs(v[2]) >
95  params_.filters_[i_filter].parameter_[0]) {
96  check = true; break;
97  }
98  break;
99 
101  if (std::fabs(v[0]) >
102  params_.filters_[i_filter].parameter_[0]) {
103  check = true; break;
104  }
105  if (std::fabs(v[1]) >
106  params_.filters_[i_filter].parameter_[1]) {
107  check = true; break;
108  }
109  if (std::fabs(v[2]) >
110  params_.filters_[i_filter].parameter_[2]) {
111  check = true; break;
112  }
113  break;
114 
116  if (v[0] * v[0] + v[1] * v[1] + v[2] * v[2] >
117  params_.filters_[i_filter].parameter_[0]) {
118  check = true; break;
119  }
120  break;
121 
123  if (v[1] * v[1] + v[2] * v[2] >
124  params_.filters_[i_filter].parameter_[0]) {
125  check = true; break;
126  }
127  if (std::fabs(v[0]) >
128  params_.filters_[i_filter].parameter_[1]) {
129  check = true; break;
130  }
131  break;
132 
134  if (v[0] <= 0) {
135  check = true; break;
136  }
137 
138  if (v[0] > params_.filters_[i_filter].parameter_[0]) {
139  check = true; break;
140  }
141 
142  if ((v[1] * v[1] + v[2] * v[2]) > (v[0] * v[0]) *
143  params_.filters_[i_filter].parameter_[1]) {
144  check = true; break;
145  }
146  break;
147  }
148  if (params_.filters_[i_filter].inverse_) {
149  check = ! check;
150  }
151  if (check == false) {
152  count[i_filter]++;
153  mask[i_point] = false;
154  break;
155  }
156  }
157  }
158 
159  return count;
160 }
std::vector< cPcdFilterPaFilter > filters_
internal filters for pointcloud
ROSCPP_DECL bool check()
std::vector< int > pointcloudFilter(const cv::Mat &pointcloud, std::vector< bool > &mask) const
~cPcdFilterPa()
default destructor
cPcdFilterPa()
default constructor
cPcdFilterPaParameter params_
specific parameter
Definition: pcdfilter_pa.h:78


pcdfilter_pa
Author(s):
autogenerated on Mon Dec 23 2019 03:56:23