Namespaces | |
namespace | msg |
Classes | |
struct | Cell |
struct | CellOutOfBoundsException |
Exception for Cell off map. More... | |
struct | GridUtilsException |
Base class for exceptions from this package. More... | |
struct | InflationQueueItem |
struct | LocalizedCloud_ |
struct | NavigationFunction_ |
struct | OverlayClouds_ |
struct | PointOutOfBoundsException |
Exception for point off map. More... | |
struct | PQItem |
struct | QueueItem |
class | RayTraceIterator |
struct | ShortestPathResult |
struct | TerminationCondition |
Termination condition for shortest path search max_dist is a distance such that as soon as we see a cell with greater than this distance, we stop goals is a set such that once we've expanded all the cells in this set, we stop. More... | |
Typedefs | |
typedef std::pair< Path, double > | AStarResult |
typedef std::set< Cell > | Cells |
typedef int16_t | coord_t |
typedef boost::shared_ptr < nm::OccupancyGrid const > | GridConstPtr |
typedef boost::shared_ptr < nm::OccupancyGrid > | GridPtr |
typedef uint32_t | index_t |
typedef ::occupancy_grid_utils::LocalizedCloud_ < std::allocator< void > > | LocalizedCloud |
typedef boost::shared_ptr < ::occupancy_grid_utils::LocalizedCloud const > | LocalizedCloudConstPtr |
typedef boost::shared_ptr < ::occupancy_grid_utils::LocalizedCloud > | LocalizedCloudPtr |
typedef ::occupancy_grid_utils::NavigationFunction_ < std::allocator< void > > | NavigationFunction |
typedef boost::shared_ptr < ::occupancy_grid_utils::NavigationFunction const > | NavigationFunctionConstPtr |
typedef boost::shared_ptr < ::occupancy_grid_utils::NavigationFunction > | NavigationFunctionPtr |
typedef ::occupancy_grid_utils::OverlayClouds_ < std::allocator< void > > | OverlayClouds |
typedef boost::shared_ptr < ::occupancy_grid_utils::OverlayClouds const > | OverlayCloudsConstPtr |
typedef boost::shared_ptr < ::occupancy_grid_utils::OverlayClouds > | OverlayCloudsPtr |
typedef std::vector< Cell > | Path |
typedef std::pair < RayTraceIterator, RayTraceIterator > | RayTraceIterRange |
typedef boost::shared_ptr < const ShortestPathResult > | ResultPtr |
Functions | |
void | addCloud (OverlayClouds *overlay, LocalizedCloud::ConstPtr cloud, const int inc) |
void | addCloud (OverlayClouds *overlay, LocalizedCloud::ConstPtr cloud) |
Raytrace a cloud onto grid in overlay. | |
void | addKnownFreePoint (OverlayClouds *overlay, const gm::Point &p, const double r) |
void | addKnownFreePoint (OverlayClouds *overlay, const geometry_msgs::Point &p, double r) |
Assert that a square centered at this point with side 2*r contains no obstacles. | |
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. | |
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) |
bool | cellWithinBounds (const nm::MapMetaData &info, const Cell &c) |
GridPtr | combineGrids (const vector< GridConstPtr > &grids) |
GridPtr | combineGrids (const vector< GridConstPtr > &grids, const double resolution) |
nav_msgs::OccupancyGrid::Ptr | combineGrids (const std::vector< nav_msgs::OccupancyGrid::ConstPtr > &grids) |
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) |
Combines a set of grids. | |
bool | containsVertex (const nm::MapMetaData &info, const Cell &c, const gm::Polygon &poly) |
OverlayClouds | createCloudOverlay (const nm::OccupancyGrid &grid, const std::string &frame_id, double occupancy_threshold, double max_distance, double min_pass_through) |
OverlayClouds | createCloudOverlay (const nav_msgs::OccupancyGrid &grid, const std::string &frame_id, double occupancy_threshold=DEFAULT_OCCUPANCY_THRESHOLD, double max_distance=DEFAULT_MAX_DISTANCE, double min_pass_through=DEFAULT_MIN_PASS_THROUGH) |
Create a cloud overlay object to which clouds can then be added The returned (ros message) object should only be accessed using the api below. | |
int8_t | determineOccupancy (const unsigned hit_count, const unsigned pass_through_count, const double occupancy_threshold, const double min_pass_through) |
boost::optional< double > | distance (ResultPtr shortest_path_result, const Cell &dest) |
From result of single-source shortest paths, extract distance to some destination. | |
double | euclideanDistance (const gm::Point &p1, const gm::Point &p2) |
gm::Polygon | expandPolygon (const gm::Polygon &p, const double r) |
boost::optional< Path > | extractPath (ResultPtr shortest_path_result, const Cell &dest) |
Extract a path from the result of single-source shortest paths. | |
nm::MapMetaData | getCombinedGridInfo (const vector< GridConstPtr > &grids, const double resolution) |
nav_msgs::OccupancyGrid::Ptr | getGrid (const OverlayClouds &overlay) |
Get the current grid. It's fine to modify the returned object. | |
nav_msgs::MapMetaData | gridInfo (const OverlayClouds &overlay) |
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. | |
GridPtr | inflateObstacles (const nm::OccupancyGrid &g, const double r, const bool allow_unknown) |
nav_msgs::OccupancyGrid::Ptr | inflateObstacles (const nav_msgs::OccupancyGrid &g, double r, bool allow_unknown=false) |
Inflate obstacles in a grid. | |
set< Cell > | intersectingCells (const nm::MapMetaData &info, const nm::MapMetaData &info2, const Cell &cell2) |
double | manhattanHeuristic (const Cell &c1, const Cell &c2) |
tf::Transform | mapToWorld (const nav_msgs::MapMetaData &info) |
double | maxX (const nm::MapMetaData &info) |
double | maxY (const nm::MapMetaData &info) |
double | minX (const nm::MapMetaData &info) |
double | minY (const nm::MapMetaData &info) |
bool | myGt (const signed char x, const signed char y) |
bool | operator< (const QueueItem &i1, const QueueItem &i2) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::occupancy_grid_utils::OverlayClouds_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::occupancy_grid_utils::NavigationFunction_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::occupancy_grid_utils::LocalizedCloud_< ContainerAllocator > &v) |
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. | |
RayTraceIterRange | rayTrace (const nm::MapMetaData &info, const gm::Point &p1, const gm::Point &p2, bool project_onto_grid, bool project_source_onto_grid) |
RayTraceIterRange | rayTrace (const Cell &c1, const Cell &c2) |
RayTraceIterRange | rayTrace (const nav_msgs::MapMetaData &info, const geometry_msgs::Point &p1, const geometry_msgs::Point &p2, bool project_target_onto_grid=false, bool project_source_onto_grid=false) |
Returns an iterator range over the cells on the line segment between two points (inclusive). | |
optional< Cell > | rayTraceOntoGrid (const nm::MapMetaData &info, const Cell &c1, const Cell &c2) |
void | removeCloud (OverlayClouds *overlay, LocalizedCloud::ConstPtr cloud) |
Effectively subtract a cloud (which was presumably previously added), by subtracting rather than adding counts, in overlay. | |
void | resetCounts (OverlayClouds *overlay) |
optional< AStarResult > | shortestPath (const nm::OccupancyGrid &g, const Cell &src, const Cell &dest) |
boost::optional< AStarResult > | shortestPath (const nav_msgs::OccupancyGrid &g, const Cell &src, const Cell &dest) |
A* using Manhattan distance cost and heuristic, with only horizontal and vertical neighbors. | |
ResultPtr | shortestPathResultFromMessage (const NavigationFunction &msg) |
Convert a shortest path result from a ros message. | |
NavigationFunction | shortestPathResultToMessage (ResultPtr res) |
Convert a shortest path result to a ros message. | |
int8_t | sign (const coord_t x) |
ResultPtr | singleSourceShortestPaths (const nm::OccupancyGrid &g, const Cell &src, const TerminationCondition &t) |
ResultPtr | singleSourceShortestPaths (const nm::OccupancyGrid &g, const Cell &src) |
ResultPtr | singleSourceShortestPaths (const nav_msgs::OccupancyGrid &g, const Cell &src, const TerminationCondition &term) |
Single source Dijkstra's algorithm. | |
ResultPtr | singleSourceShortestPaths (const nav_msgs::OccupancyGrid &g, const Cell &src) |
Single source Dijkstra's algorithm. | |
gm::Pose | transformPose (const btTransform trans, const gm::Pose p) |
gm::Point | transformPt (const btTransform &trans, const gm::Point32 &p) |
bool | withinBounds (const nav_msgs::MapMetaData &info, const Cell &c) |
Check if a cell is on the grid. | |
bool | withinBounds (const nav_msgs::MapMetaData &info, const geometry_msgs::Point &p) |
Check if a point is on the grid. | |
tf::Transform | worldToMap (const nav_msgs::MapMetaData &info) |
Variables | |
const double | DEFAULT_MAX_DISTANCE = 10.0 |
Default max_distance for OverlayClouds. | |
const double | DEFAULT_MIN_PASS_THROUGH = 2 |
Default min_pass_through for OverlayClouds. | |
const double | DEFAULT_OCCUPANCY_THRESHOLD = 0.1 |
Default occupancy threshold for OverlayClouds. | |
const int8_t | OCCUPIED = 100 |
const int8_t | UNKNOWN = 255 |
const int8_t | UNOCCUPIED = 0 |
typedef std::pair< Path, double > occupancy_grid_utils::AStarResult |
Definition at line 72 of file shortest_path.h.
typedef std::set<Cell> occupancy_grid_utils::Cells |
Definition at line 70 of file shortest_path.h.
typedef int16_t occupancy_grid_utils::coord_t |
Definition at line 55 of file coordinate_conversions.h.
typedef boost::shared_ptr< nm::OccupancyGrid const > occupancy_grid_utils::GridConstPtr |
Definition at line 55 of file combine_grids.cpp.
typedef boost::shared_ptr< nm::OccupancyGrid > occupancy_grid_utils::GridPtr |
Definition at line 54 of file combine_grids.cpp.
typedef uint32_t occupancy_grid_utils::index_t |
Definition at line 54 of file coordinate_conversions.h.
typedef ::occupancy_grid_utils::LocalizedCloud_<std::allocator<void> > occupancy_grid_utils::LocalizedCloud |
Definition at line 202 of file LocalizedCloud.h.
typedef boost::shared_ptr< ::occupancy_grid_utils::LocalizedCloud const> occupancy_grid_utils::LocalizedCloudConstPtr |
Definition at line 205 of file LocalizedCloud.h.
typedef boost::shared_ptr< ::occupancy_grid_utils::LocalizedCloud> occupancy_grid_utils::LocalizedCloudPtr |
Definition at line 204 of file LocalizedCloud.h.
typedef ::occupancy_grid_utils::NavigationFunction_<std::allocator<void> > occupancy_grid_utils::NavigationFunction |
Definition at line 167 of file NavigationFunction.h.
typedef boost::shared_ptr< ::occupancy_grid_utils::NavigationFunction const> occupancy_grid_utils::NavigationFunctionConstPtr |
Definition at line 170 of file NavigationFunction.h.
typedef boost::shared_ptr< ::occupancy_grid_utils::NavigationFunction> occupancy_grid_utils::NavigationFunctionPtr |
Definition at line 169 of file NavigationFunction.h.
typedef ::occupancy_grid_utils::OverlayClouds_<std::allocator<void> > occupancy_grid_utils::OverlayClouds |
Definition at line 213 of file OverlayClouds.h.
typedef boost::shared_ptr< ::occupancy_grid_utils::OverlayClouds const> occupancy_grid_utils::OverlayCloudsConstPtr |
Definition at line 216 of file OverlayClouds.h.
typedef boost::shared_ptr< ::occupancy_grid_utils::OverlayClouds> occupancy_grid_utils::OverlayCloudsPtr |
Definition at line 215 of file OverlayClouds.h.
typedef vector< Cell > occupancy_grid_utils::Path |
Definition at line 71 of file shortest_path.h.
typedef std::pair<RayTraceIterator, RayTraceIterator> occupancy_grid_utils::RayTraceIterRange |
Definition at line 13 of file ray_tracer.h.
typedef boost::shared_ptr<const ShortestPathResult> occupancy_grid_utils::ResultPtr |
Definition at line 68 of file shortest_path.h.
void occupancy_grid_utils::addCloud | ( | OverlayClouds * | overlay, | |
LocalizedCloud::ConstPtr | cloud, | |||
const int | inc | |||
) |
Definition at line 130 of file grid_overlay.cpp.
void occupancy_grid_utils::addCloud | ( | OverlayClouds * | overlay, | |
LocalizedCloud::ConstPtr | cloud | |||
) |
Raytrace a cloud onto grid in overlay.
Definition at line 187 of file grid_overlay.cpp.
void occupancy_grid_utils::addKnownFreePoint | ( | OverlayClouds * | overlay, | |
const gm::Point & | p, | |||
const double | r | |||
) |
Definition at line 109 of file grid_overlay.cpp.
void occupancy_grid_utils::addKnownFreePoint | ( | OverlayClouds * | overlay, | |
const geometry_msgs::Point & | p, | |||
double | r | |||
) |
Assert that a square centered at this point with side 2*r contains no obstacles.
geometry_msgs::Point occupancy_grid_utils::cellCenter | ( | const nav_msgs::MapMetaData & | info, | |
const Cell & | c | |||
) | [inline] |
Return center of a cell.
Definition at line 158 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.
CellOutOfBoundsException | if cell isn't within grid bounds |
Definition at line 113 of file coordinate_conversions.h.
geometry_msgs::Polygon occupancy_grid_utils::cellPolygon | ( | const nav_msgs::MapMetaData & | info, | |
const Cell & | c | |||
) | [inline] |
Return polygon corresponding to a cell.
Definition at line 167 of file coordinate_conversions.h.
bool occupancy_grid_utils::cellsIntersect | ( | const nm::MapMetaData & | info1, | |
const Cell & | c1, | |||
const nm::MapMetaData & | info2, | |||
const Cell & | c2 | |||
) | [inline] |
Definition at line 78 of file combine_grids.cpp.
bool occupancy_grid_utils::cellWithinBounds | ( | const nm::MapMetaData & | info, | |
const Cell & | c | |||
) | [inline] |
Definition at line 25 of file ray_tracer.cpp.
GridPtr occupancy_grid_utils::combineGrids | ( | const vector< GridConstPtr > & | grids | ) |
Definition at line 241 of file combine_grids.cpp.
GridPtr occupancy_grid_utils::combineGrids | ( | const vector< GridConstPtr > & | grids, | |
const double | resolution | |||
) |
Definition at line 210 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 the resolution of the first grid.
nav_msgs::OccupancyGrid::Ptr occupancy_grid_utils::combineGrids | ( | const std::vector< nav_msgs::OccupancyGrid::ConstPtr > & | grids, | |
double | resolution | |||
) |
Combines a set of grids.
The resulting grid's origin will be a translated version of grid 1's origin, with resolution resolution
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
bool occupancy_grid_utils::containsVertex | ( | const nm::MapMetaData & | info, | |
const Cell & | c, | |||
const gm::Polygon & | poly | |||
) | [inline] |
Definition at line 67 of file combine_grids.cpp.
OverlayClouds occupancy_grid_utils::createCloudOverlay | ( | const nm::OccupancyGrid & | grid, | |
const std::string & | frame_id, | |||
double | occupancy_threshold, | |||
double | max_distance, | |||
double | min_pass_through | |||
) |
Definition at line 93 of file grid_overlay.cpp.
OverlayClouds occupancy_grid_utils::createCloudOverlay | ( | const nav_msgs::OccupancyGrid & | grid, | |
const std::string & | frame_id, | |||
double | occupancy_threshold = DEFAULT_OCCUPANCY_THRESHOLD , |
|||
double | max_distance = DEFAULT_MAX_DISTANCE , |
|||
double | min_pass_through = DEFAULT_MIN_PASS_THROUGH | |||
) |
Create a cloud overlay object to which clouds can then be added The returned (ros message) object should only be accessed using the api below.
grid | Contains the geometry of the underlying grid. Additionally, iff the data field of this object is nonempty, rays will not be allowed to pass through obstacles in the grid. | |
frame_id | The frame name for the overlaid grid. Added clouds must have this frame_id | |
occupancy_threshold | what fraction of rays through the cell must end there for it to be considered an obstacle | |
max_distance | hits beyond this distance from the source are ignored | |
min_pass_through | cells with fewer than this many rays through them are marked UNKNOWN |
int8_t occupancy_grid_utils::determineOccupancy | ( | const unsigned | hit_count, | |
const unsigned | pass_through_count, | |||
const double | occupancy_threshold, | |||
const double | min_pass_through | |||
) | [inline] |
Definition at line 78 of file grid_overlay.cpp.
boost::optional< double > occupancy_grid_utils::distance | ( | ResultPtr | shortest_path_result, | |
const Cell & | dest | |||
) |
From result of single-source shortest paths, extract distance to some destination.
Distance | if path exists, uninitialized otherwise |
Definition at line 75 of file shortest_path.cpp.
double occupancy_grid_utils::euclideanDistance | ( | const gm::Point & | p1, | |
const gm::Point & | p2 | |||
) | [inline] |
Definition at line 68 of file grid_overlay.cpp.
gm::Polygon occupancy_grid_utils::expandPolygon | ( | const gm::Polygon & | p, | |
const double | r | |||
) | [inline] |
Definition at line 85 of file combine_grids.cpp.
boost::optional< Path > occupancy_grid_utils::extractPath | ( | ResultPtr | shortest_path_result, | |
const Cell & | dest | |||
) |
Extract a path from the result of single-source shortest paths.
path | If path exists, vector of cells where the source is first and dest is last; if not, uninitialized |
Definition at line 82 of file shortest_path.cpp.
nm::MapMetaData occupancy_grid_utils::getCombinedGridInfo | ( | const vector< GridConstPtr > & | grids, | |
const double | resolution | |||
) |
Definition at line 171 of file combine_grids.cpp.
GridPtr occupancy_grid_utils::getGrid | ( | const OverlayClouds & | overlay | ) |
Get the current grid. It's fine to modify the returned object.
Definition at line 199 of file grid_overlay.cpp.
nm::MapMetaData occupancy_grid_utils::gridInfo | ( | const OverlayClouds & | overlay | ) |
Definition at line 218 of file grid_overlay.cpp.
geometry_msgs::Polygon occupancy_grid_utils::gridPolygon | ( | const nav_msgs::MapMetaData & | info | ) | [inline] |
Return polygon corresponding to grid bounds.
Definition at line 186 of file coordinate_conversions.h.
Cell occupancy_grid_utils::indexCell | ( | const nav_msgs::MapMetaData & | info, | |
index_t | ind | |||
) | [inline] |
Returns cell corresponding to index.
Definition at line 121 of file coordinate_conversions.h.
GridPtr occupancy_grid_utils::inflateObstacles | ( | const nm::OccupancyGrid & | g, | |
const double | r, | |||
const bool | allow_unknown | |||
) |
Definition at line 202 of file shortest_path.cpp.
nav_msgs::OccupancyGrid::Ptr occupancy_grid_utils::inflateObstacles | ( | const nav_msgs::OccupancyGrid & | g, | |
double | r, | |||
bool | allow_unknown = false | |||
) |
Inflate obstacles in a grid.
Obstacles are cell values that are not 0, unless allow_unknown is true, in which case -1 is not considered an obstacle. If there exist obstacles within radius r meters of a cell, its value is replaced by the max of their values (-1 is considered to be the same as 1 for this). Rounds up when converting from meters to cells
set<Cell> occupancy_grid_utils::intersectingCells | ( | const nm::MapMetaData & | info, | |
const nm::MapMetaData & | info2, | |||
const Cell & | cell2 | |||
) |
Definition at line 110 of file combine_grids.cpp.
double occupancy_grid_utils::manhattanHeuristic | ( | const Cell & | c1, | |
const Cell & | c2 | |||
) | [inline] |
Definition at line 285 of file shortest_path.cpp.
tf::Transform occupancy_grid_utils::mapToWorld | ( | const nav_msgs::MapMetaData & | info | ) | [inline] |
Definition at line 129 of file coordinate_conversions.h.
double occupancy_grid_utils::maxX | ( | const nm::MapMetaData & | info | ) |
Definition at line 143 of file combine_grids.cpp.
double occupancy_grid_utils::maxY | ( | const nm::MapMetaData & | info | ) |
Definition at line 155 of file combine_grids.cpp.
double occupancy_grid_utils::minX | ( | const nm::MapMetaData & | info | ) |
Definition at line 137 of file combine_grids.cpp.
double occupancy_grid_utils::minY | ( | const nm::MapMetaData & | info | ) |
Definition at line 149 of file combine_grids.cpp.
bool occupancy_grid_utils::myGt | ( | const signed char | x, | |
const signed char | y | |||
) | [inline] |
Definition at line 188 of file shortest_path.cpp.
bool occupancy_grid_utils::operator< | ( | const QueueItem & | i1, | |
const QueueItem & | i2 | |||
) |
Definition at line 117 of file shortest_path.cpp.
std::ostream& occupancy_grid_utils::operator<< | ( | std::ostream & | s, | |
const ::occupancy_grid_utils::OverlayClouds_< ContainerAllocator > & | v | |||
) | [inline] |
Definition at line 220 of file OverlayClouds.h.
std::ostream& occupancy_grid_utils::operator<< | ( | std::ostream & | s, | |
const ::occupancy_grid_utils::NavigationFunction_< ContainerAllocator > & | v | |||
) | [inline] |
Definition at line 174 of file NavigationFunction.h.
std::ostream& occupancy_grid_utils::operator<< | ( | std::ostream & | s, | |
const ::occupancy_grid_utils::LocalizedCloud_< ContainerAllocator > & | v | |||
) | [inline] |
Definition at line 209 of file LocalizedCloud.h.
std::ostream& occupancy_grid_utils::operator<< | ( | std::ostream & | str, | |
const Cell & | c | |||
) | [inline] |
Definition at line 218 of file coordinate_conversions.h.
Cell occupancy_grid_utils::point32Cell | ( | const nm::MapMetaData & | info, | |
const gm::Point32 & | p | |||
) | [inline] |
Definition at line 57 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 143 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.
CellOutOfBoundsException | if point isn't within grid bounds |
Ignores z coordinate of point
Definition at line 152 of file coordinate_conversions.h.
RayTraceIterRange occupancy_grid_utils::rayTrace | ( | const nm::MapMetaData & | info, | |
const gm::Point & | p1, | |||
const gm::Point & | p2, | |||
bool | project_onto_grid, | |||
bool | project_source_onto_grid | |||
) |
Definition at line 40 of file ray_tracer.cpp.
RayTraceIterRange occupancy_grid_utils::rayTrace | ( | const Cell & | c1, | |
const Cell & | c2 | |||
) |
Definition at line 19 of file ray_tracer.cpp.
RayTraceIterRange occupancy_grid_utils::rayTrace | ( | const nav_msgs::MapMetaData & | info, | |
const geometry_msgs::Point & | p1, | |||
const geometry_msgs::Point & | p2, | |||
bool | project_target_onto_grid = false , |
|||
bool | project_source_onto_grid = false | |||
) |
Returns an iterator range over the cells on the line segment between two points (inclusive).
project_target_onto_grid | If true, p2 may be off the grid, in which case the ray stops right before falling off the grid | |
project_source_onto_grid | If true, p1 may be off the grid, in which case the ray |
PointOutOfBoundsException | if p1 is off grid and project_source_onto_grid is false | |
PointOutOfBoundsException | if p2 is off grid and project_target_onto_grid is false |
range | models Forward range with reference type const Cell&, i.e., it's a pair of iterators that you can use in for loops, std::for_each, etc. |
optional<Cell> occupancy_grid_utils::rayTraceOntoGrid | ( | const nm::MapMetaData & | info, | |
const Cell & | c1, | |||
const Cell & | c2 | |||
) |
Definition at line 30 of file ray_tracer.cpp.
void occupancy_grid_utils::removeCloud | ( | OverlayClouds * | overlay, | |
LocalizedCloud::ConstPtr | cloud | |||
) |
Effectively subtract a cloud (which was presumably previously added), by subtracting rather than adding counts, in overlay.
Definition at line 192 of file grid_overlay.cpp.
void occupancy_grid_utils::resetCounts | ( | OverlayClouds * | overlay | ) |
Definition at line 212 of file grid_overlay.cpp.
optional<AStarResult> occupancy_grid_utils::shortestPath | ( | const nm::OccupancyGrid & | g, | |
const Cell & | src, | |||
const Cell & | dest | |||
) |
Definition at line 290 of file shortest_path.cpp.
boost::optional<AStarResult> occupancy_grid_utils::shortestPath | ( | const nav_msgs::OccupancyGrid & | g, | |
const Cell & | src, | |||
const Cell & | dest | |||
) |
A* using Manhattan distance cost and heuristic, with only horizontal and vertical neighbors.
ResultPtr occupancy_grid_utils::shortestPathResultFromMessage | ( | const NavigationFunction & | msg | ) |
Convert a shortest path result from a ros message.
Definition at line 350 of file shortest_path.cpp.
NavigationFunction occupancy_grid_utils::shortestPathResultToMessage | ( | ResultPtr | res | ) |
Convert a shortest path result to a ros message.
Definition at line 385 of file shortest_path.cpp.
int8_t occupancy_grid_utils::sign | ( | const coord_t | x | ) | [inline] |
Definition at line 8 of file ray_trace_iterator.h.
ResultPtr occupancy_grid_utils::singleSourceShortestPaths | ( | const nm::OccupancyGrid & | g, | |
const Cell & | src, | |||
const TerminationCondition & | t | |||
) |
Definition at line 128 of file shortest_path.cpp.
ResultPtr occupancy_grid_utils::singleSourceShortestPaths | ( | const nm::OccupancyGrid & | g, | |
const Cell & | src | |||
) |
Definition at line 123 of file shortest_path.cpp.
ResultPtr occupancy_grid_utils::singleSourceShortestPaths | ( | const nav_msgs::OccupancyGrid & | g, | |
const Cell & | src, | |||
const TerminationCondition & | term | |||
) |
Single source Dijkstra's algorithm.
Structure | from which paths can be extracted or distances computed |
term | allows stopping early when a distance bound is reached or when a a set of goal cells have been found |
Each cell is connected to its horizontal and vertical neighbors, with cost 1, and diagonal neighbors with cost sqrt(2). Only cells with value UNOCCUPIED are considered.
ResultPtr occupancy_grid_utils::singleSourceShortestPaths | ( | const nav_msgs::OccupancyGrid & | g, | |
const Cell & | src | |||
) |
Single source Dijkstra's algorithm.
Structure | from which paths can be extracted or distances computed |
Each cell is connected to its horizontal and vertical neighbors, with cost 1, and diagonal neighbors with cost sqrt(2). Only cells with value UNOCCUPIED are considered.
gm::Pose occupancy_grid_utils::transformPose | ( | const btTransform | trans, | |
const gm::Pose | p | |||
) |
Definition at line 161 of file combine_grids.cpp.
gm::Point occupancy_grid_utils::transformPt | ( | const btTransform & | trans, | |
const gm::Point32 & | p | |||
) | [inline] |
Definition at line 60 of file grid_overlay.cpp.
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 231 of file coordinate_conversions.h.
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 225 of file coordinate_conversions.h.
tf::Transform occupancy_grid_utils::worldToMap | ( | const nav_msgs::MapMetaData & | info | ) | [inline] |
Definition at line 137 of file coordinate_conversions.h.
const double occupancy_grid_utils::DEFAULT_MAX_DISTANCE = 10.0 |
Default max_distance for OverlayClouds.
Definition at line 41 of file ray_tracer.h.
const double occupancy_grid_utils::DEFAULT_MIN_PASS_THROUGH = 2 |
Default min_pass_through for OverlayClouds.
Definition at line 44 of file ray_tracer.h.
const double occupancy_grid_utils::DEFAULT_OCCUPANCY_THRESHOLD = 0.1 |
Default occupancy threshold for OverlayClouds.
Definition at line 38 of file ray_tracer.h.
const int8_t occupancy_grid_utils::OCCUPIED = 100 |
Definition at line 70 of file coordinate_conversions.h.
const int8_t occupancy_grid_utils::UNKNOWN = 255 |
Definition at line 71 of file coordinate_conversions.h.
const int8_t occupancy_grid_utils::UNOCCUPIED = 0 |
Definition at line 69 of file coordinate_conversions.h.