28#include <rclcpp/rclcpp.hpp>
46 GLOBAL_OBSTACLES_LAYER = 0,
47 LOCAL_OBSTACLES_LAYER = 1,
48 GLOBAL_INFLATED_LAYER = 2,
49 LOCAL_INFLATED_LAYER = 3
60 bool exists(std::string layerName);
62 void enable(std::string layerName);
66 void disable(std::string layerName);
71 std::string costmapName, std::string enablePropertyName =
"enabled");
82 std::string costmap_name, std::string enablePropertyName, rclcpp::Node::SharedPtr nh);
88 rclcpp::Node::SharedPtr
nh_;
CostmapProxy(std::string costmap_name, std::string enablePropertyName, rclcpp::Node::SharedPtr nh)
void setCostmapEnabled(bool value)
rclcpp::Node::SharedPtr nh_
rclcpp::Node::SharedPtr getNode()
cl_nav2z::ClNav2Z * moveBaseClient_
bool exists(std::string layerName)
void onInitialize() override
static std::array< std::string, 4 > layerNames
static std::string getStandardCostmapName(StandardLayers layertype)
void disable(std::string layerName)
void registerProxyFromDynamicReconfigureServer(std::string costmapName, std::string enablePropertyName="enabled")
void enable(std::string layerName)
std::map< std::string, std::shared_ptr< CostmapProxy > > costmapProxies