|  | 
| void | nav_2d_utils::calculateMinAndMaxDistances (const nav_2d_msgs::Polygon2D &polygon, double &min_dist, double &max_dist) | 
|  | Calculate the minimum and maximum distance from (0, 0) to any point on the polygon.  More... 
 | 
|  | 
| bool | nav_2d_utils::equals (const nav_2d_msgs::Polygon2D &polygon0, const nav_2d_msgs::Polygon2D &polygon1) | 
|  | check if two polygons are equal. Used in testing  More... 
 | 
|  | 
| bool | nav_2d_utils::isInside (const nav_2d_msgs::Polygon2D &polygon, const double x, const double y) | 
|  | Check if a given point is inside of a polygon.  More... 
 | 
|  | 
| nav_2d_msgs::Polygon2D | nav_2d_utils::movePolygonToPose (const nav_2d_msgs::Polygon2D &polygon, const geometry_msgs::Pose2D &pose) | 
|  | Translate and rotate a polygon to a new pose.  More... 
 | 
|  | 
| std::vector< std::vector< double > > | nav_2d_utils::parseVVD (const std::string &input) | 
|  | Parse a vector of vectors of doubles from a string. Syntax is [[1.0, 2.0], [3.3, 4.4, 5.5], ...].  More... 
 | 
|  | 
| nav_2d_msgs::Polygon2D | nav_2d_utils::polygonFromParallelArrays (const std::vector< double > &xs, const std::vector< double > &ys) | 
|  | Create a polygon from two parallel arrays.  More... 
 | 
|  | 
| nav_2d_msgs::Polygon2D | nav_2d_utils::polygonFromParams (const ros::NodeHandle &nh, const std::string parameter_name, bool search=true) | 
|  | Load a polygon from a parameter, whether it is a string or array, or two arrays.  More... 
 | 
|  | 
| nav_2d_msgs::Polygon2D | nav_2d_utils::polygonFromRadius (const double radius, const unsigned int num_points=16) | 
|  | Create a "circular" polygon from a given radius.  More... 
 | 
|  | 
| nav_2d_msgs::Polygon2D | nav_2d_utils::polygonFromString (const std::string &polygon_string) | 
|  | Make a polygon from the given string. Format should be bracketed array of arrays of doubles, like so: [[1.0, 2.2], [3.3, 4.2], ...].  More... 
 | 
|  | 
| nav_2d_msgs::Polygon2D | nav_2d_utils::polygonFromXMLRPC (XmlRpc::XmlRpcValue &polygon_xmlrpc) | 
|  | Create a polygon from the given XmlRpcValue.  More... 
 | 
|  | 
| void | nav_2d_utils::polygonToParallelArrays (const nav_2d_msgs::Polygon2D polygon, std::vector< double > &xs, std::vector< double > &ys) | 
|  | Create two parallel arrays from a polygon.  More... 
 | 
|  | 
| void | nav_2d_utils::polygonToParams (const nav_2d_msgs::Polygon2D &polygon, const ros::NodeHandle &nh, const std::string parameter_name, bool array_of_arrays=true) | 
|  | Save a polygon to a parameter.  More... 
 | 
|  | 
| XmlRpc::XmlRpcValue | nav_2d_utils::polygonToXMLRPC (const nav_2d_msgs::Polygon2D &polygon, bool array_of_arrays=true) | 
|  | Create XMLRPC Value for writing the polygon to the parameter server.  More... 
 | 
|  | 
| std::vector< nav_2d_msgs::Point2D > | nav_2d_utils::triangulate (const nav_2d_msgs::ComplexPolygon2D &polygon) | 
|  | Decompose a complex polygon into a set of triangles.  More... 
 | 
|  | 
| std::vector< nav_2d_msgs::Point2D > | nav_2d_utils::triangulate (const nav_2d_msgs::Polygon2D &polygon) | 
|  | Decompose a simple polygon into a set of triangles.  More... 
 | 
|  |