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 <ros/ros.h>
34 #include <vector>
35 
37 
38 namespace costmap_cspace
39 {
40 class Vec
41 {
42 public:
43  float c[2];
44  float& operator[](const int& i)
45  {
46  ROS_ASSERT(i < 2);
47  return c[i];
48  }
49  const float& operator[](const int& i) const
50  {
51  ROS_ASSERT(i < 2);
52  return c[i];
53  }
54  Vec operator-(const Vec& a) const
55  {
56  Vec out = *this;
57  out[0] -= a[0];
58  out[1] -= a[1];
59  return out;
60  }
61  float cross(const Vec& a) const
62  {
63  return (*this)[0] * a[1] - (*this)[1] * a[0];
64  }
65  float dot(const Vec& a) const
66  {
67  return (*this)[0] * a[0] + (*this)[1] * a[1];
68  }
69  float dist(const Vec& a) const
70  {
71  return hypotf((*this)[0] - a[0], (*this)[1] - a[1]);
72  }
73  float dist_line(const Vec& a, const Vec& b) const
74  {
75  return (b - a).cross((*this) - a) / b.dist(a);
76  }
77  float dist_linestrip(const Vec& a, const Vec& b) const
78  {
79  if ((b - a).dot((*this) - a) <= 0)
80  return this->dist(a);
81  if ((a - b).dot((*this) - b) <= 0)
82  return this->dist(b);
83  return fabs(this->dist_line(a, b));
84  }
85 };
86 class Polygon
87 {
88 public:
89  std::vector<Vec> v;
90 
92  {
93  }
94  explicit Polygon(const XmlRpc::XmlRpcValue footprint_xml_const)
95  {
96  XmlRpc::XmlRpcValue footprint_xml = footprint_xml_const;
97  if (footprint_xml.getType() != XmlRpc::XmlRpcValue::TypeArray || footprint_xml.size() < 3)
98  {
99  throw std::runtime_error("Invalid footprint xml.");
100  }
101 
102  for (int i = 0; i < footprint_xml.size(); i++)
103  {
104  Vec p;
105  try
106  {
107  p[0] = static_cast<double>(footprint_xml[i][0]);
108  p[1] = static_cast<double>(footprint_xml[i][1]);
109  }
110  catch (XmlRpc::XmlRpcException& e)
111  {
112  throw std::runtime_error(("Invalid footprint xml." + e.getMessage()).c_str());
113  }
114 
115  v.push_back(p);
116  }
117  v.push_back(v.front());
118  }
119  geometry_msgs::PolygonStamped toMsg() const
120  {
121  geometry_msgs::PolygonStamped msg;
122 
123  msg.polygon.points.clear();
124  msg.header.frame_id = "base_link";
125  for (const auto& p : v)
126  {
127  geometry_msgs::Point32 point;
128  point.x = p[0];
129  point.y = p[1];
130  point.z = 0;
131  msg.polygon.points.push_back(point);
132  }
133  msg.polygon.points.push_back(msg.polygon.points[0]);
134 
135  return msg;
136  }
137  float radius() const
138  {
139  float radius = 0;
140  for (const auto& p : v)
141  {
142  const auto dist = hypotf(p[0], p[1]);
143  if (dist > radius)
144  radius = dist;
145  }
146  return radius;
147  }
148  void move(const float& x, const float& y, const float& yaw)
149  {
150  float cos_v = cosf(yaw);
151  float sin_v = sinf(yaw);
152  for (auto& p : v)
153  {
154  auto tmp = p;
155  p[0] = cos_v * tmp[0] - sin_v * tmp[1] + x;
156  p[1] = sin_v * tmp[0] + cos_v * tmp[1] + y;
157  }
158  }
159  bool inside(const Vec& a) const
160  {
161  int cn = 0;
162  for (size_t i = 0; i < v.size() - 1; i++)
163  {
164  auto& v1 = v[i];
165  auto& v2 = v[i + 1];
166  if ((v1[1] <= a[1] && a[1] < v2[1]) ||
167  (v2[1] <= a[1] && a[1] < v1[1]))
168  {
169  float lx;
170  lx = v1[0] + (v2[0] - v1[0]) * (a[1] - v1[1]) / (v2[1] - v1[1]);
171  if (a[0] < lx)
172  cn++;
173  }
174  }
175  return ((cn & 1) == 1);
176  }
177  float dist(const Vec& a) const
178  {
179  float dist = FLT_MAX;
180  for (size_t i = 0; i < v.size() - 1; i++)
181  {
182  auto& v1 = v[i];
183  auto& v2 = v[i + 1];
184  auto d = a.dist_linestrip(v1, v2);
185  if (d < dist)
186  dist = d;
187  }
188  return dist;
189  }
190 };
191 } // namespace costmap_cspace
192 
193 #endif // COSTMAP_CSPACE_POLYGON_H
Polygon(const XmlRpc::XmlRpcValue footprint_xml_const)
Definition: polygon.h:94
d
float dist_linestrip(const Vec &a, const Vec &b) const
Definition: polygon.h:77
const std::string & getMessage() const
float dot(const Vec &a) const
Definition: polygon.h:65
float cross(const Vec &a) const
Definition: polygon.h:61
int size() const
void move(const float &x, const float &y, const float &yaw)
Definition: polygon.h:148
geometry_msgs::PolygonStamped toMsg() const
Definition: polygon.h:119
Type const & getType() const
std::vector< Vec > v
Definition: polygon.h:89
const float & operator[](const int &i) const
Definition: polygon.h:49
bool inside(const Vec &a) const
Definition: polygon.h:159
float & operator[](const int &i)
Definition: polygon.h:44
float dist(const Vec &a) const
Definition: polygon.h:69
float dist(const Vec &a) const
Definition: polygon.h:177
float radius() const
Definition: polygon.h:137
#define ROS_ASSERT(cond)
float dist_line(const Vec &a, const Vec &b) const
Definition: polygon.h:73
Vec operator-(const Vec &a) const
Definition: polygon.h:54


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 04:59:48