46 #ifndef __PCD_FILTER_PA_ROS_FILTER_H 47 #define __PCD_FILTER_PA_ROS_FILTER_H 57 #include <opencv2/highgui/highgui.hpp> 123 const char symbol)
const;
126 std::string
_getValue(
const std::string &str,
int &pos)
const;
129 std::string
_getComment(
const std::string &str)
const;
132 std::string
_floatToStr(
const double &value)
const;
135 bool _StrToFloat(
const std::string &str,
double &value)
const;
145 bool add(std::string filter);
151 std::vector<std::string>
get(void)
const;
155 const std::string base_frame,
const ros::Time time,
156 std::vector<cPcdFilterPaFilter> &result)
const;
159 std::string getLast(
void)
const;
162 int size(
void)
const;
176 const double relative_pos = 0.0)
const;
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