#include <voronoi_graph_node.h>

Public Member Functions | |
| void | publishMap () |
| void | publishSegments () |
| VoronoiGeneratorNode (ros::NodeHandle &n) | |
Public Member Functions inherited from voronoi_map::VoronoiPathGenerator | |
| void | computeDistanceField (const cv::Mat &_map, cv::Mat &_distField) |
| computes the distance field of a map More... | |
| void | computeVoronoiMap (const cv::Mat &_distField, cv::Mat &_voronoiMap) |
| computes the voronoi _map More... | |
| void | prepareMap (const cv::Mat &_map, cv::Mat &_smoothedMap, int _erodeSize) |
| prepares the map by smoothing it More... | |
| VoronoiPathGenerator () | |
Public Member Functions inherited from tuw_graph::VoronoiGraphGenerator | |
| std::vector< Segment > | calcSegments (cv::Mat &_map, cv::Mat &_distField, cv::Mat &_voronoiPath, float *potential, float _path_length, float _optimizeCrossingPixels, float _optimizeEndSegmentsPixel) |
| calculates the search graph More... | |
| VoronoiGraphGenerator () | |
Public Member Functions inherited from tuw_graph::Serializer | |
| size_t | getHash (const std::vector< signed char > &_map, const std::vector< double > &_parameters) const |
| generate a hash from a _map More... | |
| bool | load (const std::string &_mapPath, std::vector< Segment > &_segs, Eigen::Vector2d &_origin, float &_resolution) |
| loads a graph from memory which is saved in plain text More... | |
| bool | load (const std::string &_mapPath, std::vector< Segment > &_segs, Eigen::Vector2d &_origin, float &_resolution, cv::Mat &_map) |
| loads a graph from memory which is saved in plain text More... | |
| void | save (const std::string &_mapPath, const std::vector< Segment > &_segs, const Eigen::Vector2d &_origin, const float &_resolution) |
| saves the graph to a specific path in xml format More... | |
| void | save (const std::string &_mapPath, const std::vector< Segment > &_segs, const Eigen::Vector2d &_origin, const float &_resolution, const cv::Mat &_map) |
| saves the graph to a specific path in xml format More... | |
| Serializer () | |
Public Attributes | |
| ros::NodeHandle | n_ |
| ros::NodeHandle | n_param_ |
| std::unique_ptr< ros::Rate > | rate_ |
Private Member Functions | |
| void | createGraph (const nav_msgs::OccupancyGrid::ConstPtr &_map, size_t _map_hash) |
| void | globalMapCallback (const nav_msgs::OccupancyGrid::ConstPtr &_map) |
| bool | loadCustomGraph (std::string _path) |
| bool | loadGraph (size_t _hash) |
Private Attributes | |
| float | crossingOptimization_ |
| size_t | current_map_hash_ |
| std::string | customGraphPath_ |
| cv::Mat | distField_ |
| float | endSegmentOptimization_ |
| std::string | frameGlobalMap_ |
| std::string | frameVoronoiMap_ |
| std::string | graphCachePath_ |
| double | inflation_ |
| cv::Mat | map_ |
| Eigen::Vector2d | origin_ |
| for debuging More... | |
| std::unique_ptr< float[]> | potential |
| bool | publishVoronoiMapImage_ |
| ros::Publisher | pubSegments_ |
| ros::Publisher | pubVoronoiMapImage_ |
| float | resolution_ |
| float | segment_length_ |
| std::vector< Segment > | segments_ |
| int | smoothing_ |
| ros::Subscriber | subMap_ |
| cv::Mat | voronoiMap_ |
| nav_msgs::OccupancyGrid | voronoiMapImage_ |
Definition at line 19 of file voronoi_graph_node.h.
| tuw_graph::VoronoiGeneratorNode::VoronoiGeneratorNode | ( | ros::NodeHandle & | n | ) |
|
private |
Definition at line 137 of file voronoi_graph_node.cpp.
|
private |
Definition at line 79 of file voronoi_graph_node.cpp.
|
private |
Definition at line 173 of file voronoi_graph_node.cpp.
|
private |
Definition at line 166 of file voronoi_graph_node.cpp.
| void tuw_graph::VoronoiGeneratorNode::publishMap | ( | ) |
| void tuw_graph::VoronoiGeneratorNode::publishSegments | ( | ) |
Definition at line 180 of file voronoi_graph_node.cpp.
|
private |
Definition at line 62 of file voronoi_graph_node.h.
|
private |
Definition at line 50 of file voronoi_graph_node.h.
|
private |
Definition at line 44 of file voronoi_graph_node.h.
|
private |
Definition at line 55 of file voronoi_graph_node.h.
|
private |
Definition at line 63 of file voronoi_graph_node.h.
|
private |
Definition at line 46 of file voronoi_graph_node.h.
|
private |
Definition at line 47 of file voronoi_graph_node.h.
|
private |
Definition at line 43 of file voronoi_graph_node.h.
|
private |
Definition at line 61 of file voronoi_graph_node.h.
|
private |
Definition at line 54 of file voronoi_graph_node.h.
| ros::NodeHandle tuw_graph::VoronoiGeneratorNode::n_ |
Definition at line 25 of file voronoi_graph_node.h.
| ros::NodeHandle tuw_graph::VoronoiGeneratorNode::n_param_ |
Definition at line 26 of file voronoi_graph_node.h.
|
private |
for debuging
Definition at line 52 of file voronoi_graph_node.h.
|
private |
Definition at line 58 of file voronoi_graph_node.h.
|
private |
Definition at line 51 of file voronoi_graph_node.h.
|
private |
Definition at line 39 of file voronoi_graph_node.h.
|
private |
Definition at line 38 of file voronoi_graph_node.h.
| std::unique_ptr<ros::Rate> tuw_graph::VoronoiGeneratorNode::rate_ |
Definition at line 27 of file voronoi_graph_node.h.
|
private |
Definition at line 53 of file voronoi_graph_node.h.
|
private |
Definition at line 57 of file voronoi_graph_node.h.
|
private |
Definition at line 59 of file voronoi_graph_node.h.
|
private |
Definition at line 60 of file voronoi_graph_node.h.
|
private |
Definition at line 40 of file voronoi_graph_node.h.
|
private |
Definition at line 56 of file voronoi_graph_node.h.
|
private |
Definition at line 66 of file voronoi_graph_node.h.