Classes | Public Types | Public Member Functions | Static Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
GridMap Class Reference

#include <grid-map.h>

List of all members.

Classes

struct  MapGroupEmpty
struct  MapGroupNotEmpty
struct  WrongKnownMap

Public Types

typedef std::set< GridMap * > Group
typedef boost::tuple< unsigned,
Vector, unsigned > 
Label
 A label has a center of mass, and an area.
typedef std::vector< LabelLabels
 All found labels.
typedef signed short Value
typedef Eigen::Vector2f Vector
typedef std::pair< Vector, VectorVectorPair
 A pair of vectors.

Public Member Functions

void addNearestValueSaturated (const Vector &pos, const int delta)
 Add delta ta value at pos, saturated but sampled without any interpolation.
ValueatInternalCoord (const int x, const int y)
Value atInternalCoord (const int x, const int y) const
template<typename Op >
void binaryOperation (const GridMap &that, Op &op)
 Map to map generic binary operation.
template<typename Op >
void binaryOperation (const GridMap &that, const Op &op)
 Map to map generic binary operation, overload for const op.
GridMap buildGradient (const Vector &goal, bool &isSuccess) const
 Build a gradient to a goal, and avoid obstacles (see Philippsen TR E* 06)
VectorPair closestPoints (const Label &area0, const Label &area1, const unsigned monteCarloSteps=100) const
 Return approximately the closest points between two areas.
void dilate4 (const unsigned amount, const unsigned delta=0)
 Dilate the map of amount pixels, taking into account the four N,S,W,E pixels around each pixel.
void dilate8 (const unsigned amount, const unsigned delta=0)
 Dilate the map of amount pixels, taking into account all the eight pixels around each pixel.
void erode4 (const unsigned amount, const unsigned delta=0)
 Erode the map of amount pixels, taking into account the four N,S,W,E pixels around each pixel.
void erode8 (const unsigned amount, const unsigned delta=0)
 Erode the map of amount pixels, taking into account all the eight pixels around each pixel.
void extendToFit (const Vector &pos)
 Extend to fit position.
Vector fromInternalCoord (const int x, const int y) const
Vector fromInternalCoord (const float x, const float y) const
float getInformationQuantity () const
int getInternalHeight () const
int getInternalStartX () const
int getInternalStartY () const
int getInternalWidth () const
Vector getMaxCoord () const
Vector getMinCoord () const
unsigned getRayCount () const
float getResolution () const
Vector getSize () const
Vector getSlope (const Vector &pos, const float limit=65536.f) const
 Return slope at pos, with bi-linear interpolated.
Value getValue (const Vector &pos) const
 Return value at pos, with bi-linear interpolation.
Value getValueNearest (const Vector &pos) const
 Return value at pos, sampled without any interpolation.
 GridMap (Group *gridMapGroup, const Value defaultValue)
 GridMap (const float resolution, const Value defaultValue, Group *gridMapGroup=0)
 Construct using resolution and default value and a null size, optionally initiate group.
 GridMap (const float resolution, const float startX, const float startY, const float width, const float height, const Value defaultValue, Group *gridMapGroup=0)
 Construct using user-provided demonsion, optionally initiate group.
 GridMap (const std::string &pgmFileName, const float resolution, const Value defaultValue, Group *gridMapGroup=0)
 Construct using resolution and data from an external file, optionally initiate group.
 GridMap (const GridMap &that)
void invert ()
 Invert the values of every pixel, if the value is -32768, map it to +32767.
bool isWithinBounds (const Vector &pos) const
bool isWithinBoundsInternal (const int x, const int y) const
Labels labelize (const Value threshold)
 Label this map, if value of a pixel is bigger then threshold, take into consideration for label. Return the vector of labels center of mass.
template<typename F >
void lineScan (const Vector &start, const Vector &stop, F &functor, const Value &value=0)
template<typename F >
void lineScan (const Vector &start, const Vector &stop, F &functor, const Value texture[], const unsigned textureLength)
GridMapoperator= (const GridMap &that)
void rayCountReset ()
void setNearestValue (const Vector &pos, const Value value)
 Set value at pos, sampled without any interpolation.
