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

#include <ThresholdFilter.hpp>

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

Public Member Functions

virtual bool configure ()
 
 ThresholdFilter ()
 
virtual bool update (const T &mapIn, T &mapOut)
 
virtual ~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 Attributes

std::string conditionLayer_
 Layer the threshold will be evaluated. More...
 
double lowerThreshold_
 Lower Threshold. More...
 
std::string outputLayer_
 Layer the threshold should be applied to. More...
 
double setTo_
 If threshold triggered set to this value. More...
 
double upperThreshold_
 Upper Threshold. More...
 
bool useLowerThreshold_
 Booleans to decide which threshold should be used. More...
 
bool useUpperThreshold_
 

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 grid_map::ThresholdFilter< T >

Threshold filter class to set values below/above a threshold to a specified value.

Definition at line 23 of file ThresholdFilter.hpp.

Constructor & Destructor Documentation

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

Constructor

Definition at line 19 of file ThresholdFilter.cpp.

template<typename T >
grid_map::ThresholdFilter< T >::~ThresholdFilter ( )
virtual

Destructor.

Definition at line 29 of file ThresholdFilter.cpp.

Member Function Documentation

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

Configures the filter from parameters on the parameter server.

Implements filters::FilterBase< T >.

Definition at line 34 of file ThresholdFilter.cpp.

template<typename T >
bool grid_map::ThresholdFilter< T >::update ( const T &  mapIn,
T &  mapOut 
)
virtual

Uses either an upper or lower threshold. If the threshold is exceeded the cell value is set to the predefined value setTo_.

Parameters
mapInGridMap with the different layers to apply a threshold.
mapOutGridMap with the threshold applied to the layers.

Implements filters::FilterBase< T >.

Definition at line 80 of file ThresholdFilter.cpp.

Member Data Documentation

template<typename T >
std::string grid_map::ThresholdFilter< T >::conditionLayer_
private

Layer the threshold will be evaluated.

Definition at line 53 of file ThresholdFilter.hpp.

template<typename T >
double grid_map::ThresholdFilter< T >::lowerThreshold_
private

Lower Threshold.

Definition at line 59 of file ThresholdFilter.hpp.

template<typename T >
std::string grid_map::ThresholdFilter< T >::outputLayer_
private

Layer the threshold should be applied to.

Definition at line 56 of file ThresholdFilter.hpp.

template<typename T >
double grid_map::ThresholdFilter< T >::setTo_
private

If threshold triggered set to this value.

Definition at line 68 of file ThresholdFilter.hpp.

template<typename T >
double grid_map::ThresholdFilter< T >::upperThreshold_
private

Upper Threshold.

Definition at line 62 of file ThresholdFilter.hpp.

template<typename T >
bool grid_map::ThresholdFilter< T >::useLowerThreshold_
private

Booleans to decide which threshold should be used.

Definition at line 65 of file ThresholdFilter.hpp.

template<typename T >
bool grid_map::ThresholdFilter< T >::useUpperThreshold_
private

Definition at line 65 of file ThresholdFilter.hpp.


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


grid_map_filters
Author(s): Péter Fankhauser , Martin Wermelinger
autogenerated on Tue Jun 1 2021 02:13:38