Classes |
| struct | occupancy_grid_utils::Cell |
Namespaces |
| namespace | occupancy_grid_utils |
Typedefs |
| typedef int16_t | occupancy_grid_utils::coord_t |
| typedef uint32_t | occupancy_grid_utils::index_t |
Functions |
| geometry_msgs::Point | occupancy_grid_utils::cellCenter (const nav_msgs::MapMetaData &info, const Cell &c) |
| | Return center of a cell.
|
| index_t | occupancy_grid_utils::cellIndex (const nav_msgs::MapMetaData &info, const Cell &c) |
| | Returns the index of a cell.
|
| geometry_msgs::Polygon | occupancy_grid_utils::cellPolygon (const nav_msgs::MapMetaData &info, const Cell &c) |
| | Return polygon corresponding to a cell.
|
| 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) |
| | Returns cell corresponding to index.
|
| tf::Transform | occupancy_grid_utils::mapToWorld (const nav_msgs::MapMetaData &info) |
| std::ostream & | occupancy_grid_utils::operator<< (std::ostream &str, const Cell &c) |
| Cell | occupancy_grid_utils::pointCell (const nav_msgs::MapMetaData &info, const geometry_msgs::Point &p) |
| | Returns cell corresponding to a point.
|
| index_t | occupancy_grid_utils::pointIndex (const nav_msgs::MapMetaData &info, const geometry_msgs::Point &p) |
| | Returns index of a point.
|
| void | occupancy_grid_utils::verifyDataSize (const nav_msgs::OccupancyGrid &g) |
| | Verify that data vector has the right size, throw DataSizeException otherwise.
|
| bool | occupancy_grid_utils::withinBounds (const nav_msgs::MapMetaData &info, const Cell &c) |
| | Check if a cell is on the grid.
|
| bool | occupancy_grid_utils::withinBounds (const nav_msgs::MapMetaData &info, const geometry_msgs::Point &p) |
| | Check if a point is on the grid.
|
| tf::Transform | occupancy_grid_utils::worldToMap (const nav_msgs::MapMetaData &info) |
Variables |
| const int8_t | occupancy_grid_utils::OCCUPIED = 100 |
| const int8_t | occupancy_grid_utils::UNKNOWN = 255 |
| const int8_t | occupancy_grid_utils::UNOCCUPIED = 0 |