void threshold (const Value threshold, const Value lowValue, const Value highValue)
 Apply threshold to every value of the map; if it is below threshold, set to lowValue, else set to highValue.
void toInternalCoord (const Vector &pos, int &internalX, int &internalY) const
void toInternalCoordSuperSampled (const Vector &pos, const int superSampleRes, int &internalX, int &internalY) const
nav_msgs::OccupancyGrid toOccupancyGrid (const std::string &frame_id, const GridMap *knownMap=0) const
 Return a ROS nav_msgs/OccupancyGrid message.
void toPGMFile (const std::string &fileName, const int divisorToPGM=256) const
template<typename Op >
void unaryOperation (Op &op)
 Map to map generic unary operation.
template<typename Op >
void unaryOperation (const Op &op)
 Map to map generic unary operation, overload for const op.
 ~GridMap ()

Static Public Member Functions

static Value saturatedValueFromInt (int v)

Protected Types

typedef std::vector< ValueValues

Protected Member Functions

void dilateN (const unsigned amount, const int lookup[][2], const size_t lookupSize, const unsigned delta)
void erodeN (const unsigned amount, const int lookup[][2], const size_t lookupSize, const unsigned delta)
bool extendMap (int xMin, int yMin, int xMax, int yMax)
void extendMapInternal (int deltaStartX, int deltaStartY, int newWidth, int newHeight)
void initiateMapGroup ()

Protected Attributes

Value defaultValue
int height
GroupmapGroup
unsigned rayCount
float resolution
int startX
int startY
Values values
int width

Detailed Description

Definition at line 12 of file grid-map.h.


Member Typedef Documentation

Definition at line 17 of file grid-map.h.

typedef boost::tuple<unsigned, Vector, unsigned> GridMap::Label

A label has a center of mass, and an area.

Definition at line 117 of file grid-map.h.

typedef std::vector<Label> GridMap::Labels

All found labels.

Definition at line 119 of file grid-map.h.

typedef signed short GridMap::Value

Definition at line 15 of file grid-map.h.

typedef std::vector<Value> GridMap::Values [protected]

Definition at line 33 of file grid-map.h.

typedef Eigen::Vector2f GridMap::Vector

Definition at line 16 of file grid-map.h.

typedef std::pair<Vector, Vector> GridMap::VectorPair

A pair of vectors.

Definition at line 123 of file grid-map.h.


Constructor & Destructor Documentation

GridMap::GridMap ( Group gridMapGroup,
const Value  defaultValue 
)

Definition at line 18 of file grid-map.cpp.

GridMap::GridMap ( const float  resolution,
const Value  defaultValue,
Group gridMapGroup = 0 
)

Construct using resolution and default value and a null size, optionally initiate group.

Definition at line 42 of file grid-map.cpp.

GridMap::GridMap ( const float  resolution,
const float  startX,
const float  startY,
const float  width,
const float  height,
const Value  defaultValue,
Group gridMapGroup = 0 
)

Construct using user-provided demonsion, optionally initiate group.

Definition at line 56 of file grid-map.cpp.

GridMap::GridMap ( const std::string &  pgmFileName,
const float  resolution,
const Value  defaultValue,
Group gridMapGroup = 0 
)

Construct using resolution and data from an external file, optionally initiate group.

Definition at line 71 of file grid-map.cpp.

GridMap::GridMap ( const GridMap that)

Definition at line 117 of file grid-map.cpp.

Definition at line 150 of file grid-map.cpp.


Member Function Documentation

void GridMap::addNearestValueSaturated ( const Vector pos,
const int  delta 
)

Add delta ta value at pos, saturated but sampled without any interpolation.

Definition at line 207 of file grid-map.cpp.

GridMap::Value & GridMap::atInternalCoord ( const int  x,
const int  y 
)

Definition at line 157 of file grid-map.cpp.

GridMap::Value GridMap::atInternalCoord ( const int  x,
const int  y 
) const

Definition at line 163 of file grid-map.cpp.

template<typename Op >
void GridMap::binaryOperation ( const GridMap that,
Op &  op 
) [inline]

