38 #ifndef COSTMAP_2D_LAYERED_COSTMAP_H_ 39 #define COSTMAP_2D_LAYERED_COSTMAP_H_ 61 LayeredCostmap(std::string global_frame,
bool rolling_window,
bool track_unknown);
72 void updateMap(
double robot_x,
double robot_y,
double robot_yaw);
79 void resizeMap(
unsigned int size_x,
unsigned int size_y,
double resolution,
double origin_x,
double origin_y,
80 bool size_locked =
false);
122 void getBounds(
unsigned int* x0,
unsigned int* xn,
unsigned int* y0,
unsigned int* yn)
138 void setFootprint(
const std::vector<geometry_msgs::Point>& footprint_spec);
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 ...
double circumscribed_radius_
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()
static const unsigned char NO_INFORMATION
A 2D costmap provides a mapping between points in the world and their associated "costs".
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...
~LayeredCostmap()
Destructor.
std::string global_frame_
void getUpdatedBounds(double &minx, double &miny, double &maxx, double &maxy)