layered_costmap.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
39 #include <costmap_2d/footprint.h>
40 #include <cstdio>
41 #include <string>
42 #include <algorithm>
43 #include <vector>
44 
45 using std::vector;
46 
47 namespace costmap_2d
48 {
49 
50 LayeredCostmap::LayeredCostmap(std::string global_frame, bool rolling_window, bool track_unknown) :
51  costmap_(),
52  global_frame_(global_frame),
53  rolling_window_(rolling_window),
54  current_(false),
55  minx_(0.0),
56  miny_(0.0),
57  maxx_(0.0),
58  maxy_(0.0),
59  bx0_(0),
60  bxn_(0),
61  by0_(0),
62  byn_(0),
63  initialized_(false),
64  size_locked_(false),
65  circumscribed_radius_(1.0),
66  inscribed_radius_(0.1)
67 {
68  if (track_unknown)
70  else
72 }
73 
75 {
76  while (plugins_.size() > 0)
77  {
78  plugins_.pop_back();
79  }
80 }
81 
82 void LayeredCostmap::resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x,
83  double origin_y, bool size_locked)
84 {
85  boost::unique_lock<Costmap2D::mutex_t> lock(*(costmap_.getMutex()));
86  size_locked_ = size_locked;
87  costmap_.resizeMap(size_x, size_y, resolution, origin_x, origin_y);
88  for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
89  ++plugin)
90  {
91  (*plugin)->matchSize();
92  }
93 }
94 
95 void LayeredCostmap::updateMap(double robot_x, double robot_y, double robot_yaw)
96 {
97  // Lock for the remainder of this function, some plugins (e.g. VoxelLayer)
98  // implement thread unsafe updateBounds() functions.
99  boost::unique_lock<Costmap2D::mutex_t> lock(*(costmap_.getMutex()));
100 
101  // if we're using a rolling buffer costmap... we need to update the origin using the robot's position
102  if (rolling_window_)
103  {
104  double new_origin_x = robot_x - costmap_.getSizeInMetersX() / 2;
105  double new_origin_y = robot_y - costmap_.getSizeInMetersY() / 2;
106  costmap_.updateOrigin(new_origin_x, new_origin_y);
107  }
108 
109  if (plugins_.size() == 0)
110  return;
111 
112  minx_ = miny_ = 1e30;
113  maxx_ = maxy_ = -1e30;
114 
115  for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
116  ++plugin)
117  {
118  double prev_minx = minx_;
119  double prev_miny = miny_;
120  double prev_maxx = maxx_;
121  double prev_maxy = maxy_;
122  (*plugin)->updateBounds(robot_x, robot_y, robot_yaw, &minx_, &miny_, &maxx_, &maxy_);
123  if (minx_ > prev_minx || miny_ > prev_miny || maxx_ < prev_maxx || maxy_ < prev_maxy)
124  {
125  ROS_WARN_THROTTLE(1.0, "Illegal bounds change, was [tl: (%f, %f), br: (%f, %f)], but "
126  "is now [tl: (%f, %f), br: (%f, %f)]. The offending layer is %s",
127  prev_minx, prev_miny, prev_maxx , prev_maxy,
128  minx_, miny_, maxx_ , maxy_,
129  (*plugin)->getName().c_str());
130  }
131  }
132 
133  int x0, xn, y0, yn;
136 
137  x0 = std::max(0, x0);
138  xn = std::min(int(costmap_.getSizeInCellsX()), xn + 1);
139  y0 = std::max(0, y0);
140  yn = std::min(int(costmap_.getSizeInCellsY()), yn + 1);
141 
142  ROS_DEBUG("Updating area x: [%d, %d] y: [%d, %d]", x0, xn, y0, yn);
143 
144  if (xn < x0 || yn < y0)
145  return;
146 
147  costmap_.resetMap(x0, y0, xn, yn);
148  for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
149  ++plugin)
150  {
151  (*plugin)->updateCosts(costmap_, x0, y0, xn, yn);
152  }
153 
154  bx0_ = x0;
155  bxn_ = xn;
156  by0_ = y0;
157  byn_ = yn;
158 
159  initialized_ = true;
160 }
161 
163 {
164  current_ = true;
165  for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
166  ++plugin)
167  {
168  current_ = current_ && (*plugin)->isCurrent();
169  }
170  return current_;
171 }
172 
173 void LayeredCostmap::setFootprint(const std::vector<geometry_msgs::Point>& footprint_spec)
174 {
175  footprint_ = footprint_spec;
177 
178  for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
179  ++plugin)
180  {
181  (*plugin)->onFootprintChanged();
182  }
183 }
184 
185 } // namespace costmap_2d
mutex_t * getMutex()
Definition: costmap_2d.h:295
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Definition: costmap_2d.cpp:72
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:436
void setFootprint(const std::vector< geometry_msgs::Point > &footprint_spec)
Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintCha...
void setDefaultValue(unsigned char c)
Definition: costmap_2d.h:236
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:441
LayeredCostmap(std::string global_frame, bool rolling_window, bool track_unknown)
Constructor for a costmap.
void worldToMapEnforceBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates, constraining results to legal bounds.
Definition: costmap_2d.cpp:228
std::vector< geometry_msgs::Point > footprint_
#define ROS_WARN_THROTTLE(period,...)
std::vector< boost::shared_ptr< Layer > > plugins_
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:431
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:426
virtual void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location.... keeping data when it can.
Definition: costmap_2d.cpp:260
void updateMap(double robot_x, double robot_y, double robot_yaw)
Update the underlying costmap with new data. If you want to update the map outside of the update loop...
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist)
Calculate the extreme distances for the footprint.
Definition: footprint.cpp:41
#define ROS_DEBUG(...)
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Definition: costmap_2d.cpp:93


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:17