Public Member Functions | Static Public Member Functions | List of all members
grid_map::GridMapCvProcessing Class Reference

#include <GridMapCvProcessing.hpp>

Public Member Functions

 GridMapCvProcessing ()
 
virtual ~GridMapCvProcessing ()
 

Static Public Member Functions

static bool changeResolution (const GridMap &gridMapSource, GridMap &gridMapResult, const double resolution, const int interpolationAlgorithm=cv::INTER_CUBIC)
 
static GridMap getTransformedMap (GridMap &&gridMapSource, const Eigen::Isometry3d &transform, const std::string &heightLayerName, const std::string &newFrameId)
 

Detailed Description

Processing of grid maps with OpenCV methods.

Definition at line 21 of file GridMapCvProcessing.hpp.

Constructor & Destructor Documentation

grid_map::GridMapCvProcessing::GridMapCvProcessing ( )

Default constructor.

Definition at line 17 of file GridMapCvProcessing.cpp.

grid_map::GridMapCvProcessing::~GridMapCvProcessing ( )
virtual

Destructor.

Definition at line 19 of file GridMapCvProcessing.cpp.

Member Function Documentation

bool grid_map::GridMapCvProcessing::changeResolution ( const GridMap gridMapSource,
GridMap gridMapResult,
const double  resolution,
const int  interpolationAlgorithm = cv::INTER_CUBIC 
)
static

Changes the resolution of a grid map with help of OpenCV's interpolation algorithms.

Parameters
[in]gridMapSourcethe source grid map.
[out]gridMapResultthe resulting grid map with the desired resolution.
[in]resolutionthe desired resolution.
[in]

Definition at line 21 of file GridMapCvProcessing.cpp.

GridMap grid_map::GridMapCvProcessing::getTransformedMap ( GridMap &&  gridMapSource,
const Eigen::Isometry3d &  transform,
const std::string &  heightLayerName,
const std::string &  newFrameId 
)
static

Apply isometric transformation (rotation + offset) to grid map and returns the transformed map. Note: The returned map may not have the same length since it's geometric description contains the original map. Also note that the map treats the height layer differently from other layers. I.e, the translation in z-direction is applied only to the height layer. For layers other than the height layer that contain geometric information this function might compute unexpected results. E.g transforming the layers normals_x/y/z will only represent the same values at the transformed location but will not transform the normal vectors into the new coordinate system.

Parameters

Definition at line 57 of file GridMapCvProcessing.cpp.


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


grid_map_cv
Author(s): Péter Fankhauser , Magnus Gärtner
autogenerated on Tue Jun 1 2021 02:13:32