Go to the documentation of this file.
38 #ifndef COSTMAP_2D_STATIC_LAYER_H_
39 #define COSTMAP_2D_STATIC_LAYER_H_
44 #include <costmap_2d/GenericPluginConfig.h>
45 #include <dynamic_reconfigure/server.h>
46 #include <nav_msgs/OccupancyGrid.h>
47 #include <map_msgs/OccupancyGridUpdate.h>
53 class StaticLayer :
public CostmapLayer
63 virtual void updateBounds(
double robot_x,
double robot_y,
double robot_yaw,
double* min_x,
double* min_y,
64 double* max_x,
double* max_y);
76 void incomingMap(
const nav_msgs::OccupancyGridConstPtr& new_map);
77 void incomingUpdate(
const map_msgs::OccupancyGridUpdateConstPtr& update);
78 void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level);
96 dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig> *
dsrv_;
101 #endif // COSTMAP_2D_STATIC_LAYER_H_
unsigned char lethal_threshold_
void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to up...
bool subscribe_to_updates_
frame that map is located in
virtual void activate()
Restart publishers if they've been stopped.
unsigned char interpretValue(unsigned char value)
A 2D costmap provides a mapping between points in the world and their associated "costs".
ros::Subscriber map_update_sub_
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
std::string global_frame_
The global frame for the costmap.
bool track_unknown_space_
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
virtual void deactivate()
Stop publishers.
bool first_map_only_
Store the first static map and reuse it on reinitializing.
void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
dynamic_reconfigure::Server< costmap_2d::GenericPluginConfig > * dsrv_
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().
unsigned char unknown_cost_value_
void incomingMap(const nav_msgs::OccupancyGridConstPtr &new_map)
Callback to update the costmap's map from the map_server.
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17