Classes |
class | CircleProvider |
| Singleton class which provides the mid-point circle algorithm implementation. More...
|
class | ConnectedComponents |
| API for 8-connected connected components algorithm to find critical regions in a map demarcated by obstalces and critical lines Neigbouring critical regions help form the topological graph. Since this algorithm is 8-connected, any demarcating lines should be drawn 4-connected if they are single pixel. More...
|
class | DirectedDFS |
| The directed DFS class. Checks whether 2 points are close inside the map in obstacle space. Uses euclidean distance to goal to guide the search. More...
|
struct | Edge |
class | MapLoader |
| Base class for reading a standard ROS map from a YAML file and writing it to an OpenCV Image. More...
|
class | PathFinder |
| Performs a 4-connected dynamic programming search around a given point to find which other points it is connected to in the map. More...
|
class | Point2d |
| A simple class to hold a 2D pixel point along with distance to a reference position. More...
|
class | Point2dDistanceComp |
| A simple class acting as a comparator for Point2d using the reference distance. Useful while using std::sort. More...
|
class | TopologicalMapper |
| Computes the 2 variants of the topological graph using the voronoi approximator. More...
|
struct | Vertex |
class | VoronoiApproximator |
| The voronoi approximator API. Inherits MapLoader to directly load a map from file and be able to draw a map. More...
|
class | VoronoiPoint |
Typedefs |
typedef boost::adjacency_list
< boost::vecS, boost::vecS,
boost::undirectedS, Vertex,
Edge > | Graph |
typedef cv::Point2f | Point2f |
Functions |
void | drawArrowOnGraph (cv::Mat &image, const Graph &graph, std::pair< size_t, float > arrow, uint32_t map_width, uint32_t map_height, cv::Scalar color=cv::Scalar(0, 0, 255), uint32_t orig_x=0, uint32_t orig_y=0) |
void | drawArrowOnImage (cv::Mat &image, const cv::Point2f &arrow_center, float orientation, const cv::Scalar &color, int size, int thickness) |
void | drawCircleOnGraph (cv::Mat &image, const Graph &graph, size_t node, cv::Scalar color=cv::Scalar(0, 0, 255), uint32_t orig_x=0, uint32_t orig_y=0) |
void | drawGraph (cv::Mat &image, const Graph &graph, uint32_t orig_x=0, uint32_t orig_y=0, bool put_text=true, bool put_all_edges=true, std::vector< std::pair< size_t, size_t > > specific_edges=std::vector< std::pair< size_t, size_t > >()) |
| draws the given graph onto an image starting at (orig_x, orig_y)
|
void | drawSquareOnGraph (cv::Mat &image, const Graph &graph, size_t node, cv::Scalar color=cv::Scalar(0, 0, 255), uint32_t orig_x=0, uint32_t orig_y=0, int size=30, int thickness=2) |
void | getAdjacentNodes (size_t v, const Graph &graph, std::vector< size_t > &adjacent_vertices) |
size_t | getClosestIdOnGraph (const Point2f &point, const Graph &graph, double threshold=0.0) |
size_t | getClosestIdOnGraphFromEdge (const Point2f &point, const Graph &graph, size_t prev_graph_id) |
float | getEuclideanDistance (size_t u, size_t v, const Graph &graph) |
Point2f | getLocationFromGraphId (int idx, const Graph &graph) |
float | getMagnitude (Point2f v) |
float | getNodeAngle (size_t u, size_t v, const Graph &graph) |
float | getShortestPathDistance (size_t start_idx, size_t goal_idx, const Graph &graph) |
float | getShortestPathWithDistance (size_t start_idx, size_t goal_idx, std::vector< size_t > &path_from_goal, const Graph &graph) |
void | getVisibleNodes (size_t v, const Graph &graph, const nav_msgs::OccupancyGrid &grid, std::vector< size_t > &visible_vertices, float visibility_range=0.0f) |
void | inflateMap (double threshold, const nav_msgs::OccupancyGrid &map, nav_msgs::OccupancyGrid &inflated_map) |
| A simple utility function that expands the map based on inflation distance in meters.
|
bool | isVisible (size_t u, size_t v, const Graph &graph, const nav_msgs::OccupancyGrid &map) |
bool | locationsInDirectLineOfSight (const Point2f &pt1, const Point2f &pt2, const nav_msgs::OccupancyGrid map) |
float | minimumDistanceToLineSegment (Point2f v, Point2f w, Point2f p) |
void | readGraphFromFile (const std::string &filename, const nav_msgs::MapMetaData &info, Graph &graph) |
Point2f | toGrid (const Point2f &pt, const nav_msgs::MapMetaData &info) |
Point2f | toMap (const Point2f &pt, const nav_msgs::MapMetaData &info) |
void | writeGraphToFile (const std::string &filename, const Graph &graph, const nav_msgs::MapMetaData &info) |