#include <CurvatureFilter.hpp>

Public Member Functions | |
| bool | configure () override |
| CurvatureFilter () | |
| bool | update (const GridMap &mapIn, GridMap &mapOut) override |
| ~CurvatureFilter () override | |
Public Member Functions inherited from filters::FilterBase< GridMap > | |
| bool | configure (const std::string ¶m_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 GridMap &data_in, GridMap &data_out)=0 |
| 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< GridMap > | |
| bool | getParam (const std::string &name, std::string &value) const |
| bool | getParam (const std::string &name, XmlRpc::XmlRpcValue &value) const |
| bool | getParam (const std::string &name, double &value) const |
| bool | getParam (const std::string &name, std::vector< double > &value) const |
| bool | getParam (const std::string &name, unsigned int &value) const |
| bool | getParam (const std::string &name, int &value) const |
| bool | getParam (const std::string &name, std::vector< std::string > &value) const |
| bool | getParam (const std::string &name, bool &value) const |
| bool | loadConfiguration (XmlRpc::XmlRpcValue &config) |
Protected Attributes inherited from filters::FilterBase< GridMap > | |
| bool | configured_ |
| std::string | filter_name_ |
| std::string | filter_type_ |
| string_map_t | params_ |
Compute the curvature (second derivative) of a layer in the map.
Definition at line 22 of file CurvatureFilter.hpp.
|
default |
Constructor
|
overridedefault |
Destructor.
|
overridevirtual |
Configures the filter from parameters on the Parameter Server
Implements filters::FilterBase< GridMap >.
Definition at line 23 of file CurvatureFilter.cpp.
Compute the curvature of a layer in a map and saves it as additional grid map layer.
| mapIn | grid map containing the layer for which the curvature is computed for. |
| mapOut | grid map containing mapIn and the new layer for the curvature. |
Definition at line 39 of file CurvatureFilter.cpp.
|
private |
Input layer name.
Definition at line 49 of file CurvatureFilter.hpp.
|
private |
Output layer name.
Definition at line 52 of file CurvatureFilter.hpp.