base.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_BASE_H
31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H
32 
33 #include <ros/ros.h>
34 
35 #include <geometry_msgs/PolygonStamped.h>
36 #include <nav_msgs/OccupancyGrid.h>
37 
38 #include <costmap_cspace_msgs/CSpace3D.h>
39 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
40 
41 #include <algorithm>
42 #include <map>
43 #include <string>
44 
45 namespace costmap_cspace
46 {
47 class CSpace3DMsg : public costmap_cspace_msgs::CSpace3D
48 {
49 public:
50  using Ptr = std::shared_ptr<CSpace3DMsg>;
51  using ConstPtr = std::shared_ptr<const CSpace3DMsg>;
52  size_t address(const int& x, const int& y, const int& yaw) const
53  {
54  return (yaw * info.height + y) * info.width + x;
55  }
56  const int8_t& getCost(const int& x, const int& y, const int& yaw) const
57  {
58  ROS_ASSERT(static_cast<size_t>(yaw) < info.angle);
59  ROS_ASSERT(static_cast<size_t>(x) < info.width);
60  ROS_ASSERT(static_cast<size_t>(y) < info.height);
61 
62  const size_t addr = address(x, y, yaw);
63  ROS_ASSERT(addr < data.size());
64 
65  return data[addr];
66  }
67  int8_t& getCost(const int& x, const int& y, const int& yaw)
68  {
69  ROS_ASSERT(static_cast<size_t>(yaw) < info.angle);
70  ROS_ASSERT(static_cast<size_t>(x) < info.width);
71  ROS_ASSERT(static_cast<size_t>(y) < info.height);
72 
73  const size_t addr = address(x, y, yaw);
74  ROS_ASSERT(addr < data.size());
75 
76  return data[addr];
77  }
78 };
79 
81 {
84 };
85 
87 {
88 public:
89  int x_, y_, yaw_;
90  int width_, height_, angle_;
92 
94  : x_(0)
95  , y_(0)
96  , yaw_(0)
97  , width_(0)
98  , height_(0)
99  , angle_(0)
100  , stamp_(0)
101  {
102  }
104  const int& x, const int& y, const int& yaw,
105  const int& width, const int& height, const int& angle,
106  const ros::Time& stamp = ros::Time())
107  : x_(x)
108  , y_(y)
109  , yaw_(yaw)
110  , width_(width)
111  , height_(height)
112  , angle_(angle)
113  , stamp_(stamp)
114  {
115  }
116  void merge(const UpdatedRegion& region)
117  {
118  if (region.width_ == 0 || region.height_ == 0 || region.angle_ == 0)
119  return;
120  if (region.stamp_ > stamp_)
121  stamp_ = region.stamp_;
122 
123  if (width_ == 0 || height_ == 0 || angle_ == 0)
124  {
125  *this = region;
126  return;
127  }
128  int x2 = x_ + width_;
129  int y2 = y_ + height_;
130  int yaw2 = yaw_ + angle_;
131 
132  const int mx2 = region.x_ + region.width_;
133  const int my2 = region.y_ + region.height_;
134  const int myaw2 = region.yaw_ + region.angle_;
135 
136  if (region.x_ < x_)
137  x_ = region.x_;
138  if (region.y_ < y_)
139  y_ = region.y_;
140  if (region.yaw_ < yaw_)
141  yaw_ = region.yaw_;
142 
143  if (x2 < mx2)
144  x2 = mx2;
145  if (y2 < my2)
146  y2 = my2;
147  if (yaw2 < myaw2)
148  yaw2 = myaw2;
149 
150  width_ = x2 - x_;
151  height_ = y2 - y_;
152  angle_ = yaw2 - yaw_;
153  }
154  void expand(const int& ex)
155  {
156  ROS_ASSERT(ex >= 0);
157  x_ -= ex;
158  y_ -= ex;
159  width_ += 2 * ex;
160  height_ += 2 * ex;
161  }
162  void normalize()
163  {
164  const int x2 = x_ + width_;
165  const int y2 = y_ + height_;
166  if (x_ < 0)
167  x_ = 0;
168  if (y_ < 0)
169  y_ = 0;
170 
171  width_ = x2 - x_;
172  height_ = y2 - y_;
173  }
174  void bitblt(const CSpace3DMsg::Ptr& dest, const CSpace3DMsg::ConstPtr& src)
175  {
176  ROS_ASSERT(dest->info.angle == src->info.angle);
177  ROS_ASSERT(dest->info.width == src->info.width);
178  ROS_ASSERT(dest->info.height == src->info.height);
179 
180  normalize();
181  const size_t copy_length =
182  std::min<size_t>(width_, src->info.width - x_) *
183  sizeof(src->data[0]);
184  for (
185  size_t a = yaw_;
186  static_cast<int>(a) < yaw_ + angle_ && a < src->info.angle;
187  ++a)
188  {
189  auto dest_pos = &dest->data[dest->address(x_, y_, a)];
190  auto src_pos = &src->data[src->address(x_, y_, a)];
191  const auto dest_stride = dest->info.width * sizeof(dest->data[0]);
192  const auto src_stride = src->info.width * sizeof(src->data[0]);
193  for (
194  size_t y = y_;
195  static_cast<int>(y) < y_ + height_ && y < src->info.height;
196  ++y)
197  {
198  memcpy(
199  dest_pos, src_pos, copy_length);
200  src_pos += src_stride;
201  dest_pos += dest_stride;
202  }
203  }
204  }
205 };
206 
208 {
209 public:
210  using Ptr = std::shared_ptr<Costmap3dLayerBase>;
211 
212 protected:
215  bool root_;
216 
219 
223  nav_msgs::OccupancyGrid::ConstPtr map_updated_;
224 
225 public:
227  : ang_grid_(-1)
228  , overlay_mode_(MapOverlayMode::MAX)
229  , root_(true)
230  , map_(new CSpace3DMsg)
231  , map_overlay_(new CSpace3DMsg)
232  {
233  }
234 
235  virtual void loadConfig(XmlRpc::XmlRpcValue config) = 0;
236  virtual void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D& info) = 0;
237 
239  const int ang_resolution)
240  {
241  ang_grid_ = ang_resolution;
242  }
244  const MapOverlayMode overlay_mode)
245  {
246  overlay_mode_ = overlay_mode;
247  }
249  {
250  child_ = child;
251  child_->setMap(getMapOverlay());
252  child_->root_ = false;
253  }
254  void setBaseMap(const nav_msgs::OccupancyGrid::ConstPtr& base_map)
255  {
256  ROS_ASSERT(root_);
257  ROS_ASSERT(ang_grid_ > 0);
258  ROS_ASSERT(base_map->data.size() >= base_map->info.width * base_map->info.height);
259 
260  const size_t xy_size = base_map->info.width * base_map->info.height;
261  map_->header = base_map->header;
262  map_->info.width = base_map->info.width;
263  map_->info.height = base_map->info.height;
264  map_->info.angle = ang_grid_;
265  map_->info.linear_resolution = base_map->info.resolution;
266  map_->info.angular_resolution = 2.0 * M_PI / ang_grid_;
267  map_->info.origin = base_map->info.origin;
268  map_->data.resize(xy_size * map_->info.angle);
269 
270  setMapMetaData(map_->info);
271 
272  for (size_t yaw = 0; yaw < map_->info.angle; yaw++)
273  {
274  for (unsigned int i = 0; i < xy_size; i++)
275  {
276  map_->data[i + yaw * xy_size] = 0;
277  }
278  }
279  updateCSpace(
280  base_map,
282  0, 0, 0,
283  map_->info.width, map_->info.height, map_->info.angle,
284  map_->header.stamp));
285  for (size_t yaw = 0; yaw < map_->info.angle; yaw++)
286  {
287  for (unsigned int i = 0; i < xy_size; i++)
288  {
289  if (base_map->data[i] < 0)
290  {
291  map_->data[i + yaw * xy_size] = -1;
292  }
293  }
294  }
295  *map_overlay_ = *map_;
296  if (child_)
297  child_->setBaseMapChain();
298 
299  updateChainEntry(
301  0, 0, 0, map_->info.width, map_->info.height, map_->info.angle,
302  base_map->header.stamp));
303  }
304  void processMapOverlay(const nav_msgs::OccupancyGrid::ConstPtr& msg)
305  {
306  ROS_ASSERT(!root_);
307  ROS_ASSERT(ang_grid_ > 0);
308  const int ox =
309  lroundf((msg->info.origin.position.x - map_->info.origin.position.x) /
310  map_->info.linear_resolution);
311  const int oy =
312  lroundf((msg->info.origin.position.y - map_->info.origin.position.y) /
313  map_->info.linear_resolution);
314 
315  const int w =
316  lroundf(msg->info.width * msg->info.resolution / map_->info.linear_resolution);
317  const int h =
318  lroundf(msg->info.height * msg->info.resolution / map_->info.linear_resolution);
319 
320  map_updated_ = msg;
321 
322  region_ = UpdatedRegion(ox, oy, 0, w, h, map_->info.angle, msg->header.stamp);
323  updateChainEntry(UpdatedRegion(ox, oy, 0, w, h, map_->info.angle, msg->header.stamp));
324  }
326  {
327  return map_;
328  }
330  {
331  map_ = map;
332  }
334  {
335  return map_overlay_;
336  }
337  int getAngularGrid() const
338  {
339  return ang_grid_;
340  }
341 
342 protected:
343  virtual bool updateChain(const bool output) = 0;
344  virtual void updateCSpace(
345  const nav_msgs::OccupancyGrid::ConstPtr& map,
346  const UpdatedRegion& region) = 0;
347  virtual int getRangeMax() const = 0;
348 
349  bool updateChainEntry(const UpdatedRegion& region, bool output = true)
350  {
351  auto region_expand = region;
352  region_expand.expand(getRangeMax());
353 
354  region_.merge(region_expand);
355 
356  auto region_prev_now = region_;
357  region_prev_now.merge(region_prev_);
358  region_prev_ = region_;
359 
360  region_prev_now.bitblt(map_overlay_, map_);
361  if (map_updated_)
362  {
363  if (map_->header.frame_id == map_updated_->header.frame_id)
364  {
365  updateCSpace(map_updated_, region_);
366  }
367  else
368  {
369  ROS_ERROR("map and map_overlay must have same frame_id. skipping");
370  }
371  }
372 
373  if (updateChain(output))
374  output = false;
375 
376  if (child_)
377  {
378  return child_->updateChainEntry(region_, output);
379  }
380  return false;
381  }
383  {
384  setMapMetaData(map_->info);
385  *map_overlay_ = *map_;
386  if (child_)
387  child_->setBaseMapChain();
388  }
389 };
390 } // namespace costmap_cspace
391 
392 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H
UpdatedRegion(const int &x, const int &y, const int &yaw, const int &width, const int &height, const int &angle, const ros::Time &stamp=ros::Time())
Definition: base.h:103
MapOverlayMode overlay_mode_
Definition: base.h:214
void bitblt(const CSpace3DMsg::Ptr &dest, const CSpace3DMsg::ConstPtr &src)
Definition: base.h:174
const int8_t & getCost(const int &x, const int &y, const int &yaw) const
Definition: base.h:56
void merge(const UpdatedRegion &region)
Definition: base.h:116
CSpace3DMsg::Ptr getMap()
Definition: base.h:325
void expand(const int &ex)
Definition: base.h:154
CSpace3DMsg::Ptr map_overlay_
Definition: base.h:218
Costmap3dLayerBase::Ptr child_
Definition: base.h:220
void setOverlayMode(const MapOverlayMode overlay_mode)
Definition: base.h:243
void setBaseMap(const nav_msgs::OccupancyGrid::ConstPtr &base_map)
Definition: base.h:254
int8_t & getCost(const int &x, const int &y, const int &yaw)
Definition: base.h:67
nav_msgs::OccupancyGrid::ConstPtr map_updated_
Definition: base.h:223
MapOverlayMode
Definition: base.h:80
void setAngleResolution(const int ang_resolution)
Definition: base.h:238
void processMapOverlay(const nav_msgs::OccupancyGrid::ConstPtr &msg)
Definition: base.h:304
TFSIMD_FORCE_INLINE Vector3 & normalize()
bool updateChainEntry(const UpdatedRegion &region, bool output=true)
Definition: base.h:349
TFSIMD_FORCE_INLINE const tfScalar & w() const
void setChild(Costmap3dLayerBase::Ptr child)
Definition: base.h:248
std::shared_ptr< CSpace3DMsg > Ptr
Definition: base.h:50
std::shared_ptr< Costmap3dLayerBase > Ptr
Definition: base.h:210
size_t address(const int &x, const int &y, const int &yaw) const
Definition: base.h:52
std::shared_ptr< const CSpace3DMsg > ConstPtr
Definition: base.h:51
#define ROS_ASSERT(cond)
#define ROS_ERROR(...)
CSpace3DMsg::Ptr getMapOverlay()
Definition: base.h:333
void setMap(CSpace3DMsg::Ptr map)
Definition: base.h:329


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