Public Member Functions | Private Member Functions | Private Attributes | List of all members
iirob_filters::ThresholdFilter< T > Class Template Reference

#include <threshold_filter.h>

Inheritance diagram for iirob_filters::ThresholdFilter< T >:
Inheritance graph
[legend]

Public Member Functions

virtual bool configure ()
 
 ThresholdFilter ()
 
virtual bool update (const T &data_in, T &data_out)
 
template<>
bool update (const geometry_msgs::WrenchStamped &data_in, geometry_msgs::WrenchStamped &data_out)
 
 ~ThresholdFilter ()
 
- Public Member Functions inherited from filters::FilterBase< T >
bool configure (const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
 
bool configure (XmlRpc::XmlRpcValue &config)
 
 FilterBase ()
 
const std::string & getName ()
 
std::string getType ()
 
virtual ~FilterBase ()
 

Private Member Functions

void reconfigureConfigurationRequest (iirob_filters::ThresholdConfig &config, uint32_t level)
 

Private Attributes

iirob_filters::ThresholdParameters params_
 
dynamic_reconfigure::Server< iirob_filters::ThresholdConfig > reconfigCalibrationSrv_
 
double threshold_
 
double threshold_angular_
 
double threshold_lin_
 

Additional Inherited Members

- Protected Member Functions inherited from filters::FilterBase< T >
bool getParam (const std::string &name, std::string &value)
 
bool getParam (const std::string &name, XmlRpc::XmlRpcValue &value)
 
bool getParam (const std::string &name, double &value)
 
bool getParam (const std::string &name, std::vector< double > &value)
 
bool getParam (const std::string &name, unsigned int &value)
 
bool getParam (const std::string &name, int &value)
 
bool getParam (const std::string &name, std::vector< std::string > &value)
 
bool getParam (const std::string &name, bool &value)
 
bool loadConfiguration (XmlRpc::XmlRpcValue &config)
 
- Protected Attributes inherited from filters::FilterBase< T >
bool configured_
 
std::string filter_name_
 
std::string filter_type_
 
string_map_t params_
 

Detailed Description

template<typename T>
class iirob_filters::ThresholdFilter< T >

Definition at line 54 of file threshold_filter.h.

Constructor & Destructor Documentation

template<typename T >
iirob_filters::ThresholdFilter< T >::ThresholdFilter ( )

Definition at line 76 of file threshold_filter.h.

template<typename T >
iirob_filters::ThresholdFilter< T >::~ThresholdFilter ( )

Definition at line 82 of file threshold_filter.h.

Member Function Documentation

template<typename T >
bool iirob_filters::ThresholdFilter< T >::configure ( )
virtual

Implements filters::FilterBase< T >.

Definition at line 87 of file threshold_filter.h.

template<typename T >
void iirob_filters::ThresholdFilter< T >::reconfigureConfigurationRequest ( iirob_filters::ThresholdConfig &  config,
uint32_t  level 
)
private

Definition at line 179 of file threshold_filter.h.

template<typename T >
bool iirob_filters::ThresholdFilter< T >::update ( const T &  data_in,
T &  data_out 
)
virtual

Implements filters::FilterBase< T >.

Definition at line 105 of file threshold_filter.h.

template<>
bool iirob_filters::ThresholdFilter< geometry_msgs::WrenchStamped >::update ( const geometry_msgs::WrenchStamped &  data_in,
geometry_msgs::WrenchStamped &  data_out 
)
inline

Definition at line 117 of file threshold_filter.h.

Member Data Documentation

template<typename T >
iirob_filters::ThresholdParameters iirob_filters::ThresholdFilter< T >::params_
private

Definition at line 64 of file threshold_filter.h.

template<typename T >
dynamic_reconfigure::Server<iirob_filters::ThresholdConfig> iirob_filters::ThresholdFilter< T >::reconfigCalibrationSrv_
private

Definition at line 69 of file threshold_filter.h.

template<typename T >
double iirob_filters::ThresholdFilter< T >::threshold_
private

Definition at line 65 of file threshold_filter.h.

template<typename T >
double iirob_filters::ThresholdFilter< T >::threshold_angular_
private

Definition at line 67 of file threshold_filter.h.

template<typename T >
double iirob_filters::ThresholdFilter< T >::threshold_lin_
private

Definition at line 66 of file threshold_filter.h.


The documentation for this class was generated from the following file:


iirob_filters
Author(s): Denis Štogl
autogenerated on Fri Sep 18 2020 03:32:19