Public Member Functions | Private Attributes | List of all members
mitre_fast_layered_map::OutlierRemoval Class Reference

#include <filters.hpp>

Inheritance diagram for mitre_fast_layered_map::OutlierRemoval:
Inheritance graph
[legend]

Public Member Functions

virtual bool configure ()
 
bool IsOutlierPoint (grid_map::GridMap &, const grid_map::Index &)
 Algorithm to determine if an occupied cell should be considered an outlier. More...
 
 OutlierRemoval ()
 
virtual bool update (const grid_map::GridMap &_mapIn, grid_map::GridMap &_mapOut)
 
virtual ~OutlierRemoval ()
 
- Public Member Functions inherited from filters::FilterBase< grid_map::GridMap >
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 layer_
 Layer of grid map to perform outlier removal on. More...
 

Additional Inherited Members

- Protected Member Functions inherited from filters::FilterBase< grid_map::GridMap >
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< grid_map::GridMap >
bool configured_
 
std::string filter_name_
 
std::string filter_type_
 
string_map_t params_
 

Detailed Description

Find outlier cells that are unlikely to be actual obstacles due to their neighborhood having no other obstacles

Definition at line 55 of file filters.hpp.

Constructor & Destructor Documentation

mitre_fast_layered_map::OutlierRemoval::OutlierRemoval ( )

Definition at line 15 of file outlier_removal.cpp.

mitre_fast_layered_map::OutlierRemoval::~OutlierRemoval ( )
virtual

Definition at line 19 of file outlier_removal.cpp.

Member Function Documentation

bool mitre_fast_layered_map::OutlierRemoval::configure ( )
virtual

Implements filters::FilterBase< grid_map::GridMap >.

Definition at line 23 of file outlier_removal.cpp.

bool mitre_fast_layered_map::OutlierRemoval::IsOutlierPoint ( grid_map::GridMap _map,
const grid_map::Index _index 
)

Algorithm to determine if an occupied cell should be considered an outlier.

grid_map::Index index(x, y);
if(IsOutlierPoint(gridMap, index))
{
// Do stuff
}

Checks all cells surrounding a supposed occupied cell If any of the surrounding cells are occupied then we believe this one If not, then we will clear it ASSUMPTION: We will use the same layer here that was passed in as a parameter

Parameters
_map[in] The grid map that stores the data
_index[in] The index within the grid map that we are checking
Returns
True if considered an outlier point, false if not

Definition at line 79 of file outlier_removal.cpp.

bool mitre_fast_layered_map::OutlierRemoval::update ( const grid_map::GridMap _mapIn,
grid_map::GridMap _mapOut 
)
virtual

Attempts to remove outliers from the TODO: Integrate with prior readings to get a more trustworthy solution

Implements filters::FilterBase< grid_map::GridMap >.

Definition at line 41 of file outlier_removal.cpp.

Member Data Documentation

std::string mitre_fast_layered_map::OutlierRemoval::layer_
private

Layer of grid map to perform outlier removal on.

Definition at line 78 of file filters.hpp.


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


mitre_fast_layered_map
Author(s):
autogenerated on Thu Mar 11 2021 03:06:49