38 #ifndef NAV2_COSTMAP_2D__COSTMAP_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__COSTMAP_LAYER_HPP_
43 #include <rclcpp/rclcpp.hpp>
44 #include <nav2_costmap_2d/layer.hpp>
45 #include <nav2_costmap_2d/layered_costmap.hpp>
63 : has_extra_bounds_(false),
64 extra_min_x_(1e6), extra_max_x_(-1e6),
65 extra_min_y_(1e6), extra_max_y_(-1e6) {}
84 virtual void clearArea(
int start_x,
int start_y,
int end_x,
int end_y,
bool invert);
95 void addExtraBounds(
double mx0,
double my0,
double mx1,
double my1);
105 void updateWithTrueOverwrite(
107 int min_i,
int min_j,
int max_i,
int max_j);
116 void updateWithOverwrite(
118 int min_i,
int min_j,
int max_i,
int max_j);
142 void updateWithMaxWithoutUnknownOverwrite(
158 void updateWithAddition(
173 void touch(
double x,
double y,
double * min_x,
double * min_y,
double * max_x,
double * max_y);
187 void useExtraBounds(
double * min_x,
double * min_y,
double * max_x,
double * max_y);
188 bool has_extra_bounds_;
198 double extra_min_x_, extra_max_x_, extra_min_y_, extra_max_y_;
A 2D costmap provides a mapping between points in the world and their associated "costs".
A costmap layer base class for costmap plugin layers. Rather than just a layer, this object also cont...
CostmapLayer()
CostmapLayer constructor.
bool isDiscretized()
If layer is discrete.
void addExtraBounds(double mx0, double my0, double mx1, double my1)
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
virtual void clearArea(int start_x, int start_y, int end_x, int end_y, bool invert)
Clear an are in the costmap with the given dimension if invert, then clear everything except these di...
virtual void matchSize()
Match the size of the master costmap.
CombinationMethod combination_method_from_int(const int value)
Converts an integer to a CombinationMethod enum and logs on failure.
Abstract class for layered costmap plugin implementations.