Classes | Typedefs | Functions | Variables
occupancy_grid_utils Namespace Reference

Classes

struct  Cell

Typedefs

typedef int16_t coord_t
typedef uint32_t index_t

Functions

geometry_msgs::Point cellCenter (const nav_msgs::MapMetaData &info, const Cell &c)
 Return center of a cell.
index_t cellIndex (const nav_msgs::MapMetaData &info, const Cell &c)
 Returns the index of a cell.
gm::Polygon cellPolygon (const nm::MapMetaData &info, const Cell &c)
geometry_msgs::Polygon cellPolygon (const nav_msgs::MapMetaData &info, const Cell &c)
 Return polygon corresponding to a cell.
bool cellsIntersect (const nm::MapMetaData &info1, const Cell &c1, const nm::MapMetaData &info2, const Cell &c2)
template<typename ForwardIt >
void combineGrids (ForwardIt first, ForwardIt last, double resolution, nav_msgs::OccupancyGrid &result)
 Combines a set of grids.
template<typename ForwardIt >
void combineGrids (ForwardIt first, ForwardIt last, nav_msgs::OccupancyGrid &result)
 Version of combineGrids that uses the resolution of the first grid.
nav_msgs::OccupancyGrid::Ptr combineGrids (const std::vector< nav_msgs::OccupancyGrid::ConstPtr > &grids, double resolution)
nav_msgs::OccupancyGrid::Ptr combineGrids (const std::vector< nav_msgs::OccupancyGrid::ConstPtr > &grids)
bool containsVertex (const nm::MapMetaData &info, const Cell &c, const gm::Polygon &poly)
gm::Polygon expandPolygon (const gm::Polygon &p, const double r)
template<typename ForwardIt >
nav_msgs::MapMetaData getCombinedGridInfo (ForwardIt first, ForwardIt last, const double resolution)
gm::Polygon gridPolygon (const nm::MapMetaData &info)
geometry_msgs::Polygon gridPolygon (const nav_msgs::MapMetaData &info)
 Return polygon corresponding to grid bounds.
Cell indexCell (const nav_msgs::MapMetaData &info, index_t ind)
 Returns cell corresponding to index.
std::set< CellintersectingCells (const nav_msgs::MapMetaData &info, const nav_msgs::MapMetaData &info2, const Cell &cell2)
set< CellintersectingCells (const nm::MapMetaData &info, const nm::MapMetaData &info2, const Cell &cell2)
tf::Transform mapToWorld (const nav_msgs::MapMetaData &info)
std::ostream & operator<< (std::ostream &str, const Cell &c)
Cell point32Cell (const nm::MapMetaData &info, const gm::Point32 &p)
Cell pointCell (const nav_msgs::MapMetaData &info, const geometry_msgs::Point &p)
 Returns cell corresponding to a point.
index_t pointIndex (const nav_msgs::MapMetaData &info, const geometry_msgs::Point &p)
 Returns index of a point.
geometry_msgs::Pose transformPose (const tf::Pose trans, const geometry_msgs::Pose p)
gm::Pose transformPose (const tf::Pose trans, const gm::Pose p)
void verifyDataSize (const nm::OccupancyGrid &g)
void verifyDataSize (const nav_msgs::OccupancyGrid &g)
 Verify that data vector has the right size.
bool withinBounds (const nav_msgs::MapMetaData &info, const geometry_msgs::Point &p)
 Check if a point is on the grid.
bool withinBounds (const nav_msgs::MapMetaData &info, const Cell &c)
 Check if a cell is on the grid.
tf::Transform worldToMap (const nav_msgs::MapMetaData &info)

Variables

const int8_t OCCUPIED = 100
const int8_t UNKNOWN = -1
const int8_t UNOCCUPIED = 0

Typedef Documentation

Definition at line 63 of file coordinate_conversions.h.

Definition at line 62 of file coordinate_conversions.h.


Function Documentation

geometry_msgs::Point occupancy_grid_utils::cellCenter ( const nav_msgs::MapMetaData &  info,
const Cell &  c 
) [inline]

Return center of a cell.

Definition at line 170 of file coordinate_conversions.h.

index_t occupancy_grid_utils::cellIndex ( const nav_msgs::MapMetaData &  info,
const Cell &  c 
) [inline]

Returns the index of a cell.

Exceptions:
std::out_of_rangeif cell isn't within grid bounds

Definition at line 125 of file coordinate_conversions.h.

gm::Polygon occupancy_grid_utils::cellPolygon ( const nm::MapMetaData &  info,
const Cell &  c 
)

Definition at line 49 of file coordinate_conversions.cpp.

geometry_msgs::Polygon occupancy_grid_utils::cellPolygon ( const nav_msgs::MapMetaData &  info,
const Cell &  c 
)

Return polygon corresponding to a cell.

bool occupancy_grid_utils::cellsIntersect ( const nm::MapMetaData &  info1,
const Cell &  c1,
const nm::MapMetaData &  info2,
const Cell &  c2 
) [inline]

Definition at line 81 of file combine_grids.cpp.

template<typename ForwardIt >
void occupancy_grid_utils::combineGrids ( ForwardIt  first,
ForwardIt  last,
double  resolution,
nav_msgs::OccupancyGrid &  result 
)

Combines a set of grids.

The resulting grid's origin will be a translated version of grid 1's origin, with resolution resolution.

All empty grids will be skipped.

