costmap_layer.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_COSTMAP_LAYER_H_
39 #define COSTMAP_2D_COSTMAP_LAYER_H_
40 #include <ros/ros.h>
41 #include <costmap_2d/layer.h>
43 
44 namespace costmap_2d
45 {
46 
47 class CostmapLayer : public Layer, public Costmap2D
48 {
49 public:
51  extra_min_x_(1e6), extra_max_x_(-1e6),
52  extra_min_y_(1e6), extra_max_y_(-1e6) {}
53 
54  bool isDiscretized()
55  {
56  return true;
57  }
58 
59  virtual void matchSize();
60 
61  virtual void clearArea(int start_x, int start_y, int end_x, int end_y, bool invert_area=false);
62 
72  void addExtraBounds(double mx0, double my0, double mx1, double my1);
73 
74 protected:
75  /*
76  * Updates the master_grid within the specified
77  * bounding box using this layer's values.
78  *
79  * TrueOverwrite means every value from this layer
80  * is written into the master grid.
81  */
82  void updateWithTrueOverwrite(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
83 
84  /*
85  * Updates the master_grid within the specified
86  * bounding box using this layer's values.
87  *
88  * Overwrite means every valid value from this layer
89  * is written into the master grid (does not copy NO_INFORMATION)
90  */
91  void updateWithOverwrite(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
92 
93  /*
94  * Updates the master_grid within the specified
95  * bounding box using this layer's values.
96  *
97  * Sets the new value to the maximum of the master_grid's value
98  * and this layer's value. If the master value is NO_INFORMATION,
99  * it is overwritten. If the layer's value is NO_INFORMATION,
100  * the master value does not change.
101  */
102  void updateWithMax(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
103 
104  /*
105  * Updates the master_grid within the specified
106  * bounding box using this layer's values.
107  *
108  * Sets the new value to the sum of the master grid's value
109  * and this layer's value. If the master value is NO_INFORMATION,
110  * it is overwritten with the layer's value. If the layer's value
111  * is NO_INFORMATION, then the master value does not change.
112  *
113  * If the sum value is larger than INSCRIBED_INFLATED_OBSTACLE,
114  * the master value is set to (INSCRIBED_INFLATED_OBSTACLE - 1).
115  */
116  void updateWithAddition(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
117 
129  void touch(double x, double y, double* min_x, double* min_y, double* max_x, double* max_y);
130 
131  /*
132  * Updates the bounding box specified in the parameters
133  * to include the bounding box from the addExtraBounds
134  * call. If addExtraBounds was not called, the method will do nothing.
135  *
136  * Should be called at the beginning of the updateBounds method
137  *
138  * @param min_x bounding box (input and output)
139  * @param min_y bounding box (input and output)
140  * @param max_x bounding box (input and output)
141  * @param max_y bounding box (input and output)
142  */
143  void useExtraBounds(double* min_x, double* min_y, double* max_x, double* max_y);
144  bool has_extra_bounds_;
145 
146 private:
148 };
149 
150 } // namespace costmap_2d
151 #endif // COSTMAP_2D_COSTMAP_LAYER_H_
costmap_2d::CostmapLayer::updateWithAddition
void updateWithAddition(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Definition: costmap_layer.cpp:127
costmap_2d::CostmapLayer::CostmapLayer
CostmapLayer()
Definition: costmap_layer.h:122
costmap_2d::CostmapLayer::extra_min_x_
double extra_min_x_
Definition: costmap_layer.h:219
costmap_2d::CostmapLayer::clearArea
virtual void clearArea(int start_x, int start_y, int end_x, int end_y, bool invert_area=false)
Definition: costmap_layer.cpp:21
costmap_2d::CostmapLayer::updateWithMax
void updateWithMax(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Definition: costmap_layer.cpp:63
ros.h
layered_costmap.h
layer.h
costmap_2d::CostmapLayer::matchSize
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
Definition: costmap_layer.cpp:14
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::CostmapLayer::updateWithOverwrite
void updateWithOverwrite(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Definition: costmap_layer.cpp:108
costmap_2d::CostmapLayer::has_extra_bounds_
bool has_extra_bounds_
Definition: costmap_layer.h:216
costmap_2d::CostmapLayer::extra_max_x_
double extra_max_x_
Definition: costmap_layer.h:219
costmap_2d::CostmapLayer::useExtraBounds
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
Definition: costmap_layer.cpp:47
costmap_2d::CostmapLayer::touch
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
Definition: costmap_layer.cpp:6
costmap_2d::CostmapLayer::updateWithTrueOverwrite
void updateWithTrueOverwrite(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Definition: costmap_layer.cpp:89
costmap_2d::CostmapLayer::extra_min_y_
double extra_min_y_
Definition: costmap_layer.h:219
costmap_2d::CostmapLayer::extra_max_y_
double extra_max_y_
Definition: costmap_layer.h:219
costmap_2d::CostmapLayer::isDiscretized
bool isDiscretized()
Definition: costmap_layer.h:126
costmap_2d
Definition: array_parser.h:37
costmap_2d::CostmapLayer::addExtraBounds
void addExtraBounds(double mx0, double my0, double mx1, double my1)
Definition: costmap_layer.cpp:38


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