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

#include <NormalVectorsFilter.hpp>

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

Public Member Functions

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

enum  Method { Method::Area, Method::Raster }
 

Private Member Functions

void computeWithArea (GridMap &map, const std::string &inputLayer, const std::string &outputLayersPrefix)
 
void computeWithRaster (GridMap &map, const std::string &inputLayer, const std::string &outputLayersPrefix)
 

Private Attributes

double estimationRadius_
 Radius of submap for normal vector estimation. More...
 
std::string inputLayer_
 Input layer name. More...
 
Method method_
 
Eigen::Vector3d normalVectorPositiveAxis_
 Normal vector positive axis. More...
 
std::string outputLayersPrefix_
 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::NormalVectorsFilter< T >

Compute the normal vectors of a layer in a map.

Definition at line 23 of file NormalVectorsFilter.hpp.

Member Enumeration Documentation

template<typename T >
enum grid_map::NormalVectorsFilter::Method
strongprivate
Enumerator
Area 
Raster 

Definition at line 55 of file NormalVectorsFilter.hpp.

Constructor & Destructor Documentation

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

Constructor

Definition at line 22 of file NormalVectorsFilter.cpp.

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

Destructor.

Definition at line 29 of file NormalVectorsFilter.cpp.

Member Function Documentation

template<typename T >
void grid_map::NormalVectorsFilter< T >::computeWithArea ( GridMap map,
const std::string &  inputLayer,
const std::string &  outputLayersPrefix 
)
private

Definition at line 102 of file NormalVectorsFilter.cpp.

template<typename T >
void grid_map::NormalVectorsFilter< T >::computeWithRaster ( GridMap map,
const std::string &  inputLayer,
const std::string &  outputLayersPrefix 
)
private

Definition at line 164 of file NormalVectorsFilter.cpp.

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

Configures the filter from parameters on the Parameter Server

Implements filters::FilterBase< T >.

Definition at line 34 of file NormalVectorsFilter.cpp.

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

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

Parameters
mapIngrid map containing the layer for which the normal vectors are computed for.
mapOutgrid map containing mapIn and the new layers for the normal vectors.

Implements filters::FilterBase< T >.

Definition at line 80 of file NormalVectorsFilter.cpp.

Member Data Documentation

template<typename T >
double grid_map::NormalVectorsFilter< T >::estimationRadius_
private

Radius of submap for normal vector estimation.

Definition at line 63 of file NormalVectorsFilter.hpp.

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

Input layer name.

Definition at line 69 of file NormalVectorsFilter.hpp.

template<typename T >
Method grid_map::NormalVectorsFilter< T >::method_
private

Definition at line 60 of file NormalVectorsFilter.hpp.

template<typename T >
Eigen::Vector3d grid_map::NormalVectorsFilter< T >::normalVectorPositiveAxis_
private

Normal vector positive axis.

Definition at line 66 of file NormalVectorsFilter.hpp.

template<typename T >
std::string grid_map::NormalVectorsFilter< T >::outputLayersPrefix_
private

Output layer name.

Definition at line 72 of file NormalVectorsFilter.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 25 2019 20:02:22