The policy for combination is that for each cell, we look at each grid cell that intersects it and consider their values. Map these to integers, where everything above OCCUPIED (100) goes to -1. Then take the max. If there are no intersecting cells, value is -1.

Assumes all grids lie on the xy plane, and will fail in weird ways if that's not true

Definition at line 178 of file combine_grids.h.

template<typename ForwardIt >
void occupancy_grid_utils::combineGrids ( ForwardIt  first,
ForwardIt  last,
nav_msgs::OccupancyGrid &  result 
)

Version of combineGrids that uses the resolution of the first grid.

Definition at line 220 of file combine_grids.h.

nav_msgs::OccupancyGrid::Ptr occupancy_grid_utils::combineGrids ( const std::vector< nav_msgs::OccupancyGrid::ConstPtr > &  grids,
double  resolution 
)

Version of combineGrids that uses shared_ptr

you should use combineGrids with raw pointers instead, which saves reference counting

Deprecated:

Definition at line 151 of file combine_grids.cpp.

nav_msgs::OccupancyGrid::Ptr occupancy_grid_utils::combineGrids ( const std::vector< nav_msgs::OccupancyGrid::ConstPtr > &  grids)

Version of combineGrids that uses shared_ptr

you should use combineGrids with raw pointers instead, which saves reference counting

Deprecated:

Definition at line 165 of file combine_grids.cpp.

bool occupancy_grid_utils::containsVertex ( const nm::MapMetaData &  info,
const Cell &  c,
const gm::Polygon &  poly 
) [inline]

Definition at line 71 of file combine_grids.cpp.

gm::Polygon occupancy_grid_utils::expandPolygon ( const gm::Polygon &  p,
const double  r 
) [inline]

Definition at line 88 of file combine_grids.cpp.

template<typename ForwardIt >
nav_msgs::MapMetaData occupancy_grid_utils::getCombinedGridInfo ( ForwardIt  first,
ForwardIt  last,
const double  resolution 
)

Definition at line 118 of file combine_grids.h.

gm::Polygon occupancy_grid_utils::gridPolygon ( const nm::MapMetaData &  info)

Definition at line 68 of file coordinate_conversions.cpp.

geometry_msgs::Polygon occupancy_grid_utils::gridPolygon ( const nav_msgs::MapMetaData &  info)

Return polygon corresponding to grid bounds.

Cell occupancy_grid_utils::indexCell ( const nav_msgs::MapMetaData &  info,
index_t  ind 
) [inline]

Returns cell corresponding to index.

Definition at line 133 of file coordinate_conversions.h.

std::set<Cell> occupancy_grid_utils::intersectingCells ( const nav_msgs::MapMetaData &  info,
const nav_msgs::MapMetaData &  info2,
const Cell &  cell2 
)
set<Cell> occupancy_grid_utils::intersectingCells ( const nm::MapMetaData &  info,
const nm::MapMetaData &  info2,
const Cell &  cell2 
)

Definition at line 113 of file combine_grids.cpp.

tf::Transform occupancy_grid_utils::mapToWorld ( const nav_msgs::MapMetaData &  info) [inline]

Definition at line 141 of file coordinate_conversions.h.

std::ostream& occupancy_grid_utils::operator<< ( std::ostream &  str,
const Cell &  c 
) [inline]

Definition at line 192 of file coordinate_conversions.h.

Cell occupancy_grid_utils::point32Cell ( const nm::MapMetaData &  info,
const gm::Point32 &  p 
) [inline]

Definition at line 61 of file combine_grids.cpp.

Cell occupancy_grid_utils::pointCell ( const nav_msgs::MapMetaData &  info,
const geometry_msgs::Point p 
) [inline]

Returns cell corresponding to a point.

The z coordinate of the point is ignored.

Definition at line 155 of file coordinate_conversions.h.

index_t occupancy_grid_utils::pointIndex ( const nav_msgs::MapMetaData &  info,
const geometry_msgs::Point p 
) [inline]

Returns index of a point.

Exceptions:
std::out_of_rangeif point isn't within grid bounds

Ignores z coordinate of point

Definition at line 164 of file coordinate_conversions.h.

Definition at line 140 of file combine_grids.cpp.

void occupancy_grid_utils::verifyDataSize ( const nm::OccupancyGrid &  g)

Definition at line 87 of file coordinate_conversions.cpp.

void occupancy_grid_utils::verifyDataSize ( const nav_msgs::OccupancyGrid &  g)

Verify that data vector has the right size.

Exceptions:
std::logic_errorotherwise
bool occupancy_grid_utils::withinBounds ( const nav_msgs::MapMetaData &  info,
const geometry_msgs::Point p 
) [inline]

Check if a point is on the grid.

Definition at line 199 of file coordinate_conversions.h.

bool occupancy_grid_utils::withinBounds ( const nav_msgs::MapMetaData &  info,
const Cell &  c 
) [inline]

Check if a cell is on the grid.

Definition at line 205 of file coordinate_conversions.h.

tf::Transform occupancy_grid_utils::worldToMap ( const nav_msgs::MapMetaData &  info) [inline]

Definition at line 149 of file coordinate_conversions.h.


Variable Documentation

const int8_t occupancy_grid_utils::OCCUPIED = 100

Definition at line 78 of file coordinate_conversions.h.

const int8_t occupancy_grid_utils::UNKNOWN = -1

Definition at line 79 of file coordinate_conversions.h.

Definition at line 77 of file coordinate_conversions.h.



map_merge
Author(s): Jiri Horner
autogenerated on Sun Mar 26 2017 03:48:10