Map to map generic binary operation.

Definition at line 146 of file grid-map.h.

template<typename Op >
void GridMap::binaryOperation ( const GridMap that,
const Op &  op 
) [inline]

Map to map generic binary operation, overload for const op.

Definition at line 155 of file grid-map.h.

GridMap GridMap::buildGradient ( const Vector goal,
bool &  isSuccess 
) const

Build a gradient to a goal, and avoid obstacles (see Philippsen TR E* 06)

Assume that this contains the speed map, where 0 corresponds to obstacles and 32767 maximum speed. Gradients have 64 subsampling resolution.

Definition at line 947 of file grid-map.cpp.

GridMap::VectorPair GridMap::closestPoints ( const Label area0,
const Label area1,
const unsigned  monteCarloSteps = 100 
) const

Return approximately the closest points between two areas.

Definition at line 886 of file grid-map.cpp.

void GridMap::dilate4 ( const unsigned  amount,
const unsigned  delta = 0 
)

Dilate the map of amount pixels, taking into account the four N,S,W,E pixels around each pixel.

Definition at line 608 of file grid-map.cpp.

void GridMap::dilate8 ( const unsigned  amount,
const unsigned  delta = 0 
)

Dilate the map of amount pixels, taking into account all the eight pixels around each pixel.

Definition at line 613 of file grid-map.cpp.

void GridMap::dilateN ( const unsigned  amount,
const int  lookup[][2],
const size_t  lookupSize,
const unsigned  delta 
) [protected]

Definition at line 618 of file grid-map.cpp.

void GridMap::erode4 ( const unsigned  amount,
const unsigned  delta = 0 
)

Erode the map of amount pixels, taking into account the four N,S,W,E pixels around each pixel.

Definition at line 638 of file grid-map.cpp.

void GridMap::erode8 ( const unsigned  amount,
const unsigned  delta = 0 
)

Erode the map of amount pixels, taking into account all the eight pixels around each pixel.

Definition at line 643 of file grid-map.cpp.

void GridMap::erodeN ( const unsigned  amount,
const int  lookup[][2],
const size_t  lookupSize,
const unsigned  delta 
) [protected]

Definition at line 648 of file grid-map.cpp.

bool GridMap::extendMap ( int  xMin,
int  yMin,
int  xMax,
int  yMax 
) [protected]

Definition at line 462 of file grid-map.cpp.

void GridMap::extendMapInternal ( int  deltaStartX,
int  deltaStartY,
int  newWidth,
int  newHeight 
) [protected]

Definition at line 538 of file grid-map.cpp.

void GridMap::extendToFit ( const Vector pos)

Extend to fit position.

Definition at line 273 of file grid-map.cpp.

GridMap::Vector GridMap::fromInternalCoord ( const int  x,
const int  y 
) const

Definition at line 169 of file grid-map.cpp.

GridMap::Vector GridMap::fromInternalCoord ( const float  x,
const float  y 
) const

Definition at line 175 of file grid-map.cpp.

Definition at line 1094 of file grid-map.cpp.

int GridMap::getInternalHeight ( ) const [inline]

Definition at line 69 of file grid-map.h.

int GridMap::getInternalStartX ( ) const [inline]

Definition at line 66 of file grid-map.h.

int GridMap::getInternalStartY ( ) const [inline]

Definition at line 67 of file grid-map.h.

int GridMap::getInternalWidth ( ) const [inline]

Definition at line 68 of file grid-map.h.

Vector GridMap::getMaxCoord ( ) const [inline]

Definition at line 73 of file grid-map.h.

Vector GridMap::getMinCoord ( ) const [inline]

Definition at line 72 of file grid-map.h.

unsigned GridMap::getRayCount ( ) const [inline]

Definition at line 165 of file grid-map.h.

float GridMap::getResolution ( ) const [inline]

Definition at line 70 of file grid-map.h.

Vector GridMap::getSize ( ) const [inline]

Definition at line 74 of file grid-map.h.

GridMap::Vector GridMap::getSlope ( const Vector pos,
const float  limit = 65536.f 
) const

Return slope at pos, with bi-linear interpolated.

