Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef NAV_2D_UTILS_POLYGONS_H
00036 #define NAV_2D_UTILS_POLYGONS_H
00037
00038 #include <ros/ros.h>
00039 #include <nav_2d_msgs/Polygon2D.h>
00040 #include <geometry_msgs/Pose2D.h>
00041 #include <vector>
00042 #include <string>
00043
00044 namespace nav_2d_utils
00045 {
00046
00051 class PolygonParseException: public std::runtime_error
00052 {
00053 public:
00054 explicit PolygonParseException(const std::string& description) : std::runtime_error(description) {}
00055 };
00056
00064 std::vector<std::vector<double> > parseVVD(const std::string& input);
00065
00073 nav_2d_msgs::Polygon2D polygonFromRadius(const double radius, const unsigned int num_points = 16);
00074
00082 nav_2d_msgs::Polygon2D polygonFromString(const std::string& polygon_string);
00083
00091 nav_2d_msgs::Polygon2D polygonFromParams(const ros::NodeHandle& nh, const std::string parameter_name,
00092 bool search = true);
00093
00101 nav_2d_msgs::Polygon2D polygonFromXMLRPC(XmlRpc::XmlRpcValue& polygon_xmlrpc);
00102
00109 XmlRpc::XmlRpcValue polygonToXMLRPC(const nav_2d_msgs::Polygon2D& polygon, bool array_of_arrays = true);
00110
00118 void polygonToParams(const nav_2d_msgs::Polygon2D& polygon, const ros::NodeHandle& nh, const std::string parameter_name,
00119 bool array_of_arrays = true);
00120
00127 nav_2d_msgs::Polygon2D polygonFromParallelArrays(const std::vector<double>& xs, const std::vector<double>& ys);
00128
00136 void polygonToParallelArrays(const nav_2d_msgs::Polygon2D polygon, std::vector<double>& xs, std::vector<double>& ys);
00137
00141 bool equals(const nav_2d_msgs::Polygon2D& polygon0, const nav_2d_msgs::Polygon2D& polygon1);
00142
00149 nav_2d_msgs::Polygon2D movePolygonToPose(const nav_2d_msgs::Polygon2D& polygon,
00150 const geometry_msgs::Pose2D& pose);
00151
00162 bool isInside(const nav_2d_msgs::Polygon2D& polygon, const double x, const double y);
00163
00170 void calculateMinAndMaxDistances(const nav_2d_msgs::Polygon2D& polygon, double& min_dist, double& max_dist);
00171
00172 }
00173
00174 #endif // NAV_2D_UTILS_POLYGONS_H