footprint.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2019, 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 <algorithm>
34 #include <cmath>
35 #include <memory>
36 #include <vector>
37 
38 #include <ros/ros.h>
39 
40 #include <costmap_cspace_msgs/CSpace3D.h>
41 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
42 #include <geometry_msgs/PolygonStamped.h>
43 #include <nav_msgs/OccupancyGrid.h>
44 
45 #include <xmlrpcpp/XmlRpcValue.h>
46 
49 #include <costmap_cspace/polygon.h>
50 
51 namespace costmap_cspace
52 {
54 {
55 public:
56  using Ptr = std::shared_ptr<Costmap3dLayerFootprint>;
57 
58 protected:
60  geometry_msgs::PolygonStamped footprint_;
65 
68  std::vector<bool> unknown_buf_;
69 
70 public:
72  : linear_expand_(0.0)
73  , linear_spread_(0.0)
74  , keep_unknown_(false)
75  , range_max_(0)
76  {
77  }
79  {
81  static_cast<double>(config["linear_expand"]),
82  static_cast<double>(config["linear_spread"]));
83  setFootprint(costmap_cspace::Polygon(config["footprint"]));
84  if (config.hasMember("keep_unknown"))
85  setKeepUnknown(config["keep_unknown"]);
86  }
87  void setKeepUnknown(const bool keep_unknown)
88  {
89  keep_unknown_ = keep_unknown;
90  }
92  const float linear_expand,
93  const float linear_spread)
94  {
95  linear_expand_ = linear_expand;
96  linear_spread_ = linear_spread;
97 
98  ROS_ASSERT(linear_expand >= 0.0);
99  ROS_ASSERT(std::isfinite(linear_expand));
100  ROS_ASSERT(linear_spread >= 0.0);
101  ROS_ASSERT(std::isfinite(linear_spread));
102  }
103  void setFootprint(const Polygon footprint)
104  {
105  footprint_p_ = footprint;
106  footprint_radius_ = footprint.radius();
107  footprint_ = footprint.toMsg();
108  }
110  {
111  return footprint_p_;
112  }
113  const geometry_msgs::PolygonStamped& getFootprintMsg() const
114  {
115  return footprint_;
116  }
117  float getFootprintRadius() const
118  {
119  return footprint_radius_;
120  }
121  int getRangeMax() const
122  {
123  return range_max_;
124  }
125  const CSpace3Cache& getTemplate() const
126  {
127  return cs_template_;
128  }
129  void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D& info)
130  {
131  ROS_ASSERT(footprint_p_.v.size() > 2);
132 
133  range_max_ =
134  std::ceil((footprint_radius_ + linear_expand_ + linear_spread_) / info.linear_resolution);
135  cs_template_.reset(range_max_, range_max_, info.angle);
136 
137  // C-Space template
138  for (size_t yaw = 0; yaw < info.angle; yaw++)
139  {
140  for (int y = -range_max_; y <= range_max_; y++)
141  {
142  for (int x = -range_max_; x <= range_max_; x++)
143  {
144  auto f = footprint_p_;
145  f.move(x * info.linear_resolution,
146  y * info.linear_resolution,
147  yaw * info.angular_resolution);
148  Vec p;
149  p[0] = 0;
150  p[1] = 0;
151  if (f.inside(p))
152  {
153  cs_template_.e(x, y, yaw) = 100;
154  }
155  else
156  {
157  const float d = f.dist(p);
158  if (d < linear_expand_)
159  {
160  cs_template_.e(x, y, yaw) = 100;
161  }
162  else if (d < linear_expand_ + linear_spread_)
163  {
164  cs_template_.e(x, y, yaw) = 100 - (d - linear_expand_) * 100 / linear_spread_;
165  }
166  else
167  {
168  cs_template_.e(x, y, yaw) = 0;
169  }
170  }
171  }
172  }
173  if (footprint_radius_ == 0)
174  cs_template_.e(0, 0, yaw) = 100;
175  }
176  }
177 
178 protected:
179  bool updateChain(const bool output)
180  {
181  return false;
182  }
184  const nav_msgs::OccupancyGrid::ConstPtr& map,
185  const UpdatedRegion& region)
186  {
187  if (root_)
188  generateCSpace(map_, map, region);
189  else
190  generateCSpace(map_overlay_, map, region);
191  }
192  virtual void generateCSpace(
193  CSpace3DMsg::Ptr map,
194  const nav_msgs::OccupancyGrid::ConstPtr& msg,
195  const UpdatedRegion& region)
196  {
197  ROS_ASSERT(ang_grid_ > 0);
198  clearTravelableArea(map, msg);
199  for (size_t yaw = 0; yaw < map->info.angle; yaw++)
200  {
201  generateSpecifiedCSpace(map, msg, yaw);
202  }
203  }
204 
205  // Clear travelable area in OVERWRITE mode
207  CSpace3DMsg::Ptr map,
208  const nav_msgs::OccupancyGrid::ConstPtr& msg)
209  {
210  if (overlay_mode_ != OVERWRITE || root_)
211  {
212  return;
213  }
214  const int ox =
215  std::lround((msg->info.origin.position.x - map->info.origin.position.x) /
216  map->info.linear_resolution);
217  const int oy =
218  std::lround((msg->info.origin.position.y - map->info.origin.position.y) /
219  map->info.linear_resolution);
220  const double resolution_scale = msg->info.resolution / map->info.linear_resolution;
221 
222  for (size_t yaw = 0; yaw < map->info.angle; yaw++)
223  {
224  for (size_t i = 0; i < msg->data.size(); i++)
225  {
226  const auto& val = msg->data[i];
227  if (val < 0)
228  continue;
229 
230  const int x = std::lround((i % msg->info.width) * resolution_scale);
231  if (x < range_max_ || static_cast<int>(msg->info.width) - range_max_ <= x)
232  continue;
233  const int y = std::lround((i / msg->info.width) * resolution_scale);
234  if (y < range_max_ || static_cast<int>(msg->info.height) - range_max_ <= y)
235  continue;
236 
237  const int res_up = std::ceil(resolution_scale);
238  for (int yp = 0; yp < res_up; yp++)
239  {
240  const int y2 = y + oy + yp;
241  if (static_cast<size_t>(y2) >= map->info.height)
242  continue;
243  for (int xp = 0; xp < res_up; xp++)
244  {
245  const int x2 = x + ox + xp;
246  if (static_cast<size_t>(x2) >= map->info.width)
247  continue;
248 
249  map->getCost(x2, y2, yaw) = -1;
250  }
251  }
252  }
253  }
254  }
256  CSpace3DMsg::Ptr map,
257  const nav_msgs::OccupancyGrid::ConstPtr& msg,
258  const size_t yaw)
259  {
260  const int ox =
261  std::lround((msg->info.origin.position.x - map->info.origin.position.x) /
262  map->info.linear_resolution);
263  const int oy =
264  std::lround((msg->info.origin.position.y - map->info.origin.position.y) /
265  map->info.linear_resolution);
266  const double resolution_scale = msg->info.resolution / map->info.linear_resolution;
267  if (keep_unknown_)
268  {
269  unknown_buf_.resize(msg->data.size());
270  for (size_t i = 0; i < msg->data.size(); i++)
271  {
272  const int gx = std::lround((i % msg->info.width) * resolution_scale) + ox;
273  const int gy = std::lround((i / msg->info.width) * resolution_scale) + oy;
274  if (static_cast<size_t>(gx) >= map->info.width ||
275  static_cast<size_t>(gy) >= map->info.height)
276  continue;
277  // If the cell is unknown in parent map and also updated map,
278  // the cell is never measured.
279  // Never measured cells should be marked unknown
280  // to be correctly processed in the planner.
281  unknown_buf_[i] = msg->data[i] < 0 && map->getCost(gx, gy, yaw) < 0;
282  }
283  }
284  for (size_t i = 0; i < msg->data.size(); i++)
285  {
286  const int8_t val = msg->data[i];
287  if (val < 0)
288  {
289  continue;
290  }
291  const int gx = std::lround((i % msg->info.width) * resolution_scale) + ox;
292  const int gy = std::lround((i / msg->info.width) * resolution_scale) + oy;
293  if (static_cast<size_t>(gx) >= map->info.width ||
294  static_cast<size_t>(gy) >= map->info.height)
295  continue;
296  if (val == 0)
297  {
298  int8_t& m = map->getCost(gx, gy, yaw);
299  if (m < 0)
300  m = 0;
301  continue;
302  }
303 
304  const int map_x_min = std::max(gx - range_max_, 0);
305  const int map_x_max = std::min(gx + range_max_, static_cast<int>(map->info.width) - 1);
306  const int map_y_min = std::max(gy - range_max_, 0);
307  const int map_y_max = std::min(gy + range_max_, static_cast<int>(map->info.height) - 1);
308  for (int map_y = map_y_min; map_y <= map_y_max; ++map_y)
309  {
310  // Use raw pointers for faster iteration
311  int8_t* cost_addr = &(map->getCost(map_x_min, map_y, yaw));
312  const char* cs_addr = &(cs_template_.e(map_x_min - gx, map_y - gy, yaw));
313  for (int n = 0; n <= map_x_max - map_x_min; ++n, ++cost_addr, ++cs_addr)
314  {
315  const int8_t c = *cs_addr * val / 100;
316  if (c > 0 && *cost_addr < c)
317  *cost_addr = c;
318  }
319  }
320  }
321  if (keep_unknown_)
322  {
323  for (size_t i = 0; i < unknown_buf_.size(); i++)
324  {
325  if (!unknown_buf_[i])
326  continue;
327  const int gx = std::lround((i % msg->info.width) * resolution_scale) + ox;
328  const int gy = std::lround((i / msg->info.width) * resolution_scale) + oy;
329  if (static_cast<size_t>(gx) >= map->info.width ||
330  static_cast<size_t>(gy) >= map->info.height)
331  continue;
332  map->getCost(gx, gy, yaw) = -1;
333  }
334  }
335  }
336 };
337 } // namespace costmap_cspace
338 
339 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H
d
MapOverlayMode overlay_mode_
Definition: base.h:259
void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D &info)
Definition: footprint.h:129
f
void setExpansion(const float linear_expand, const float linear_spread)
Definition: footprint.h:91
CSpace3DMsg::Ptr map_overlay_
Definition: base.h:263
void loadConfig(XmlRpc::XmlRpcValue config)
Definition: footprint.h:78
geometry_msgs::PolygonStamped footprint_
Definition: footprint.h:60
const CSpace3Cache & getTemplate() const
Definition: footprint.h:125
geometry_msgs::PolygonStamped toMsg() const
Definition: polygon.h:123
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< Vec > v
Definition: polygon.h:93
void setKeepUnknown(const bool keep_unknown)
Definition: footprint.h:87
void generateSpecifiedCSpace(CSpace3DMsg::Ptr map, const nav_msgs::OccupancyGrid::ConstPtr &msg, const size_t yaw)
Definition: footprint.h:255
TFSIMD_FORCE_INLINE const tfScalar & x() const
bool hasMember(const std::string &name) const
std::shared_ptr< CSpace3DMsg > Ptr
Definition: base.h:52
void reset(const int &x, const int &y, const int &yaw)
Definition: cspace3_cache.h:57
void updateCSpace(const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion &region)
Definition: footprint.h:183
float radius() const
Definition: polygon.h:141
bool updateChain(const bool output)
Definition: footprint.h:179
std::shared_ptr< Costmap3dLayerBase > Ptr
Definition: base.h:255
#define ROS_ASSERT(cond)
void setFootprint(const Polygon footprint)
Definition: footprint.h:103
char & e(const int &x, const int &y, const int &yaw)
Definition: cspace3_cache.h:73
virtual void generateCSpace(CSpace3DMsg::Ptr map, const nav_msgs::OccupancyGrid::ConstPtr &msg, const UpdatedRegion &region)
Definition: footprint.h:192
const geometry_msgs::PolygonStamped & getFootprintMsg() const
Definition: footprint.h:113
void clearTravelableArea(CSpace3DMsg::Ptr map, const nav_msgs::OccupancyGrid::ConstPtr &msg)
Definition: footprint.h:206


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