Definition at line 236 of file grid-map.cpp.

GridMap::Value GridMap::getValue ( const Vector pos) const

Return value at pos, with bi-linear interpolation.

Definition at line 215 of file grid-map.cpp.

Return value at pos, sampled without any interpolation.

Definition at line 193 of file grid-map.cpp.

void GridMap::initiateMapGroup ( ) [protected]

Definition at line 107 of file grid-map.cpp.

void GridMap::invert ( )

Invert the values of every pixel, if the value is -32768, map it to +32767.

Definition at line 564 of file grid-map.cpp.

bool GridMap::isWithinBounds ( const Vector pos) const

Definition at line 266 of file grid-map.cpp.

bool GridMap::isWithinBoundsInternal ( const int  x,
const int  y 
) const

Definition at line 261 of file grid-map.cpp.

GridMap::Labels GridMap::labelize ( const Value  threshold)

Label this map, if value of a pixel is bigger then threshold, take into consideration for label. Return the vector of labels center of mass.

Definition at line 697 of file grid-map.cpp.

template<typename F >
void GridMap::lineScan ( const Vector start,
const Vector stop,
F &  functor,
const Value value = 0 
)

Definition at line 322 of file grid-map.cpp.

template<typename F >
void GridMap::lineScan ( const Vector start,
const Vector stop,
F &  functor,
const Value  texture[],
const unsigned  textureLength 
)

Definition at line 329 of file grid-map.cpp.

GridMap & GridMap::operator= ( const GridMap that)

Definition at line 132 of file grid-map.cpp.

void GridMap::rayCountReset ( ) [inline]

Definition at line 164 of file grid-map.h.

static Value GridMap::saturatedValueFromInt ( int  v) [inline, static]

Definition at line 62 of file grid-map.h.

void GridMap::setNearestValue ( const Vector pos,
const Value  value 
)

Set value at pos, sampled without any interpolation.

Definition at line 200 of file grid-map.cpp.

void GridMap::threshold ( const Value  threshold,
const Value  lowValue,
const Value  highValue 
)

Apply threshold to every value of the map; if it is below threshold, set to lowValue, else set to highValue.

Definition at line 576 of file grid-map.cpp.

void GridMap::toInternalCoord ( const Vector pos,
int &  internalX,
int &  internalY 
) const

Definition at line 181 of file grid-map.cpp.

void GridMap::toInternalCoordSuperSampled ( const Vector pos,
const int  superSampleRes,
int &  internalX,
int &  internalY 
) const

Definition at line 187 of file grid-map.cpp.

nav_msgs::OccupancyGrid GridMap::toOccupancyGrid ( const std::string &  frame_id,
const GridMap knownMap = 0 
) const

Return a ROS nav_msgs/OccupancyGrid message.

Definition at line 280 of file grid-map.cpp.

void GridMap::toPGMFile ( const std::string &  fileName,
const int  divisorToPGM = 256 
) const

Definition at line 1103 of file grid-map.cpp.

template<typename Op >
void GridMap::unaryOperation ( Op &  op) [inline]

Map to map generic unary operation.

Definition at line 132 of file grid-map.h.

template<typename Op >
void GridMap::unaryOperation ( const Op &  op) [inline]

Map to map generic unary operation, overload for const op.

Definition at line 139 of file grid-map.h.


Member Data Documentation

Definition at line 38 of file grid-map.h.

int GridMap::height [protected]

Definition at line 37 of file grid-map.h.

Group* GridMap::mapGroup [protected]

Definition at line 40 of file grid-map.h.

unsigned GridMap::rayCount [mutable, protected]

Definition at line 41 of file grid-map.h.

float GridMap::resolution [protected]

Definition at line 35 of file grid-map.h.

int GridMap::startX [protected]

Definition at line 36 of file grid-map.h.

int GridMap::startY [protected]

Definition at line 36 of file grid-map.h.

Values GridMap::values [protected]

Definition at line 39 of file grid-map.h.

int GridMap::width [protected]

Definition at line 37 of file grid-map.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


gridmap
Author(s): Stéphane Magnenat
autogenerated on Tue Nov 20 2012 16:28:24