45 using nav_2d_msgs::Point2D;
    46 using nav_2d_msgs::Polygon2D;
    48 std::vector<std::vector<double> > 
parseVVD(
const std::string& input)
    50   std::vector<std::vector<double> > result;
    52   std::stringstream input_ss(input);
    54   std::vector<double> current_vector;
    55   while (input_ss.good())
    57     switch (input_ss.peek())
    68       current_vector.clear();
    79         result.push_back(current_vector);
    90         std::stringstream err_ss;
    91         err_ss << 
"Numbers at depth other than 2. Char was '" << char(input_ss.peek()) << 
"'.";
    95       if (input_ss >> value)
    97         current_vector.push_back(value);
   115   for (
unsigned int i = 0; i < num_points; ++i)
   117     double angle = i * 2 * M_PI / num_points;
   118     pt.x = cos(angle) * radius;
   119     pt.y = sin(angle) * radius;
   120     polygon.points.push_back(pt);
   130   std::vector<std::vector<double> > vvd = 
parseVVD(polygon_string);
   138   polygon.points.resize(vvd.size());
   139   for (
unsigned int i = 0; i < vvd.size(); i++)
   141     if (vvd[ i ].size() != 2)
   143       std::stringstream err_ss;
   144       err_ss << 
"Points in the polygon specification must be pairs of numbers. Point index " << i << 
" had ";
   145       err_ss << int(vvd[ i ].size()) << 
" numbers.";
   149     polygon.points[i].x = vvd[i][0];
   150     polygon.points[i].y = vvd[i][1];
   164     return static_cast<double>(
static_cast<int>(value));
   168     return static_cast<double>(value);
   171   std::stringstream err_ss;
   172   err_ss << 
"Values in the polygon specification must be numbers. Found value: " << value.
toXml();
   185   std::vector<double> array;
   186   for (
int i = 0; i < value.
size(); i++)
   196       polygon_xmlrpc != 
"" && polygon_xmlrpc != 
"[]")
   215     std::stringstream err_ss;
   216     err_ss << 
"Polygon must be specified as a list of lists. Found object of type " << polygon_xmlrpc.
getType()
   220   else if (polygon_xmlrpc.
size() < 3)
   227   for (
int i = 0; i < polygon_xmlrpc.
size(); ++i)
   233       std::stringstream err_ss;
   234       err_ss << 
"Each point must be specified as a list. Found object of type " << point_xml.
getType() << 
" instead.";
   237     else if (point_xml.
size() != 2)
   244     polygon.points.push_back(pt);
   251   std::string full_param_name;
   258     full_param_name = parameter_name;
   263     std::stringstream err_ss;
   264     err_ss << 
"Parameter " << parameter_name << 
"(" + nh.
resolveName(parameter_name) << 
") not found.";
   268   nh.
getParam(full_param_name, polygon_xmlrpc);
   279   for (
unsigned int i = 0; i < array.size(); ++i)
   291     xml.
setSize(polygon.points.size());
   292     for (
unsigned int i = 0; i < polygon.points.size(); ++i)
   295       const Point2D& p = polygon.points[i];
   302     std::vector<double> xs, ys;
   311                      bool array_of_arrays)
   322   else if (xs.size() != ys.size())
   328   polygon.points.resize(xs.size());
   329   for (
unsigned int i = 0; i < xs.size(); i++)
   331     Point2D& pt = polygon.points[i];
   342   for (
const Point2D& pt : polygon.points)
   349 bool equals(
const nav_2d_msgs::Polygon2D& polygon0, 
const nav_2d_msgs::Polygon2D& polygon1)
   351   if (polygon0.points.size() != polygon1.points.size())
   355   for (
unsigned int i=0; i < polygon0.points.size(); i++)
   357     if (polygon0.points[i].x != polygon1.points[i].x ||polygon0.points[i].y != polygon1.points[i].y)
   366                                          const geometry_msgs::Pose2D& pose)
   368   nav_2d_msgs::Polygon2D new_polygon;
   369   new_polygon.points.resize(polygon.points.size());
   370   double cos_th = cos(pose.theta);
   371   double sin_th = sin(pose.theta);
   372   for (
unsigned int i = 0; i < polygon.points.size(); ++i)
   374     nav_2d_msgs::Point2D& new_pt = new_polygon.points[i];
   375     new_pt.x = pose.x + polygon.points[i].x * cos_th - polygon.points[i].y * sin_th;
   376     new_pt.y = pose.y + polygon.points[i].x * sin_th + polygon.points[i].y * cos_th;
   381 bool isInside(
const nav_2d_msgs::Polygon2D& polygon, 
const double x, 
const double y)
   385   int n = polygon.points.size();
   389   for (
int i = 0, j = n - 1; i < n; j = i++)
   392     if ( ((polygon.points[i].y > y) != (polygon.points[j].y > y))
   393            && (x < (polygon.points[j].x - polygon.points[i].x) * (y - polygon.points[i].y) /
   394             (polygon.points[j].y - polygon.points[i].y) + polygon.points[i].x) )
   400   return cross % 2 > 0;
   405   min_dist = std::numeric_limits<double>::max();
   407   auto& points = polygon.points;
   408   if (points.size() == 0)
   413   for (
unsigned int i = 0; i < points.size() - 1; ++i)
   416     double vertex_dist = hypot(points[i].
x, points[i].
y);
   417     double edge_dist = 
