35 #ifndef NAV_2D_UTILS_POLYGONS_H 36 #define NAV_2D_UTILS_POLYGONS_H 39 #include <nav_2d_msgs/Polygon2D.h> 40 #include <nav_2d_msgs/ComplexPolygon2D.h> 41 #include <geometry_msgs/Pose2D.h> 65 std::vector<std::vector<double> >
parseVVD(
const std::string& input);
74 nav_2d_msgs::Polygon2D
polygonFromRadius(
const double radius,
const unsigned int num_points = 16);
120 bool array_of_arrays =
true);
137 void polygonToParallelArrays(
const nav_2d_msgs::Polygon2D polygon, std::vector<double>& xs, std::vector<double>& ys);
142 bool equals(
const nav_2d_msgs::Polygon2D& polygon0,
const nav_2d_msgs::Polygon2D& polygon1);
151 const geometry_msgs::Pose2D& pose);
163 bool isInside(
const nav_2d_msgs::Polygon2D& polygon,
const double x,
const double y);
183 std::vector<nav_2d_msgs::Point2D>
triangulate(
const nav_2d_msgs::ComplexPolygon2D& polygon);
195 std::vector<nav_2d_msgs::Point2D>
triangulate(
const nav_2d_msgs::Polygon2D& polygon);
199 #endif // NAV_2D_UTILS_POLYGONS_H 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], ...].
A set of utility functions for Bounds objects interacting with other messages/types.
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
std::vector< nav_2d_msgs::Point2D > triangulate(const nav_2d_msgs::ComplexPolygon2D &polygon)
Decompose a complex polygon into a set of triangles.
Exception to throw when Polygon doesn't load correctly.
TFSIMD_FORCE_INLINE const tfScalar & y() const
void polygonToParallelArrays(const nav_2d_msgs::Polygon2D polygon, std::vector< double > &xs, std::vector< double > &ys)
Create two parallel arrays from a polygon.
nav_2d_msgs::Polygon2D polygonFromRadius(const double radius, const unsigned int num_points=16)
Create a "circular" polygon from a given radius.
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
PolygonParseException(const std::string &description)
nav_2d_msgs::Polygon2D polygonFromParallelArrays(const std::vector< double > &xs, const std::vector< double > &ys)
Create a polygon from two parallel arrays.
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.
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.
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
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.