polygons.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef NAV_2D_UTILS_POLYGONS_H
36 #define NAV_2D_UTILS_POLYGONS_H
37 
38 #include <ros/ros.h>
39 #include <nav_2d_msgs/Polygon2D.h>
40 #include <nav_2d_msgs/ComplexPolygon2D.h>
41 #include <geometry_msgs/Pose2D.h>
42 #include <vector>
43 #include <string>
44 
45 namespace nav_2d_utils
46 {
47 
52 class PolygonParseException: public std::runtime_error
53 {
54 public:
55  explicit PolygonParseException(const std::string& description) : std::runtime_error(description) {}
56 };
57 
65 std::vector<std::vector<double> > parseVVD(const std::string& input);
66 
74 nav_2d_msgs::Polygon2D polygonFromRadius(const double radius, const unsigned int num_points = 16);
75 
83 nav_2d_msgs::Polygon2D polygonFromString(const std::string& polygon_string);
84 
92 nav_2d_msgs::Polygon2D polygonFromParams(const ros::NodeHandle& nh, const std::string parameter_name,
93  bool search = true);
94 
102 nav_2d_msgs::Polygon2D polygonFromXMLRPC(XmlRpc::XmlRpcValue& polygon_xmlrpc);
103 
110 XmlRpc::XmlRpcValue polygonToXMLRPC(const nav_2d_msgs::Polygon2D& polygon, bool array_of_arrays = true);
111 
119 void polygonToParams(const nav_2d_msgs::Polygon2D& polygon, const ros::NodeHandle& nh, const std::string parameter_name,
120  bool array_of_arrays = true);
121 
128 nav_2d_msgs::Polygon2D polygonFromParallelArrays(const std::vector<double>& xs, const std::vector<double>& ys);
129 
137 void polygonToParallelArrays(const nav_2d_msgs::Polygon2D polygon, std::vector<double>& xs, std::vector<double>& ys);
138 
142 bool equals(const nav_2d_msgs::Polygon2D& polygon0, const nav_2d_msgs::Polygon2D& polygon1);
143 
150 nav_2d_msgs::Polygon2D movePolygonToPose(const nav_2d_msgs::Polygon2D& polygon,
151  const geometry_msgs::Pose2D& pose);
152 
163 bool isInside(const nav_2d_msgs::Polygon2D& polygon, const double x, const double y);
164 
171 void calculateMinAndMaxDistances(const nav_2d_msgs::Polygon2D& polygon, double& min_dist, double& max_dist);
172 
183 std::vector<nav_2d_msgs::Point2D> triangulate(const nav_2d_msgs::ComplexPolygon2D& polygon);
184 
195 std::vector<nav_2d_msgs::Point2D> triangulate(const nav_2d_msgs::Polygon2D& polygon);
196 
197 } // namespace nav_2d_utils
198 
199 #endif // NAV_2D_UTILS_POLYGONS_H
nav_2d_msgs::Polygon2D polygonFromXMLRPC(XmlRpc::XmlRpcValue &polygon_xmlrpc)
Create a polygon from the given XmlRpcValue.
Definition: polygons.cpp:194
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], ...].
Definition: polygons.cpp:49
A set of utility functions for Bounds objects interacting with other messages/types.
Definition: bounds.h:45
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.
Definition: polygons.cpp:250
bool equals(const nav_2d_msgs::Polygon2D &polygon0, const nav_2d_msgs::Polygon2D &polygon1)
check if two polygons are equal. Used in testing
Definition: polygons.cpp:350
std::vector< nav_2d_msgs::Point2D > triangulate(const nav_2d_msgs::ComplexPolygon2D &polygon)
Decompose a complex polygon into a set of triangles.
Definition: polygons.cpp:462
Exception to throw when Polygon doesn&#39;t load correctly.
Definition: polygons.h:52
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.
Definition: polygons.cpp:339
nav_2d_msgs::Polygon2D polygonFromRadius(const double radius, const unsigned int num_points=16)
Create a "circular" polygon from a given radius.
Definition: polygons.cpp:112
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.
Definition: polygons.cpp:311
TFSIMD_FORCE_INLINE const tfScalar & x() const
PolygonParseException(const std::string &description)
Definition: polygons.h:55
nav_2d_msgs::Polygon2D polygonFromParallelArrays(const std::vector< double > &xs, const std::vector< double > &ys)
Create a polygon from two parallel arrays.
Definition: polygons.cpp:317
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.
Definition: polygons.cpp:404
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...
Definition: polygons.cpp:127
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.
Definition: polygons.cpp:366
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.
Definition: polygons.cpp:287
bool isInside(const nav_2d_msgs::Polygon2D &polygon, const double x, const double y)
Check if a given point is inside of a polygon.
Definition: polygons.cpp:382


nav_2d_utils
Author(s):
autogenerated on Sun Jan 10 2021 04:08:32