footprint.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2018, 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_COSTMAP_3D_LAYER_FOOTPRINT_H
31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H
32 
33 #include <ros/ros.h>
34 
35 #include <geometry_msgs/PolygonStamped.h>
36 #include <nav_msgs/OccupancyGrid.h>
37 #include <costmap_cspace_msgs/CSpace3D.h>
38 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
39 
40 #include <xmlrpcpp/XmlRpcValue.h>
41 
44 #include <costmap_cspace/polygon.h>
45 
46 namespace costmap_cspace
47 {
49 {
50 public:
51  using Ptr = std::shared_ptr<Costmap3dLayerFootprint>;
52 
53 protected:
55  geometry_msgs::PolygonStamped footprint_;
59 
62 
63 public:
65  : linear_expand_(0.0)
66  , linear_spread_(0.0)
67  , range_max_(0)
68  {
69  }
71  {
73  static_cast<double>(config["linear_expand"]),
74  static_cast<double>(config["linear_spread"]));
75  setFootprint(costmap_cspace::Polygon(config["footprint"]));
76  }
78  const float linear_expand,
79  const float linear_spread)
80  {
81  linear_expand_ = linear_expand;
82  linear_spread_ = linear_spread;
83 
84  ROS_ASSERT(linear_expand >= 0.0);
85  ROS_ASSERT(std::isfinite(linear_expand));
86  ROS_ASSERT(linear_spread >= 0.0);
87  ROS_ASSERT(std::isfinite(linear_spread));
88  }
89  void setFootprint(const Polygon footprint)
90  {
91  footprint_p_ = footprint;
92  footprint_radius_ = footprint.radius();
93  footprint_ = footprint.toMsg();
94  }
96  {
97  return footprint_p_;
98  }
99  const geometry_msgs::PolygonStamped& getFootprintMsg() const
100  {
101  return footprint_;
102  }
103  float getFootprintRadius() const
104  {
105  return footprint_radius_;
106  }
107  int getRangeMax() const
108  {
109  return range_max_;
110  }
111  const CSpace3Cache& getTemplate() const
112  {
113  return cs_template_;
114  }
115  void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D& info)
116  {
117  ROS_ASSERT(footprint_p_.v.size() > 2);
118 
119  range_max_ =
120  ceilf((footprint_radius_ + linear_expand_ + linear_spread_) / info.linear_resolution);
121  cs_template_.reset(range_max_, range_max_, info.angle);
122 
123  // C-Space template
124  for (size_t yaw = 0; yaw < info.angle; yaw++)
125  {
126  for (int y = -range_max_; y <= range_max_; y++)
127  {
128  for (int x = -range_max_; x <= range_max_; x++)
129  {
130  auto f = footprint_p_;
131  f.move(x * info.linear_resolution,
132  y * info.linear_resolution,
133  yaw * info.angular_resolution);
134  Vec p;
135  p[0] = 0;
136  p[1] = 0;
137  if (f.inside(p))
138  {
139  cs_template_.e(x, y, yaw) = 100;
140  }
141  else
142  {
143  const float d = f.dist(p);
144  if (d < linear_expand_)
145  {
146  cs_template_.e(x, y, yaw) = 100;
147  }
148  else if (d < linear_expand_ + linear_spread_)
149  {
150  cs_template_.e(x, y, yaw) = 100 - (d - linear_expand_) * 100 / linear_spread_;
151  }
152  else
153  {
154  cs_template_.e(x, y, yaw) = 0;
155  }
156  }
157  }
158  }
159  if (footprint_radius_ == 0)
160  cs_template_.e(0, 0, yaw) = 100;
161  }
162  }
163 
164 protected:
165  bool updateChain(const bool output)
166  {
167  return false;
168  }
170  const nav_msgs::OccupancyGrid::ConstPtr& map,
171  const UpdatedRegion& region)
172  {
173  if (root_)
174  gemerateCSpace(map_, map, region);
175  else
176  gemerateCSpace(map_overlay_, map, region);
177  }
179  CSpace3DMsg::Ptr map,
180  const nav_msgs::OccupancyGrid::ConstPtr& msg,
181  const UpdatedRegion& region)
182  {
183  ROS_ASSERT(ang_grid_ > 0);
184  const int ox =
185  lroundf((msg->info.origin.position.x - map->info.origin.position.x) /
186  map->info.linear_resolution);
187  const int oy =
188  lroundf((msg->info.origin.position.y - map->info.origin.position.y) /
189  map->info.linear_resolution);
190  // Clear travelable area in OVERWRITE mode
191  if (overlay_mode_ == OVERWRITE && !root_)
192  {
193  for (size_t yaw = 0; yaw < map->info.angle; yaw++)
194  {
195  for (unsigned int i = 0; i < msg->data.size(); i++)
196  {
197  const auto& val = msg->data[i];
198  if (val < 0)
199  continue;
200 
201  const int x =
202  lroundf((i % msg->info.width) * msg->info.resolution / map->info.linear_resolution);
203  if (x < range_max_ || static_cast<int>(msg->info.width) - range_max_ <= x)
204  continue;
205  const int y =
206  lroundf((i / msg->info.width) * msg->info.resolution / map->info.linear_resolution);
207  if (y < range_max_ || static_cast<int>(msg->info.height) - range_max_ <= y)
208  continue;
209 
210  const int res_up = ceilf(msg->info.resolution / map->info.linear_resolution);
211  for (int yp = 0; yp < res_up; yp++)
212  {
213  for (int xp = 0; xp < res_up; xp++)
214  {
215  const int x2 = x + ox + xp;
216  const int y2 = y + oy + yp;
217  if (static_cast<unsigned int>(x2) >= map->info.width ||
218  static_cast<unsigned int>(y2) >= map->info.height)
219  continue;
220 
221  auto& m = map->getCost(x2, y2, yaw);
222  m = 0;
223  }
224  }
225  }
226  }
227  }
228  // Get max
229  for (size_t yaw = 0; yaw < map->info.angle; yaw++)
230  {
231  for (unsigned int i = 0; i < msg->data.size(); i++)
232  {
233  const int gx = lroundf((i % msg->info.width) * msg->info.resolution / map->info.linear_resolution) + ox;
234  const int gy = lroundf((i / msg->info.width) * msg->info.resolution / map->info.linear_resolution) + oy;
235  if ((unsigned int)gx >= map->info.width ||
236  (unsigned int)gy >= map->info.height)
237  continue;
238 
239  auto val = msg->data[i];
240  if (val <= 0)
241  continue;
242 
243  for (int y = -range_max_; y <= range_max_; y++)
244  {
245  for (int x = -range_max_; x <= range_max_; x++)
246  {
247  const int x2 = gx + x;
248  const int y2 = gy + y;
249  if (static_cast<unsigned int>(x2) >= map->info.width ||
250  static_cast<unsigned int>(y2) >= map->info.height)
251  continue;
252 
253  auto& m = map->getCost(x2, y2, yaw);
254  const auto c = cs_template_.e(x, y, yaw) * val / 100;
255  if (m < c)
256  m = c;
257  }
258  }
259  }
260  }
261  }
262 };
263 } // namespace costmap_cspace
264 
265 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H
d
MapOverlayMode overlay_mode_
Definition: base.h:214
void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D &info)
Definition: footprint.h:115
f
void setExpansion(const float linear_expand, const float linear_spread)
Definition: footprint.h:77
CSpace3DMsg::Ptr map_overlay_
Definition: base.h:218
void loadConfig(XmlRpc::XmlRpcValue config)
Definition: footprint.h:70
geometry_msgs::PolygonStamped footprint_
Definition: footprint.h:55
const CSpace3Cache & getTemplate() const
Definition: footprint.h:111
geometry_msgs::PolygonStamped toMsg() const
Definition: polygon.h:119
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< Vec > v
Definition: polygon.h:89
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::shared_ptr< CSpace3DMsg > Ptr
Definition: base.h:50
void reset(const int &x, const int &y, const int &yaw)
Definition: cspace3_cache.h:55
void updateCSpace(const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion &region)
Definition: footprint.h:169
void gemerateCSpace(CSpace3DMsg::Ptr map, const nav_msgs::OccupancyGrid::ConstPtr &msg, const UpdatedRegion &region)
Definition: footprint.h:178
float radius() const
Definition: polygon.h:137
bool updateChain(const bool output)
Definition: footprint.h:165
std::shared_ptr< Costmap3dLayerBase > Ptr
Definition: base.h:210
#define ROS_ASSERT(cond)
void setFootprint(const Polygon footprint)
Definition: footprint.h:89
char & e(const int &x, const int &y, const int &yaw)
Definition: cspace3_cache.h:71
const geometry_msgs::PolygonStamped & getFootprintMsg() const
Definition: footprint.h:99


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