pcdfilter_pa_filter.cpp
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * pcdfilter_pa_filter.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 // standard headers
50 #include <sstream>
51 
52 //**************************[cPcdFilterPaFilter]*******************************
54 
55  type_ = ftNONE;
56  inverse_ = false ;
57 
58  parameter_[0] = 0;
59  parameter_[1] = 0;
60  parameter_[2] = 0;
61 
62  rotation_ = cv::Matx33f::eye();
63  //translation_ = cv::Vec3f();
64 }
65 
66 //**************************[cPcdFilterPaFilter]*******************************
68  const cPcdFilterPaFilter &other) {
69 
70  *this = other;
71 }
72 
73 //**************************[operator = ]**************************************
75  const cPcdFilterPaFilter &other) {
76 
77  type_ = other.type_ ;
78  inverse_ = other.inverse_ ;
79 
80  parameter_[0] = other.parameter_[0];
81  parameter_[1] = other.parameter_[1];
82  parameter_[2] = other.parameter_[2];
83 
84  rotation_ = other.rotation_ ;
85  translation_ = other.translation_ ;
86 
87  return *this;
88 }
89 
90 //**************************[toString]*****************************************
91 std::string cPcdFilterPaFilter::toString(void) const {
92  std::stringstream result;
93 
94  if (inverse_) {
95  result << '!';
96  }
97 
98  int count_para = 0;
99  switch (type_) {
100  case ftNONE : result << "none" ; break;
101  case ftCUBE : result << "cube" ; count_para = 1; break;
102  case ftSPHERE : result << "sphere" ; count_para = 1; break;
103  case ftBLOCK : result << "block" ; count_para = 3; break;
104  case ftCYLINDER: result << "cylinder"; count_para = 2; break;
105  case ftCONE : result << "cone" ; count_para = 2; break;
106  default : result << "error" ; break;
107  }
108  result << ":";
109 
110  for (int i = 0; i < count_para; i++) {
111  result << ' ' << parameter_[i];
112  }
113 
114  result << "; rot=[[";
115  for (int y = 0; y < 3; y++) {
116  if (y > 0) { result << "], [";}
117  for (int x = 0; x < 3; x++) {
118  if (x > 0) { result << ", ";}
119  result << rotation_(y,x);
120  }
121  }
122  result << "]]";
123 
124  result << "; trans=[";
125  for (int x = 0; x < 3; x++) {
126  if (x > 0) { result << ", ";}
127  result << translation_(x);
128  }
129  result << "]";
130 
131  return result.str();
132 }
eFiltertype type_
filter type
TFSIMD_FORCE_INLINE const tfScalar & y() const
bool inverse_
inverted filter
std::string toString(void) const
cPcdFilterPaFilter & operator=(const cPcdFilterPaFilter &other)
TFSIMD_FORCE_INLINE const tfScalar & x() const


pcdfilter_pa
Author(s):
autogenerated on Fri Jun 7 2019 21:53:31