#include "shortest_path_result.h"#include <occupancy_grid_utils/coordinate_conversions.h>#include <occupancy_grid_utils/ray_tracer.h>#include <occupancy_grid_utils/file.h>#include <occupancy_grid_utils/geometry.h>#include <occupancy_grid_utils/shortest_path.h>#include <boost/python.hpp>#include <boost/python/suite/indexing/vector_indexing_suite.hpp>
Go to the source code of this file.
Namespaces | |
| namespace | occupancy_grid_utils |
Defines | |
| #define | BOOST_PYTHON_VECTOR(t, name) |
| #define | DEFINE_DUMMY_EQUALITY(ns, t) |
Functions | |
| void | occupancy_grid_utils::allocateGrid (nav_msgs::OccupancyGrid &grid) |
| occupancy_grid_utils::BOOST_PYTHON_MODULE (occupancy_grid_utils) | |
| vector< Cell > | occupancy_grid_utils::cellVectorInConvexPolygon (const nm::MapMetaData &info, const gm::Polygon &p) |
| void | occupancy_grid_utils::exportRosMessages () |
| void | occupancy_grid_utils::exportSTL () |
| int | occupancy_grid_utils::getCell (const nav_msgs::OccupancyGrid &grid, const Cell &c) |
| nm::OccupancyGrid::Ptr | occupancy_grid_utils::loadGrid1 (const string &fname) |
| nm::OccupancyGrid::Ptr | occupancy_grid_utils::loadGrid2 (const string &fname, const double resolution) |
| nm::OccupancyGrid::Ptr | occupancy_grid_utils::loadGrid3 (const string &fname, const double res, const gm::Pose &p) |
| void | occupancy_grid_utils::setCell (nav_msgs::OccupancyGrid &grid, const Cell &c, const int x) |
| sm::LaserScan::Ptr | occupancy_grid_utils::simulateRangeScan3 (const nm::OccupancyGrid &grid, const gm::Pose &sensor_pose, const sm::LaserScan &scanner_info) |
| sm::LaserScan::Ptr | occupancy_grid_utils::simulateRangeScan4 (const nm::OccupancyGrid &grid, const gm::Pose &sensor_pose, const sm::LaserScan &scanner_info, const bool unknown_obstacles) |
| ResultPtr | occupancy_grid_utils::sssp1 (const nav_msgs::OccupancyGrid &g, const Cell &start, const double max_dist) |
| double | occupancy_grid_utils::ssspDistance (ResultPtr res, const Cell &dest) |
| bool | occupancy_grid_utils::withinBoundsCell (const nm::MapMetaData &info, const Cell &c) |
| bool | occupancy_grid_utils::withinBoundsPoint (const nm::MapMetaData &info, const gm::Point &p) |
Boost python exports for occupancy_grid_utils library
Definition in file boost_python_exports.cpp.
| #define BOOST_PYTHON_VECTOR | ( | t, | |
| name | |||
| ) |
boost::python::class_<std::vector<t> >(name) \ .def(boost::python::vector_indexing_suite<std::vector<t> >())
Definition at line 49 of file boost_python_exports.cpp.
| #define DEFINE_DUMMY_EQUALITY | ( | ns, | |
| t | |||
| ) |
namespace ns { \ bool operator== (const t& x1, const t& x2) { return false; } \ }
Definition at line 53 of file boost_python_exports.cpp.