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 <geometry_msgs/Pose2D.h>
41 #include <vector>
42 #include <string>
43 
44 namespace nav_2d_utils
45 {
46 
51 class PolygonParseException: public std::runtime_error
52 {
53 public:
54  explicit PolygonParseException(const std::string& description) : std::runtime_error(description) {}
55 };
56 
64 std::vector<std::vector<double> > parseVVD(const std::string& input);
65 
73 nav_2d_msgs::Polygon2D polygonFromRadius(const double radius, const unsigned int num_points = 16);
74 
82 nav_2d_msgs::Polygon2D polygonFromString(const std::string& polygon_string);
83 
91 nav_2d_msgs::Polygon2D polygonFromParams(const ros::NodeHandle& nh, const std::string parameter_name,
92  bool search = true);
93 
101 nav_2d_msgs::Polygon2D polygonFromXMLRPC(XmlRpc::XmlRpcValue& polygon_xmlrpc);
102 
109 XmlRpc::XmlRpcValue polygonToXMLRPC(const nav_2d_msgs::Polygon2D& polygon, bool array_of_arrays = true);
110 
118 void polygonToParams(const nav_2d_msgs::Polygon2D& polygon, const ros::NodeHandle& nh, const std::string parameter_name,
119  bool array_of_arrays = true);
120 
127 nav_2d_msgs::Polygon2D polygonFromParallelArrays(const std::vector<double>& xs, const std::vector<double>& ys);
128 
136 void polygonToParallelArrays(const nav_2d_msgs::Polygon2D polygon, std::vector<double>& xs, std::vector<double>& ys);
137 
141 bool equals(const nav_2d_msgs::Polygon2D& polygon0, const nav_2d_msgs::Polygon2D& polygon1);
142 
149 nav_2d_msgs::Polygon2D movePolygonToPose(const nav_2d_msgs::Polygon2D& polygon,
150  const geometry_msgs::Pose2D& pose);
151 
162 bool isInside(const nav_2d_msgs::Polygon2D& polygon, const double x, const double y);
163 
170 void calculateMinAndMaxDistances(const nav_2d_msgs::Polygon2D& polygon, double& min_dist, double& max_dist);
171 
172 } // namespace nav_2d_utils
173 
174 #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:193
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:48
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:249
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:349
Exception to throw when Polygon doesn&#39;t load correctly.
Definition: polygons.h:51
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:338
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:111
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:310
TFSIMD_FORCE_INLINE const tfScalar & x() const
PolygonParseException(const std::string &description)
Definition: polygons.h:54
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:316
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:403
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:126
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:365
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:286
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:381


nav_2d_utils
Author(s):
autogenerated on Wed Jun 26 2019 20:06:11