#include <set>#include <iterator>#include <limits>#include <cmath>#include <ros/assert.h>#include <nav_msgs/OccupancyGrid.h>#include <tf/transform_datatypes.h>#include <boost/foreach.hpp>#include <occupancy_grid_utils/coordinate_conversions.h>

Go to the source code of this file.
Namespaces | |
| namespace | occupancy_grid_utils |
Defines | |
| #define | POLYGON_BOUND(polygon, minmax, xy) |
Functions | |
| template<typename ForwardIt > | |
| void | occupancy_grid_utils::combineGrids (ForwardIt first, ForwardIt last, double resolution, nav_msgs::OccupancyGrid &result) |
| Combines a set of grids. | |
| 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. | |
| nav_msgs::OccupancyGrid::Ptr | occupancy_grid_utils::combineGrids (const std::vector< nav_msgs::OccupancyGrid::ConstPtr > &grids, double resolution) |
| nav_msgs::OccupancyGrid::Ptr | occupancy_grid_utils::combineGrids (const std::vector< nav_msgs::OccupancyGrid::ConstPtr > &grids) |
| template<typename ForwardIt > | |
| nav_msgs::MapMetaData | occupancy_grid_utils::getCombinedGridInfo (ForwardIt first, ForwardIt last, const double resolution) |
| std::set< Cell > | occupancy_grid_utils::intersectingCells (const nav_msgs::MapMetaData &info, const nav_msgs::MapMetaData &info2, const Cell &cell2) |
| geometry_msgs::Pose | occupancy_grid_utils::transformPose (const tf::Pose trans, const geometry_msgs::Pose p) |
Combining overlapping grids
Definition in file combine_grids.h.
| #define POLYGON_BOUND | ( | polygon, | |
| minmax, | |||
| xy | |||
| ) |
static_cast<double>(std::minmax(polygon.points[0].xy, \ std::minmax(polygon.points[1].xy, \ std::minmax(polygon.points[2].xy, polygon.points[3].xy))))
Definition at line 68 of file combine_grids.h.