38 #ifndef RTABMAP_ROS_STATIC_LAYER_H_ 39 #define RTABMAP_ROS_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> 63 virtual void updateBounds(
double robot_x,
double robot_y,
double robot_yaw,
double* min_x,
double* min_y,
double* max_x,
76 void incomingMap(
const nav_msgs::OccupancyGridConstPtr& new_map);
94 mutable boost::recursive_mutex
lock_;
95 dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig> *
dsrv_;
100 #endif // RTABMAP_ROS_DYNAMIC_LAYER_H_ virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
bool subscribe_to_updates_
void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
bool track_unknown_space_
dynamic_reconfigure::Server< costmap_2d::GenericPluginConfig > * dsrv_
void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
bool update(const T &new_val, T &my_val)
ros::Subscriber map_update_sub_
unsigned char unknown_cost_value_
void incomingMap(const nav_msgs::OccupancyGridConstPtr &new_map)
Callback to update the costmap's map from the map_server.
unsigned char interpretValue(unsigned char value)
std::string global_frame_
The global frame for the costmap.
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
boost::recursive_mutex lock_
virtual void onInitialize()
unsigned char lethal_threshold_
virtual void deactivate()