polygon.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2017, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef COSTMAP_CSPACE_POLYGON_H
31 #define COSTMAP_CSPACE_POLYGON_H
32 
33 #include <cmath>
34 #include <limits>
35 #include <utility>
36 #include <vector>
37 
38 #include <ros/ros.h>
39 
41 
42 namespace costmap_cspace
43 {
44 class Vec
45 {
46 public:
47  float c[2];
48  float& operator[](const int& i)
49  {
50  ROS_ASSERT(i < 2);
51  return c[i];
52  }
53  const float& operator[](const int& i) const
54  {
55  ROS_ASSERT(i < 2);
56  return c[i];
57  }
58  Vec operator-(const Vec& a) const
59  {
60  Vec out = *this;
61  out[0] -= a[0];
62  out[1] -= a[1];
63  return out;
64  }
65  float cross(const Vec& a) const
66  {
67  return (*this)[0] * a[1] - (*this)[1] * a[0];
68  }
69  float dot(const Vec& a) const
70  {
71  return (*this)[0] * a[0] + (*this)[1] * a[1];
72  }
73  float dist(const Vec& a) const
74  {
75  return std::hypot((*this)[0] - a[0], (*this)[1] - a[1]);
76  }
77  float dist_line(const Vec& a, const Vec& b) const
78  {
79  return (b - a).cross((*this) - a) / b.dist(a);
80  }
81  float dist_linestrip(const Vec& a, const Vec& b) const
82  {
83  if ((b - a).dot((*this) - a) <= 0)
84  return this->dist(a);
85  if ((a - b).dot((*this) - b) <= 0)
86  return this->dist(b);
87  return std::abs(this->dist_line(a, b));
88  }
89 };
90 class Polygon
91 {
92 public:
93  std::vector<Vec> v;
94 
96  {
97  }
98  explicit Polygon(const XmlRpc::XmlRpcValue footprint_xml_const)
99  {
100  XmlRpc::XmlRpcValue footprint_xml = footprint_xml_const;
101  if (footprint_xml.getType() != XmlRpc::XmlRpcValue::TypeArray || footprint_xml.size() < 3)
102  {
103  throw std::runtime_error("Invalid footprint xml.");
104  }
105 
106  for (int i = 0; i < footprint_xml.size(); i++)
107  {
108  Vec p;
109  try
110  {
111  p[0] = static_cast<double>(footprint_xml[i][0]);
112  p[1] = static_cast<double>(footprint_xml[i][1]);
113  }
114  catch (XmlRpc::XmlRpcException& e)
115  {
116  throw std::runtime_error(("Invalid footprint xml." + e.getMessage()).c_str());
117  }
118 
119  v.push_back(p);
120  }
121  v.push_back(v.front());
122  }
123  geometry_msgs::PolygonStamped toMsg() const
124  {
125  geometry_msgs::PolygonStamped msg;
126 
127  msg.polygon.points.clear();
128  msg.header.frame_id = "base_link";
129  for (const auto& p : v)
130  {
131  geometry_msgs::Point32 point;
132  point.x = p[0];
133  point.y = p[1];
134  point.z = 0;
135  msg.polygon.points.push_back(point);
136  }
137  msg.polygon.points.push_back(msg.polygon.points[0]);
138 
139  return msg;
140  }
141  float radius() const
142  {
143  float radius = 0;
144  for (const auto& p : v)
145  {
146  const auto dist = std::hypot(p[0], p[1]);
147  if (dist > radius)
148  radius = dist;
149  }
150  return radius;
151  }
152  void move(const float& x, const float& y, const float& yaw)
153  {
154  float cos_v = cosf(yaw);
155  float sin_v = sinf(yaw);
156  for (auto& p : v)
157  {
158  auto tmp = p;
159  p[0] = cos_v * tmp[0] - sin_v * tmp[1] + x;
160  p[1] = sin_v * tmp[0] + cos_v * tmp[1] + y;
161  }
162  }
163  bool inside(const Vec& a) const
164  {
165  int cn = 0;
166  for (size_t i = 0; i < v.size() - 1; i++)
167  {
168  auto& v1 = v[i];
169  auto& v2 = v[i + 1];
170  if ((v1[1] <= a[1] && a[1] < v2[1]) ||
171  (v2[1] <= a[1] && a[1] < v1[1]))
172  {
173  float lx;
174  lx = v1[0] + (v2[0] - v1[0]) * (a[1] - v1[1]) / (v2[1] - v1[1]);
175  if (a[0] < lx)
176  cn++;
177  }
178  }
179  return ((cn & 1) == 1);
180  }
181  float dist(const Vec& a) const
182  {
183  float dist = std::numeric_limits<float>::max();
184  for (size_t i = 0; i < v.size() - 1; i++)
185  {
186  auto& v1 = v[i];
187  auto& v2 = v[i + 1];
188  auto d = a.dist_linestrip(v1, v2);
189  if (d < dist)
190  dist = d;
191  }
192  return dist;
193  }
194 };
195 } // namespace costmap_cspace
196 
197 #endif // COSTMAP_CSPACE_POLYGON_H
Polygon(const XmlRpc::XmlRpcValue footprint_xml_const)
Definition: polygon.h:98
d
float dist_linestrip(const Vec &a, const Vec &b) const
Definition: polygon.h:81
const std::string & getMessage() const
float dot(const Vec &a) const
Definition: polygon.h:69
float cross(const Vec &a) const
Definition: polygon.h:65
int size() const
void move(const float &x, const float &y, const float &yaw)
Definition: polygon.h:152
geometry_msgs::PolygonStamped toMsg() const
Definition: polygon.h:123
Type const & getType() const
std::vector< Vec > v
Definition: polygon.h:93
const float & operator[](const int &i) const
Definition: polygon.h:53
bool inside(const Vec &a) const
Definition: polygon.h:163
float & operator[](const int &i)
Definition: polygon.h:48
float dist(const Vec &a) const
Definition: polygon.h:73
float dist(const Vec &a) const
Definition: polygon.h:181
float radius() const
Definition: polygon.h:141
#define ROS_ASSERT(cond)
float dist_line(const Vec &a, const Vec &b) const
Definition: polygon.h:77
Vec operator-(const Vec &a) const
Definition: polygon.h:58


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:29