pcdfilter_pa_ros_filter.h
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * pcdfilter_pa_ros_filter.h *
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 #ifndef __PCD_FILTER_PA_ROS_FILTER_H
47 #define __PCD_FILTER_PA_ROS_FILTER_H
48 
49 // local headers
51 
52 // ros headers
53 #include <tf/transform_datatypes.h>
54 #include <tf/transform_listener.h>
55 
56 // additional libraries
57 #include <opencv2/highgui/highgui.hpp>
58 
59 // standard headers
60 #include <string>
61 #include <vector>
62 
63 //**************************[cPcdFilterPaRosFilter]****************************
65  public:
66  enum eFiltertype {
74  };
75  enum {
78  };
79 
83  const cPcdFilterPaRosFilter &other);
84 
86  bool inverse_;
87 
90 
92  bool required_;
93 
96 
98  std::string frame_[COUNT_FRAME];
99 
100  // additional offsets relative to frames
102 
104  std::string comment_;
105 
107  bool fromString(const std::string &filter);
109  std::string toString(void) const;
110 
112  void reset(void);
113 
115  bool isValid(void) const;
116 
117  private:
119  bool _skipWhitespace(const std::string &str, int &pos) const;
120 
122  bool _checkSymbol(const std::string &str, int &pos,
123  const char symbol) const;
124 
126  std::string _getValue(const std::string &str, int &pos) const;
127 
129  std::string _getComment(const std::string &str) const;
130 
132  std::string _floatToStr(const double &value) const;
133 
135  bool _StrToFloat(const std::string &str, double &value) const;
136 };
137 
138 //**************************[cPcdFilterPaRosFilters]***************************
140  public:
142 
143 
144  // adds a new filter
145  bool add(std::string filter);
146 
147  // clears all filters
148  void clear(void);
149 
150  // return all filters
151  std::vector<std::string> get(void) const;
152 
153  // returns simple filters based on numbers instead of frames
154  bool update( const tf::TransformListener &tf_listener,
155  const std::string base_frame, const ros::Time time,
156  std::vector<cPcdFilterPaFilter> &result) const;
157 
158  // returns last added filter (also includes erroneous filters)
159  std::string getLast(void) const;
160 
161  // return number of elements
162  int size(void) const;
163 
164  // access single element
165  cPcdFilterPaRosFilter& operator[](int i);
166  // access single element (const)
167  const cPcdFilterPaRosFilter& operator[](int i) const;
168 
169  // time before tf lookup fails - for updating filters
171 
172  protected:
173  // get tansform between two tfs
174  double update_transform(const tf::Transform &start,
175  const tf::Transform &goal, tf::Transform &result,
176  const double relative_pos = 0.0) const;
177 
178 
179  std::vector<cPcdFilterPaRosFilter> filters_;
180 
182 };
183 
184 #endif // __PCD_FILTER_PA_ROS_FILTER_H
std::string toString(void) const
returning string equivalent of filter
cPcdFilterPaRosFilter last_filter_
void reset(void)
reseting this filter
std::string _floatToStr(const double &value) const
helper function for converting a double
bool inverse_
inverted filter
std::string frame_[COUNT_FRAME]
frame id(s)
bool fromString(const std::string &filter)
setting filter from string
std::vector< cPcdFilterPaRosFilter > filters_
cPcdFilterPaRosFilter & operator=(const cPcdFilterPaRosFilter &other)
bool isValid(void) const
returning if filter is valid
std::string _getValue(const std::string &str, int &pos) const
helper function for returning the next value
bool add(const actionlib::TwoIntsGoal &req, actionlib::TwoIntsResult &res)
bool _StrToFloat(const std::string &str, double &value) const
helper function for converting a double
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
bool _skipWhitespace(const std::string &str, int &pos) const
helper function for skipping whitespace
std::string comment_
comment to filter
eFiltertype type_
filter type
std::string _getComment(const std::string &str) const
helper function for returning the comment
bool _checkSymbol(const std::string &str, int &pos, const char symbol) const
helper function for checking a certain symbol
tf::Transform offset_[COUNT_FRAME]
bool required_
required filter
double parameter_[COUNT_PARAMETER]
single parameter of filter


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