distanceToLine(0.0, 0.0, points[i].x, points[i].y,
   418                                       points[i + 1].x, points[i + 1].y);
   419     min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
   420     max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
   424   double vertex_dist = hypot(points.back().x, points.back().y);
   425   double edge_dist = 
distanceToLine(0.0, 0.0, points.back().x, points.back().y,
   426                                       points.front().x, points.front().y);
   427   min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
   428   max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
 double distanceToLine(double pX, double pY, double x0, double y0, double x1, double y1)
Distance from point (pX, pY) to closest point on line from (x0, y0) to (x1, y1) 
nav_2d_msgs::Polygon2D polygonFromXMLRPC(XmlRpc::XmlRpcValue &polygon_xmlrpc)
Create a polygon from the given XmlRpcValue. 
std::vector< std::vector< double > > 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], ...]. 
nav_2d_msgs::Polygon2D 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. 
bool equals(const nav_2d_msgs::Polygon2D &polygon0, const nav_2d_msgs::Polygon2D &polygon1)
check if two polygons are equal. Used in testing 
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const 
XmlRpc::XmlRpcValue vectorToXMLRPC(const std::vector< double > &array)
Helper method to convert a vector of doubles. 
std::string resolveName(const std::string &name, bool remap=true) const 
Exception to throw when Polygon doesn't load correctly. 
Type const & getType() const 
TFSIMD_FORCE_INLINE const tfScalar & y() const 
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
double getNumberFromXMLRPC(XmlRpc::XmlRpcValue &value)
Helper function. Convert value to double. 
void polygonToParallelArrays(const nav_2d_msgs::Polygon2D polygon, std::vector< double > &xs, std::vector< double > &ys)
Create two parallel arrays from a polygon. 
std::string toXml() const 
nav_2d_msgs::Polygon2D polygonFromRadius(const double radius, const unsigned int num_points=16)
Create a "circular" polygon from a given radius. 
std::vector< double > getNumberVectorFromXMLRPC(XmlRpc::XmlRpcValue &value)
Helper function. Convert value to double array. 
bool searchParam(const std::string &key, std::string &result) const 
void 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. 
TFSIMD_FORCE_INLINE const tfScalar & x() const 
nav_2d_msgs::Polygon2D polygonFromParallelArrays(const std::vector< double > &xs, const std::vector< double > &ys)
Create a polygon from two parallel arrays. 
bool hasMember(const std::string &name) const 
bool getParam(const std::string &key, std::string &s) const 
void 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. 
bool hasParam(const std::string &key) const 
nav_2d_msgs::Polygon2D polygonFromString(const std::string &polygon_string)
Make a polygon from the given string. Format should be bracketed array of arrays of doubles...
nav_2d_msgs::Polygon2D movePolygonToPose(const nav_2d_msgs::Polygon2D &polygon, const geometry_msgs::Pose2D &pose)
Translate and rotate a polygon to a new pose. 
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const 
XmlRpc::XmlRpcValue polygonToXMLRPC(const nav_2d_msgs::Polygon2D &polygon, bool array_of_arrays=true)
Create XMLRPC Value for writing the polygon to the parameter server. 
bool isInside(const nav_2d_msgs::Polygon2D &polygon, const double x, const double y)
Check if a given point is inside of a polygon.