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

#include <MedianFillFilter.hpp>

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

Public Member Functions

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

Protected Member Functions

void addCvMatAsLayer (T &gridMap, const cv::Mat &cvLayer, const std::string &layerName)
 
cv::Mat_< bool > cleanedMask (const cv::Mat_< bool > &inputMask)
 
Eigen::MatrixXf computeAndAddFillMask (const Eigen::MatrixXf &inputMap, T &mapOut)
 
cv::Mat_< bool > fillHoles (const cv::Mat_< bool > &isValidMask, const size_t numDilationClosingIterations)
 
float getMedian (Eigen::Ref< const grid_map::Matrix > inputMap, const grid_map::Index &centerIndex, const size_t radiusInPixels, const grid_map::Size bufferSize)
 
- 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)
 

Private Attributes

bool debug_
 If set, the filtered grid_map is augmented with additional debug layers. More...
 
std::string debugInfillMaskLayer_ = "debug_infill_mask"
 Layer used to visualize the intermediate, sparse outlier removed fill mask. More...
 
double existingValueRadius_
 Median filtering radius for existing values in the input. More...
 
double fillHoleRadius_
 Median filtering radius of NaN values in the input. More...
 
std::string fillMaskLayer_ = "should_fill"
 Layer containing indicating which areas to fill, will be computed if not present. More...
 
bool filterExistingValues_
 Flag indicating whether to also filter finite values. More...
 
std::string inputLayer_
 Input layer name. More...
 
std::string outputLayer_
 Output layer name. More...
 

Additional Inherited Members

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

Uses std::nth_element to fill holes in the input layer by the median of the surrounding values. The result is put into the output_layer. Note: Only values for which the fill_layer is true will be filled. The fill_layer is auto computed if not present in the input.

Definition at line 26 of file MedianFillFilter.hpp.

Constructor & Destructor Documentation

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

Constructor

Definition at line 28 of file MedianFillFilter.cpp.

template<typename T >
grid_map::MedianFillFilter< T >::~MedianFillFilter ( )
virtualdefault

Destructor.

Member Function Documentation

template<typename T >
void grid_map::MedianFillFilter< T >::addCvMatAsLayer ( T &  gridMap,
const cv::Mat &  cvLayer,
const std::string &  layerName 
)
protected

Adds a float cv matrix as layer to a given map.

Parameters
[in,out]gridMapThe map to add the layer.
[in]cvLayerThe cv matrix to add.
[in]layerNameThe layer name

Definition at line 247 of file MedianFillFilter.cpp.

template<typename T >
cv::Mat_< bool > grid_map::MedianFillFilter< T >::cleanedMask ( const cv::Mat_< bool > &  inputMask)
protected

Remove sparse valid regions by morphological opening.

Remarks
Check https://docs.opencv.org/master/d9/d61/tutorial_py_morphological_ops.html for more information about the opening operation.
Parameters
inputMaskInitial mask possibly containing also sparse valid regions that will be removed.
Returns
An opencv mask of the same size as input mask with small sparse valid regions removed.

Definition at line 216 of file MedianFillFilter.cpp.

template<typename T >
Eigen::MatrixXf grid_map::MedianFillFilter< T >::computeAndAddFillMask ( const Eigen::MatrixXf &  inputMap,
T &  mapOut 
)
protected

Computes a mask of which cells to fill-in based on the validity of input cells. I.e small holes between (and including) valid cells are marked to be filled.

Remarks
The returned fill_mask is also added as layer to the output to be reused in following iterations of this filter. If debug is enabled, an intermediate mask is added as layer to the output grid map.
Parameters
inputMapThe input layer, used to check which cells contain valid values.
mapOutThe output GridMap will contain the additional fill_mask layer afterwards.
Returns
An eigen mask indicating which cells should be filled by the median filter.

Definition at line 191 of file MedianFillFilter.cpp.

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

Configures the filter from parameters on the Parameter Server

Implements filters::FilterBase< T >.

Definition at line 34 of file MedianFillFilter.cpp.

template<typename T >
cv::Mat_< bool > grid_map::MedianFillFilter< T >::fillHoles ( const cv::Mat_< bool > &  isValidMask,
const size_t  numDilationClosingIterations 
)
protected

Performs morphological closing on a boolean cv matrix mask.

Parameters
[in]isValidMaskA 2d mask where holes up to a certain size will be filled.
[in]numDilationClosingIterationsAlgorithm specific parameter. Higher means that bigger holes will still be filled.
Returns
A mask of the same size as isValidMask but with small holes filled.

Definition at line 231 of file MedianFillFilter.cpp.

template<typename T >
float grid_map::MedianFillFilter< T >::getMedian ( Eigen::Ref< const grid_map::Matrix inputMap,
const grid_map::Index centerIndex,
const size_t  radiusInPixels,
const grid_map::Size  bufferSize 
)
protected

Returns the median of the values in inputData in the neighbourhood around the centerIndex. The size of the quadratic neighbourhood is specified by radiusInPixels. If the number of values is even the "lower center" value is taken, eg with four values the second lowest is taken as median.

Parameters
inputMapThe data layer to compute a local median.
centerIndexThe center cell of the neighbourhood.
radiusInPixelsThe maximum L_inf distance from index.
bufferSizeThe buffer size of the input
Returns
The median of finites in the specified neighbourhood.

Definition at line 155 of file MedianFillFilter.cpp.

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

Adds a new output layer to the map. Uses the Boost accumulator median in the input layer. Saves the filter output in mapOut[output_layer].

Parameters
mapIngrid map containing input layer
mapOutgrid map containing mapIn and median filtered input layer.

Implements filters::FilterBase< T >.

Definition at line 107 of file MedianFillFilter.cpp.

Member Data Documentation

template<typename T >
bool grid_map::MedianFillFilter< T >::debug_
private

If set, the filtered grid_map is augmented with additional debug layers.

Definition at line 126 of file MedianFillFilter.hpp.

template<typename T >
std::string grid_map::MedianFillFilter< T >::debugInfillMaskLayer_ = "debug_infill_mask"
private

Layer used to visualize the intermediate, sparse outlier removed fill mask.

Definition at line 123 of file MedianFillFilter.hpp.

template<typename T >
double grid_map::MedianFillFilter< T >::existingValueRadius_
private

Median filtering radius for existing values in the input.

Definition at line 108 of file MedianFillFilter.hpp.

template<typename T >
double grid_map::MedianFillFilter< T >::fillHoleRadius_
private

Median filtering radius of NaN values in the input.

Definition at line 105 of file MedianFillFilter.hpp.

template<typename T >
std::string grid_map::MedianFillFilter< T >::fillMaskLayer_ = "should_fill"
private

Layer containing indicating which areas to fill, will be computed if not present.

Definition at line 120 of file MedianFillFilter.hpp.

template<typename T >
bool grid_map::MedianFillFilter< T >::filterExistingValues_
private

Flag indicating whether to also filter finite values.

Definition at line 111 of file MedianFillFilter.hpp.

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

Input layer name.

Definition at line 114 of file MedianFillFilter.hpp.

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

Output layer name.

Definition at line 117 of file MedianFillFilter.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