Node for comparing different normal filters performances. More...
Namespaces | |
bicubic | |
bicubic_conv | |
internal | |
Classes | |
class | BufferNormalizerFilter |
class | BufferRegion |
class | CircleIterator |
struct | Clamp |
union | Color |
class | ColorBlendingFilter |
class | ColorFillFilter |
class | ColorMapFilter |
class | CurvatureFilter |
class | DeletionFilter |
class | DuplicationFilter |
class | EllipseIterator |
class | GridMap |
class | GridMapCvConverter |
class | GridMapCvProcessing |
class | GridMapIterator |
class | GridMapOctomapConverter |
class | GridMapRosConverter |
class | InpaintFilter |
class | LightIntensityFilter |
class | LineIterator |
class | MathExpressionFilter |
class | MeanInRadiusFilter |
class | MedianFillFilter |
class | MinInRadiusFilter |
class | MockFilter |
class | NormalColorMapFilter |
class | NormalVectorsFilter |
class | Polygon |
class | PolygonIterator |
class | PolygonRosConverter |
class | SetBasicLayersFilter |
class | SlidingWindowIterator |
class | SlidingWindowMathExpressionFilter |
class | SpiralIterator |
class | SubmapGeometry |
class | SubmapIterator |
class | ThresholdFilter |
Typedefs | |
typedef Matrix::Scalar | DataType |
typedef Matrix::Scalar | DataType |
typedef Matrix::Scalar | DataType |
typedef Matrix::Scalar | DataType |
typedef Matrix::Scalar | DataType |
typedef Matrix::Scalar | DataType |
typedef Matrix::Scalar | DataType |
typedef Matrix::Scalar | DataType |
typedef Matrix::Scalar | DataType |
typedef Eigen::Matrix4d | FunctionValueMatrix |
typedef Eigen::Matrix4d | FunctionValueMatrix |
typedef Eigen::Matrix4d | FunctionValueMatrix |
typedef Eigen::Matrix4d | FunctionValueMatrix |
typedef Eigen::Matrix4d | FunctionValueMatrix |
typedef Eigen::Matrix4d | FunctionValueMatrix |
typedef Eigen::Matrix4d | FunctionValueMatrix |
typedef Eigen::Matrix4d | FunctionValueMatrix |
typedef Eigen::Matrix4d | FunctionValueMatrix |
typedef Eigen::Array2i | Index |
typedef Eigen::Array2i | Index |
typedef Eigen::Array2i | Index |
typedef Eigen::Array2i | Index |
typedef Eigen::Array2i | Index |
typedef Eigen::Array2i | Index |
typedef Eigen::Array2i | Index |
typedef Eigen::Array2i | Index |
typedef Eigen::Array2i | Index |
typedef Eigen::Array2d | Length |
typedef Eigen::Array2d | Length |
typedef Eigen::Array2d | Length |
typedef Eigen::Array2d | Length |
typedef Eigen::Array2d | Length |
typedef Eigen::Array2d | Length |
typedef Eigen::Array2d | Length |
typedef Eigen::Array2d | Length |
typedef Eigen::Array2d | Length |
typedef Eigen::MatrixXf | Matrix |
typedef Eigen::MatrixXf | Matrix |
typedef Eigen::MatrixXf | Matrix |
typedef Eigen::MatrixXf | Matrix |
typedef Eigen::MatrixXf | Matrix |
typedef Eigen::MatrixXf | Matrix |
typedef Eigen::MatrixXf | Matrix |
typedef Eigen::MatrixXf | Matrix |
typedef Eigen::MatrixXf | Matrix |
typedef Eigen::Vector2d | Position |
typedef Eigen::Vector2d | Position |
typedef Eigen::Vector2d | Position |
typedef Eigen::Vector2d | Position |
typedef Eigen::Vector2d | Position |
typedef Eigen::Vector2d | Position |
typedef Eigen::Vector2d | Position |
typedef Eigen::Vector2d | Position |
typedef Eigen::Vector2d | Position |
typedef Eigen::Vector3d | Position3 |
typedef Eigen::Vector3d | Position3 |
typedef Eigen::Vector3d | Position3 |
typedef Eigen::Vector3d | Position3 |
typedef Eigen::Vector3d | Position3 |
typedef Eigen::Vector3d | Position3 |
typedef Eigen::Vector3d | Position3 |
typedef Eigen::Vector3d | Position3 |
typedef Eigen::Vector3d | Position3 |
typedef Eigen::Array2i | Size |
typedef Eigen::Array2i | Size |
typedef Eigen::Array2i | Size |
typedef Eigen::Array2i | Size |
typedef Eigen::Array2i | Size |
typedef Eigen::Array2i | Size |
typedef Eigen::Array2i | Size |
typedef Eigen::Array2i | Size |
typedef Eigen::Array2i | Size |
typedef uint64_t | Time |
typedef uint64_t | Time |
typedef uint64_t | Time |
typedef uint64_t | Time |
typedef uint64_t | Time |
typedef uint64_t | Time |
typedef uint64_t | Time |
typedef uint64_t | Time |
typedef uint64_t | Time |
typedef Eigen::Vector2d | Vector |
typedef Eigen::Vector2d | Vector |
typedef Eigen::Vector2d | Vector |
typedef Eigen::Vector2d | Vector |
typedef Eigen::Vector2d | Vector |
typedef Eigen::Vector2d | Vector |
typedef Eigen::Vector2d | Vector |
typedef Eigen::Vector2d | Vector |
typedef Eigen::Vector2d | Vector |
typedef Eigen::Vector3d | Vector3 |
typedef Eigen::Vector3d | Vector3 |
typedef Eigen::Vector3d | Vector3 |
typedef Eigen::Vector3d | Vector3 |
typedef Eigen::Vector3d | Vector3 |
typedef Eigen::Vector3d | Vector3 |
typedef Eigen::Vector3d | Vector3 |
typedef Eigen::Vector3d | Vector3 |
typedef Eigen::Vector3d | Vector3 |
Functions | |
void | assertEqual (const M1 &A, const M2 &B, std::string const &message="") |
void | assertFinite (const M1 &A, std::string const &message="") |
void | assertNear (const M1 &A, const M2 &B, T tolerance, std::string const &message="") |
unsigned int | bindIndexToRange (int idReq, unsigned int nElem) |
void | boundIndexToRange (Index &index, const Size &bufferSize) |
void | boundIndexToRange (int &index, const int &bufferSize) |
void | boundPositionToRange (Position &position, const Length &mapLength, const Position &mapPosition) |
bool | checkIfIndexInRange (const Index &index, const Size &bufferSize) |
bool | checkIfPositionWithinMap (const Position &position, const Length &mapLength, const Position &mapPosition) |
bool | colorValueToVector (const unsigned long &colorValue, Eigen::Vector3i &colorVector) |
bool | colorValueToVector (const unsigned long &colorValue, Eigen::Vector3f &colorVector) |
bool | colorValueToVector (const float &colorValue, Eigen::Vector3f &colorVector) |
bool | colorVectorToValue (const Eigen::Vector3i &colorVector, unsigned long &colorValue) |
void | colorVectorToValue (const Eigen::Vector3i &colorVector, float &colorValue) |
void | colorVectorToValue (const Eigen::Vector3f &colorVector, float &colorValue) |
bool | compareRelative (double a, double b, double percentTolerance, double *percentError=NULL) |
void | expectNear (const M1 &A, const M2 &B, T tolerance, std::string const &message="") |
Index | getBufferIndexFromIndex (const Index &index, const Size &bufferSize, const Index &bufferStartIndex) |
const Eigen::Matrix2i | getBufferOrderToMapFrameAlignment () |
bool | getBufferRegionsForSubmap (std::vector< BufferRegion > &submapBufferRegions, const Index &submapIndex, const Size &submapBufferSize, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero()) |
unsigned int | getCols (const MultiArrayMessageType_ &message) |
Index | getIndexFromBufferIndex (const Index &bufferIndex, const Size &bufferSize, const Index &bufferStartIndex) |
Index | getIndexFromLinearIndex (const size_t linearIndex, const Size &bufferSize, const bool rowMajor=false) |
bool | getIndexFromPosition (Index &index, const Position &position, const Length &mapLength, const Position &mapPosition, const double &resolution, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero()) |
bool | getIndexShiftFromPositionShift (Index &indexShift, const Vector &positionShift, const double &resolution) |
double | getLayerValue (const Matrix &layerMat, int rowReq, int colReq) |
size_t | getLinearIndexFromIndex (const Index &index, const Size &bufferSize, const bool rowMajor=false) |
bool | getPositionFromIndex (Position &position, const Index &index, const Length &mapLength, const Position &mapPosition, const double &resolution, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero()) |
void | getPositionOfDataStructureOrigin (const Position &position, const Length &mapLength, Position &positionOfOrigin) |
bool | getPositionShiftFromIndexShift (Vector &positionShift, const Index &indexShift, const double &resolution) |
unsigned int | getRows (const MultiArrayMessageType_ &message) |
bool | getSubmapInformation (Index &submapTopLeftIndex, Size &submapBufferSize, Position &submapPosition, Length &submapLength, Index &requestedIndexInSubmap, const Position &requestedSubmapPosition, const Length &requestedSubmapLength, const Length &mapLength, const Position &mapPosition, const double &resolution, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero()) |
Size | getSubmapSizeFromCornerIndeces (const Index &topLeftIndex, const Index &bottomRightIndex, const Size &bufferSize, const Index &bufferStartIndex) |
bool | incrementIndex (Index &index, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero()) |
bool | incrementIndexForSubmap (Index &submapIndex, Index &index, const Index &submapTopLeftIndex, const Size &submapBufferSize, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero()) |
bool | isRowMajor (const MultiArrayMessageType_ &message) |
void | mapAddNoise (grid_map::GridMap &map, const grid_map::Size &gridMapSize, const double &noise_on_map) |
void | mapAddOutliers (grid_map::GridMap &map, const grid_map::Size &gridMapSize, const double outlierPercentage) |
void | mapAverageFiltering (grid_map::GridMap &map, const grid_map::Size &gridMapSize, const double filterRadius) |
bool | matrixEigenCopyToMultiArrayMessage (const EigenType_ &e, MultiArrayMessageType_ &m) |
bool | multiArrayMessageCopyToMatrixEigen (const MultiArrayMessageType_ &m, EigenType_ &e) |
bool | multiArrayMessageMapToMatrixEigen (MultiArrayMessageType_ &m, EigenType_ &e) |
int | nDimensions () |
void | normalsErrorCalculation (grid_map::GridMap &map, const grid_map::Size &gridMapSize, double &directionalErrorAreaSum, double &directionalErrorRasterSum) |
Eigen::Matrix< double, N, N > | randomCovariance () |
Eigen::MatrixXd | randomCovarianceXd (int N) |
void | wrapIndexToRange (int &index, int bufferSize) |
void | wrapIndexToRange (Index &index, const Size &bufferSize) |
Node for comparing different normal filters performances.
void grid_map::mapAddNoise | ( | grid_map::GridMap & | map, |
const grid_map::Size & | gridMapSize, | ||
const double & | noise_on_map | ||
) |
Function to add noise to the elevation map. Noise added is white noise from a uniform distribution [-1:1] multiplied by the amount of noise wanted specified by noise_on_map.
map | grid map to which add the layers that contains the errors. |
gridMapSize | Dimensions of grid map, passed as parameter to not being calculated every time. |
noise_on_map | Amount of noise wanted in meters, can be set as an argument in the roslaunch phase. |
Definition at line 236 of file normal_filter_comparison_node.cpp.
void grid_map::mapAddOutliers | ( | grid_map::GridMap & | map, |
const grid_map::Size & | gridMapSize, | ||
const double | outlierPercentage | ||
) |
Function to add outliers to the elevation map. Outliers are point where the elevation value is set to infinity. It has to be performed after mapAddNoise.
map | grid map to which add the layers that contains the errors. |
gridMapSize | Dimensions of grid map, passed as parameter to not being calculated every time. |
outlierPercentage | Amount of outliers wanted percentage, can be set as an argument in the roslaunch phase. |
Definition at line 242 of file normal_filter_comparison_node.cpp.
void grid_map::mapAverageFiltering | ( | grid_map::GridMap & | map, |
const grid_map::Size & | gridMapSize, | ||
const double | filterRadius | ||
) |
Function to add outliers to the elevation map. Outliers are point where the elevation value is set to infinity. It has to be performed after mapAddNoise.
map | grid map to which add the layers that contains the errors. |
gridMapSize | Dimensions of grid map, passed as parameter to not being calculated every time. |
filterRadius | Radius of the wanted shifting average filter. |
Definition at line 254 of file normal_filter_comparison_node.cpp.
void grid_map::normalsErrorCalculation | ( | grid_map::GridMap & | map, |
const grid_map::Size & | gridMapSize, | ||
double & | directionalErrorAreaSum, | ||
double & | directionalErrorRasterSum | ||
) |
Function to calculate the normal vector computation error.Error is defined as sum over the map of absolute cosines between analytical and computed normals. The cosines are calculated using the dot product between two unitary vectors. The error sum is then averaged between the latest 20 iteration of the functions.
map | grid map to which add the layers that contains the errors. |
gridMapSize | Dimensions of grid map, passed as parameter to not being calculated every time. |
directionalErrorAreaSum | Average of the summed error over the map for area method. |
directionalErrorRasterSum | Average of the summed error over the map for raster method. |
Definition at line 181 of file normal_filter_comparison_node.cpp.