46 using nav_2d_msgs::Point2D;
47 using nav_2d_msgs::Polygon2D;
49 std::vector<std::vector<double> >
parseVVD(
const std::string& input)
51 std::vector<std::vector<double> > result;
53 std::stringstream input_ss(input);
55 std::vector<double> current_vector;
56 while (input_ss.good())
58 switch (input_ss.peek())
69 current_vector.clear();
80 result.push_back(current_vector);
91 std::stringstream err_ss;
92 err_ss <<
"Numbers at depth other than 2. Char was '" << char(input_ss.peek()) <<
"'.";
96 if (input_ss >> value)
98 current_vector.push_back(value);
116 for (
unsigned int i = 0; i < num_points; ++i)
118 double angle = i * 2 * M_PI / num_points;
119 pt.x = cos(
angle) * radius;
120 pt.y = sin(
angle) * radius;
121 polygon.points.push_back(pt);
131 std::vector<std::vector<double> > vvd =
parseVVD(polygon_string);
139 polygon.points.resize(vvd.size());
140 for (
unsigned int i = 0; i < vvd.size(); i++)
142 if (vvd[ i ].size() != 2)
144 std::stringstream err_ss;
145 err_ss <<
"Points in the polygon specification must be pairs of numbers. Point index " << i <<
" had ";
146 err_ss << int(vvd[ i ].size()) <<
" numbers.";
150 polygon.points[i].x = vvd[i][0];
151 polygon.points[i].y = vvd[i][1];
165 return static_cast<double>(
static_cast<int>(value));
169 return static_cast<double>(value);
172 std::stringstream err_ss;
173 err_ss <<
"Values in the polygon specification must be numbers. Found value: " << value.
toXml();
186 std::vector<double> array;
187 for (
int i = 0; i < value.
size(); i++)
197 polygon_xmlrpc !=
"" && polygon_xmlrpc !=
"[]")
216 std::stringstream err_ss;
217 err_ss <<
"Polygon must be specified as a list of lists. Found object of type " << polygon_xmlrpc.
getType()
221 else if (polygon_xmlrpc.
size() < 3)
228 for (
int i = 0; i < polygon_xmlrpc.
size(); ++i)
234 std::stringstream err_ss;
235 err_ss <<
"Each point must be specified as a list. Found object of type " << point_xml.
getType() <<
" instead.";
238 else if (point_xml.
size() != 2)
245 polygon.points.push_back(pt);
252 std::string full_param_name;
259 full_param_name = parameter_name;
264 std::stringstream err_ss;
265 err_ss <<
"Parameter " << parameter_name <<
"(" + nh.
resolveName(parameter_name) <<
") not found.";
269 nh.
getParam(full_param_name, polygon_xmlrpc);
280 for (
unsigned int i = 0; i < array.size(); ++i)
292 xml.
setSize(polygon.points.size());
293 for (
unsigned int i = 0; i < polygon.points.size(); ++i)
296 const Point2D& p = polygon.points[i];
303 std::vector<double> xs, ys;
312 bool array_of_arrays)
323 else if (xs.size() != ys.size())
329 polygon.points.resize(xs.size());
330 for (
unsigned int i = 0; i < xs.size(); i++)
332 Point2D& pt = polygon.points[i];
343 for (
const Point2D& pt : polygon.points)
350 bool equals(
const nav_2d_msgs::Polygon2D& polygon0,
const nav_2d_msgs::Polygon2D& polygon1)
352 if (polygon0.points.size() != polygon1.points.size())
356 for (
unsigned int i=0; i < polygon0.points.size(); i++)
358 if (polygon0.points[i].x != polygon1.points[i].x ||polygon0.points[i].y != polygon1.points[i].y)
367 const geometry_msgs::Pose2D& pose)
369 nav_2d_msgs::Polygon2D new_polygon;
370 new_polygon.points.resize(polygon.points.size());
371 double cos_th = cos(pose.theta);
372 double sin_th = sin(pose.theta);
373 for (
unsigned int i = 0; i < polygon.points.size(); ++i)
375 nav_2d_msgs::Point2D& new_pt = new_polygon.points[i];
376 new_pt.x = pose.x + polygon.points[i].x * cos_th - polygon.points[i].y * sin_th;
377 new_pt.y = pose.y + polygon.points[i].x * sin_th + polygon.points[i].y * cos_th;
382 bool isInside(
const nav_2d_msgs::Polygon2D& polygon,
const double x,
const double y)
386 int n = polygon.points.size();
390 for (
int i = 0, j = n - 1; i < n; j = i++)
393 if ( ((polygon.points[i].y > y) != (polygon.points[j].y > y))
394 && (x < (polygon.points[j].x - polygon.points[i].x) * (y - polygon.points[i].y) /
395 (polygon.points[j].y - polygon.points[i].y) + polygon.points[i].x) )
401 return cross % 2 > 0;
406 min_dist = std::numeric_limits<double>::max();
408 auto& points = polygon.points;
409 if (points.size() == 0)
414 for (
unsigned int i = 0; i < points.size() - 1; ++i)
417 double vertex_dist = hypot(points[i].x, points[i].y);
418 double edge_dist =
distanceToLine(0.0, 0.0, points[i].x, points[i].y,
419 points[i + 1].x, points[i + 1].y);
420 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
421 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
425 double vertex_dist = hypot(points.back().x, points.back().y);
426 double edge_dist =
distanceToLine(0.0, 0.0, points.back().x, points.back().y,
427 points.front().x, points.front().y);
428 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
429 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
439 struct nth<0, nav_2d_msgs::Point2D>
441 inline static double get(
const nav_2d_msgs::Point2D& point)
448 struct nth<1, nav_2d_msgs::Point2D>
450 inline static double get(
const nav_2d_msgs::Point2D& point)
462 std::vector<nav_2d_msgs::Point2D>
triangulate(
const nav_2d_msgs::ComplexPolygon2D& polygon)
465 std::vector<std::vector<nav_2d_msgs::Point2D>> rings;
466 rings.reserve(1 + polygon.inner.size());
467 rings.push_back(polygon.outer.points);
468 for (
const nav_2d_msgs::Polygon2D& inner : polygon.inner)
470 rings.push_back(inner.points);
472 std::vector<unsigned int> indices = mapbox::earcut<unsigned int>(rings);
475 std::vector<nav_2d_msgs::Point2D> points;
476 for (
const auto& ring : rings)
478 for (
const nav_2d_msgs::Point2D& point : ring)
480 points.push_back(point);
485 std::vector<nav_2d_msgs::Point2D> result;
486 result.reserve(indices.size());
487 for (
unsigned int index : indices)
489 result.push_back(points[index]);
494 std::vector<nav_2d_msgs::Point2D>
triangulate(
const nav_2d_msgs::Polygon2D& polygon)
496 nav_2d_msgs::ComplexPolygon2D complex;
497 complex.outer = polygon;