layered_costmap.h
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  *********************************************************************/
38 #ifndef COSTMAP_2D_LAYERED_COSTMAP_H_
39 #define COSTMAP_2D_LAYERED_COSTMAP_H_
40 
41 #include <costmap_2d/cost_values.h>
42 #include <costmap_2d/layer.h>
43 #include <costmap_2d/costmap_2d.h>
44 #include <vector>
45 #include <string>
46 
47 namespace costmap_2d
48 {
49 class Layer;
50 
56 {
57 public:
61  LayeredCostmap(std::string global_frame, bool rolling_window, bool track_unknown);
62 
67 
72  void updateMap(double robot_x, double robot_y, double robot_yaw);
73 
74  std::string getGlobalFrameID() const
75  {
76  return global_frame_;
77  }
78 
79  void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y,
80  bool size_locked = false);
81 
82  void getUpdatedBounds(double& minx, double& miny, double& maxx, double& maxy)
83  {
84  minx = minx_;
85  miny = miny_;
86  maxx = maxx_;
87  maxy = maxy_;
88  }
89 
90  bool isCurrent();
91 
93  {
94  return &costmap_;
95  }
96 
97  bool isRolling()
98  {
99  return rolling_window_;
100  }
101 
103  {
105  }
106 
107  std::vector<boost::shared_ptr<Layer> >* getPlugins()
108  {
109  return &plugins_;
110  }
111 
113  {
114  plugins_.push_back(plugin);
115  }
116 
118  {
119  return size_locked_;
120  }
121 
122  void getBounds(unsigned int* x0, unsigned int* xn, unsigned int* y0, unsigned int* yn)
123  {
124  *x0 = bx0_;
125  *xn = bxn_;
126  *y0 = by0_;
127  *yn = byn_;
128  }
129 
131  {
132  return initialized_;
133  }
134 
138  void setFootprint(const std::vector<geometry_msgs::Point>& footprint_spec);
139 
141  const std::vector<geometry_msgs::Point>& getFootprint() { return footprint_; }
142 
149 
156 
157 private:
159  std::string global_frame_;
160 
162 
163  bool current_;
164  double minx_, miny_, maxx_, maxy_;
165  unsigned int bx0_, bxn_, by0_, byn_;
166 
167  std::vector<boost::shared_ptr<Layer> > plugins_;
168 
172  std::vector<geometry_msgs::Point> footprint_;
173 };
174 
175 } // namespace costmap_2d
176 
177 #endif // COSTMAP_2D_LAYERED_COSTMAP_H_
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
std::string getGlobalFrameID() const
void setFootprint(const std::vector< geometry_msgs::Point > &footprint_spec)
Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintCha...
std::vector< boost::shared_ptr< Layer > > * getPlugins()
void getBounds(unsigned int *x0, unsigned int *xn, unsigned int *y0, unsigned int *yn)
LayeredCostmap(std::string global_frame, bool rolling_window, bool track_unknown)
Constructor for a costmap.
double getInscribedRadius()
The radius of a circle centered at the origin of the robot which is just within all points and edges ...
void addPlugin(boost::shared_ptr< Layer > plugin)
std::vector< geometry_msgs::Point > footprint_
std::vector< boost::shared_ptr< Layer > > plugins_
const std::vector< geometry_msgs::Point > & getFootprint()
Returns the latest footprint stored with setFootprint().
unsigned char getDefaultValue()
Definition: costmap_2d.h:241
static const unsigned char NO_INFORMATION
Definition: cost_values.h:42
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:60
Instantiates different layer plugins and aggregates them into one score.
double getCircumscribedRadius()
The radius of a circle centered at the origin of the robot which just surrounds all points on the rob...
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 getUpdatedBounds(double &minx, double &miny, double &maxx, double &maxy)


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:42