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

#include <CurvatureFilter.hpp>

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

Public Member Functions

virtual bool configure ()
 
 CurvatureFilter ()
 
virtual bool update (const T &mapIn, T &mapOut)
 
virtual ~CurvatureFilter ()
 
- 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 inputLayer_
 Input layer name. More...
 
std::string outputLayer_
 Output layer name. More...
 

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::CurvatureFilter< T >

Compute the curvature (second derivative) of a layer in the map.

Definition at line 22 of file CurvatureFilter.hpp.

Constructor & Destructor Documentation

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

Constructor

Definition at line 21 of file CurvatureFilter.cpp.

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

Destructor.

Definition at line 26 of file CurvatureFilter.cpp.

Member Function Documentation

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

Configures the filter from parameters on the Parameter Server

Implements filters::FilterBase< T >.

Definition at line 31 of file CurvatureFilter.cpp.

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

Compute the curvature of a layer in a map and saves it as additional grid map layer.

Parameters
mapIngrid map containing the layer for which the curvature is computed for.
mapOutgrid map containing mapIn and the new layer for the curvature.

Implements filters::FilterBase< T >.

Definition at line 49 of file CurvatureFilter.cpp.

Member Data Documentation

template<typename T >
std::string grid_map::CurvatureFilter< T >::inputLayer_
private

Input layer name.

Definition at line 51 of file CurvatureFilter.hpp.

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

Output layer name.

Definition at line 54 of file CurvatureFilter.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