38 #ifndef RAPP_COSTMAP_2D_STATIC_LAYER_H_
39 #define RAPP_COSTMAP_2D_STATIC_LAYER_H_
42 #include <ros/service_manager.h>
43 #include <costmap_2d/costmap_layer.h>
44 #include <costmap_2d/layered_costmap.h>
45 #include <costmap_2d/GenericPluginConfig.h>
46 #include <dynamic_reconfigure/server.h>
47 #include <nav_msgs/OccupancyGrid.h>
48 #include <nav_msgs/GetMap.h>
49 #include <map_msgs/OccupancyGridUpdate.h>
50 #include <message_filters/subscriber.h>
52 #include <rapp_platform_ros_communications/Costmap2dRosSrv.h>
67 virtual void updateBounds(
double robot_x,
double robot_y,
double robot_yaw,
double* min_x,
double* min_y,
double* max_x,
69 virtual void updateCosts(costmap_2d::Costmap2D& master_grid,
int min_i,
int min_j,
int max_i,
int max_j);
80 void incomingMap(
const nav_msgs::OccupancyGridConstPtr& new_map);
81 void incomingUpdate(
const map_msgs::OccupancyGridUpdateConstPtr& update);
82 void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level);
84 rapp_platform_ros_communications::Costmap2dRosSrvResponse& res);
99 mutable boost::recursive_mutex
lock_;
100 dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig> *
dsrv_;
105 #endif // RAPP_COSTMAP_2D_STATIC_LAYER_H_
bool track_unknown_space_
unsigned char lethal_threshold_
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
virtual void deactivate()
virtual ~RappStaticLayer()
ros::Subscriber map_update_sub_
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)
bool incomingUpdateService(rapp_platform_ros_communications::Costmap2dRosSrvRequest &req, rapp_platform_ros_communications::Costmap2dRosSrvResponse &res)
void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
ros::ServiceServer costmap_update_service
boost::recursive_mutex lock_
unsigned char interpretValue(unsigned char value)
void incomingMap(const nav_msgs::OccupancyGridConstPtr &new_map)
Callback to update the costmap's map from the map_server.
virtual void onInitialize()
bool subscribe_to_updates_
void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
unsigned char unknown_cost_value_
dynamic_reconfigure::Server< costmap_2d::GenericPluginConfig > * dsrv_