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 
55 class LayeredCostmap
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  inline const std::string& getGlobalFrameID() const noexcept
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 
102  bool isTrackingUnknown()
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 
117  bool isSizeLocked()
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 
130  bool isInitialized()
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 
155  double getInscribedRadius() { return inscribed_radius_; }
156 
157 private:
159  std::string global_frame_;
160 
161  bool rolling_window_;
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 
169  bool initialized_;
170  bool size_locked_;
172  std::vector<geometry_msgs::Point> footprint_;
173 };
174 
175 } // namespace costmap_2d
176 
177 #endif // COSTMAP_2D_LAYERED_COSTMAP_H_
costmap_2d::LayeredCostmap::isSizeLocked
bool isSizeLocked()
Definition: layered_costmap.h:153
costmap_2d::LayeredCostmap::global_frame_
std::string global_frame_
Definition: layered_costmap.h:195
boost::shared_ptr
costmap_2d::LayeredCostmap::isRolling
bool isRolling()
Definition: layered_costmap.h:133
costmap_2d::LayeredCostmap::by0_
unsigned int by0_
Definition: layered_costmap.h:201
costmap_2d::LayeredCostmap::inscribed_radius_
double inscribed_radius_
Definition: layered_costmap.h:207
costmap_2d::LayeredCostmap::setFootprint
void setFootprint(const std::vector< geometry_msgs::Point > &footprint_spec)
Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintCha...
Definition: layered_costmap.cpp:177
costmap_2d::NO_INFORMATION
static const unsigned char NO_INFORMATION
Definition: cost_values.h:77
costmap_2d::LayeredCostmap::initialized_
bool initialized_
Definition: layered_costmap.h:205
costmap_2d::LayeredCostmap::resizeMap
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
Definition: layered_costmap.cpp:82
layer.h
costmap_2d::LayeredCostmap::size_locked_
bool size_locked_
Definition: layered_costmap.h:206
costmap_2d::Costmap2D
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:96
costmap_2d::LayeredCostmap::rolling_window_
bool rolling_window_
Definition: layered_costmap.h:197
costmap_2d::Costmap2D::getDefaultValue
unsigned char getDefaultValue()
Definition: costmap_2d.h:277
costmap_2d::LayeredCostmap::isTrackingUnknown
bool isTrackingUnknown()
Definition: layered_costmap.h:138
costmap_2d::LayeredCostmap::getInscribedRadius
double getInscribedRadius()
The radius of a circle centered at the origin of the robot which is just within all points and edges ...
Definition: layered_costmap.h:191
costmap_2d.h
costmap_2d::LayeredCostmap::footprint_
std::vector< geometry_msgs::Point > footprint_
Definition: layered_costmap.h:208
costmap_2d::LayeredCostmap::circumscribed_radius_
double circumscribed_radius_
Definition: layered_costmap.h:207
costmap_2d::LayeredCostmap::getBounds
void getBounds(unsigned int *x0, unsigned int *xn, unsigned int *y0, unsigned int *yn)
Definition: layered_costmap.h:158
costmap_2d::LayeredCostmap::bx0_
unsigned int bx0_
Definition: layered_costmap.h:201
costmap_2d::LayeredCostmap::getPlugins
std::vector< boost::shared_ptr< Layer > > * getPlugins()
Definition: layered_costmap.h:143
costmap_2d::LayeredCostmap::LayeredCostmap
LayeredCostmap(std::string global_frame, bool rolling_window, bool track_unknown)
Constructor for a costmap.
Definition: layered_costmap.cpp:50
costmap_2d::LayeredCostmap::minx_
double minx_
Definition: layered_costmap.h:200
costmap_2d::LayeredCostmap::plugins_
std::vector< boost::shared_ptr< Layer > > plugins_
Definition: layered_costmap.h:203
costmap_2d::LayeredCostmap::getFootprint
const std::vector< geometry_msgs::Point > & getFootprint()
Returns the latest footprint stored with setFootprint().
Definition: layered_costmap.h:177
costmap_2d::LayeredCostmap::maxy_
double maxy_
Definition: layered_costmap.h:200
costmap_2d::LayeredCostmap::addPlugin
void addPlugin(boost::shared_ptr< Layer > plugin)
Definition: layered_costmap.h:148
costmap_2d::LayeredCostmap::bxn_
unsigned int bxn_
Definition: layered_costmap.h:201
costmap_2d::LayeredCostmap::current_
bool current_
<
Definition: layered_costmap.h:199
costmap_2d::LayeredCostmap::isCurrent
bool isCurrent()
Definition: layered_costmap.cpp:165
costmap_2d::LayeredCostmap::byn_
unsigned int byn_
Definition: layered_costmap.h:201
costmap_2d::LayeredCostmap::maxx_
double maxx_
Definition: layered_costmap.h:200
cost_values.h
costmap_2d::LayeredCostmap::updateMap
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...
Definition: layered_costmap.cpp:95
costmap_2d::LayeredCostmap::~LayeredCostmap
~LayeredCostmap()
Destructor.
Definition: layered_costmap.cpp:74
costmap_2d::LayeredCostmap::isInitialized
bool isInitialized()
Definition: layered_costmap.h:166
costmap_2d::LayeredCostmap::getUpdatedBounds
void getUpdatedBounds(double &minx, double &miny, double &maxx, double &maxy)
Definition: layered_costmap.h:118
costmap_2d::LayeredCostmap::costmap_
Costmap2D costmap_
Definition: layered_costmap.h:194
costmap_2d::LayeredCostmap::getCostmap
Costmap2D * getCostmap()
Definition: layered_costmap.h:128
costmap_2d::LayeredCostmap::getGlobalFrameID
const std::string & getGlobalFrameID() const noexcept
Definition: layered_costmap.h:110
costmap_2d::LayeredCostmap::miny_
double miny_
Definition: layered_costmap.h:200
costmap_2d
Definition: array_parser.h:37
costmap_2d::LayeredCostmap::getCircumscribedRadius
double getCircumscribedRadius()
The radius of a circle centered at the origin of the robot which just surrounds all points on the rob...
Definition: layered_costmap.h:184


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17