Public Member Functions | Protected Attributes | Friends | List of all members
cras::FilterBase< F > Class Template Reference

#include <filter_base.hpp>

Inheritance diagram for cras::FilterBase< F >:
Inheritance graph
[legend]

Public Member Functions

 FilterBase ()
 Construct the filter and pass the corresponding Log and GetParam helpers. More...
 
void setNodelet (const ::nodelet::Nodelet *nodelet)
 Inform this filter that it is running inside the passed nodelet. This should be called after configure(). More...
 
 ~FilterBase () override=default
 
- Public Member Functions inherited from filters::FilterBase< F >
bool configure (const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
 
bool configure (XmlRpc::XmlRpcValue &config)
 
 FilterBase ()
 
const std::string & getName () const
 
std::string getType ()
 
virtual bool update (const T &data_in, T &data_out)=0
 
- Public Member Functions inherited from cras::BoundParamHelper
 BoundParamHelper (const ::cras::LogHelperPtr &log, const ::cras::GetParamAdapterPtr &param)
 
inline ::std::string getNamespace () const
 Return the namespace this helper operates in. More...
 
inline ::std::string getParam (const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::std::string getParam (const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions< std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::GetParamResult< std::string > getParamVerbose (const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
bool hasParam (const ::std::string &name, const bool searchNested=true) const
 Whether a parameter with the given name exists. More...
 
inline ::cras::BoundParamHelperPtr paramsInNamespace (const ::std::string &ns) const
 Return a parameter helper of a sub-namespace. More...
 
 ~BoundParamHelper () override=default
 

Protected Attributes

const ::nodelet::Nodeletnodelet {nullptr}
 The nodelet this filter is running in. It should be set via setNodelet() after the filter is configured. More...
 
- Protected Attributes inherited from filters::FilterBase< F >
bool configured_
 
std::string filter_name_
 
std::string filter_type_
 
string_map_t params_
 
- Protected Attributes inherited from cras::BoundParamHelper
::cras::GetParamAdapterPtr param
 The bound parameter adapter. More...
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 Log helper. More...
 

Friends

struct ::cras::FilterGetParamAdapter< F >
 

Additional Inherited Members

- Protected Member Functions inherited from filters::FilterBase< F >
virtual bool configure ()=0
 
bool getParam (const std::string &name, bool &value) const
 
bool getParam (const std::string &name, double &value) const
 
bool getParam (const std::string &name, int &value) const
 
bool getParam (const std::string &name, std::string &value) const
 
bool getParam (const std::string &name, std::vector< double > &value) const
 
bool getParam (const std::string &name, std::vector< std::string > &value) const
 
bool getParam (const std::string &name, unsigned int &value) const
 
bool getParam (const std::string &name, XmlRpc::XmlRpcValue &value) const
 
bool loadConfiguration (XmlRpc::XmlRpcValue &config)
 
- Protected Member Functions inherited from cras::ParamHelper
::cras::LogHelperPtr getLogger () const
 Return the log helper used for logging. More...
 
inline ::std::string getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::std::string getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
 ParamHelper (const ::cras::LogHelperPtr &log)
 
void setLogger (const ::cras::LogHelperPtr &logger)
 Set the log helper used for logging. More...
 
virtual ~ParamHelper ()=default
 
- Protected Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 This is the function picked up by CRAS_* logging macros. More...
 
 HasLogger (const ::cras::LogHelperPtr &log)
 Associate the logger with this interface. More...
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 Set the logger to be used for logging. More...
 

Detailed Description

template<typename F>
class cras::FilterBase< F >

This FilterBase implementation adds access to the templated getParam() methods from param_utils. It also adds possibility to inform the filter about the nodelet it is running in (if it is running in one).

Template Parameters
FType of the filtered data.

Definition at line 40 of file filter_base.hpp.

Constructor & Destructor Documentation

◆ FilterBase()

template<typename F >
cras::FilterBase< F >::FilterBase ( )
inline

Construct the filter and pass the corresponding Log and GetParam helpers.

Definition at line 46 of file filter_base.hpp.

◆ ~FilterBase()

template<typename F >
cras::FilterBase< F >::~FilterBase ( )
overridevirtualdefault

Reimplemented from filters::FilterBase< F >.

Member Function Documentation

◆ setNodelet()

template<typename F >
void cras::FilterBase< F >::setNodelet ( const ::nodelet::Nodelet nodelet)
inline

Inform this filter that it is running inside the passed nodelet. This should be called after configure().

Parameters
nodeletThe nodelet running this filter.

Definition at line 58 of file filter_base.hpp.

Friends And Related Function Documentation

◆ ::cras::FilterGetParamAdapter< F >

template<typename F >
friend struct ::cras::FilterGetParamAdapter< F >
friend

Definition at line 64 of file filter_base.hpp.

Member Data Documentation

◆ nodelet

template<typename F >
const ::nodelet::Nodelet* cras::FilterBase< F >::nodelet {nullptr}
protected

The nodelet this filter is running in. It should be set via setNodelet() after the filter is configured.

Definition at line 71 of file filter_base.hpp.


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


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sun Jan 14 2024 03:48:14