#include <occupancy_grid_utils/exceptions.h>#include <boost/format.hpp>#include <stdexcept>#include <geometry_msgs/Point.h>#include <string>#include <vector>#include <ostream>#include "ros/serialization.h"#include "ros/builtin_message_traits.h"#include "ros/message_operations.h"#include "ros/message.h"#include "ros/time.h"#include "std_msgs/Header.h"#include "geometry_msgs/Quaternion.h"#include "geometry_msgs/Vector3.h"#include "geometry_msgs/Pose.h"#include "btMatrix3x3.h"#include "ros/console.h"#include <nav_msgs/OccupancyGrid.h>#include <ros/assert.h>#include <cstdlib>

Go to the source code of this file.
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. | |
| 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 |
General utilities for coordinate conversions
Definition in file coordinate_conversions.h.