15 #ifndef NAV2_COSTMAP_2D__CLEAR_COSTMAP_SERVICE_HPP_
16 #define NAV2_COSTMAP_2D__CLEAR_COSTMAP_SERVICE_HPP_
22 #include "rclcpp/rclcpp.hpp"
23 #include "nav2_msgs/srv/clear_costmap_except_region.hpp"
24 #include "nav2_msgs/srv/clear_costmap_around_robot.hpp"
25 #include "nav2_msgs/srv/clear_costmap_around_pose.hpp"
26 #include "nav2_msgs/srv/clear_entire_costmap.hpp"
27 #include "nav2_costmap_2d/costmap_layer.hpp"
28 #include "nav2_util/lifecycle_node.hpp"
60 void clearRegion(
double reset_distance,
bool invert);
65 void clearAroundPose(
const geometry_msgs::msg::PoseStamped & pose,
double reset_distance);
74 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_costmap_2d")};
80 unsigned char reset_value_;
83 rclcpp::Service<nav2_msgs::srv::ClearCostmapExceptRegion>::SharedPtr clear_except_service_;
87 void clearExceptRegionCallback(
88 const std::shared_ptr<rmw_request_id_t> request_header,
89 const std::shared_ptr<nav2_msgs::srv::ClearCostmapExceptRegion::Request> request,
90 const std::shared_ptr<nav2_msgs::srv::ClearCostmapExceptRegion::Response> response);
92 rclcpp::Service<nav2_msgs::srv::ClearCostmapAroundRobot>::SharedPtr clear_around_service_;
96 void clearAroundRobotCallback(
97 const std::shared_ptr<rmw_request_id_t> request_header,
98 const std::shared_ptr<nav2_msgs::srv::ClearCostmapAroundRobot::Request> request,
99 const std::shared_ptr<nav2_msgs::srv::ClearCostmapAroundRobot::Response> response);
101 rclcpp::Service<nav2_msgs::srv::ClearCostmapAroundPose>::SharedPtr
102 clear_around_pose_service_;
106 void clearAroundPoseCallback(
107 const std::shared_ptr<rmw_request_id_t> request_header,
108 const std::shared_ptr<nav2_msgs::srv::ClearCostmapAroundPose::Request> request,
109 const std::shared_ptr<nav2_msgs::srv::ClearCostmapAroundPose::Response> response);
111 rclcpp::Service<nav2_msgs::srv::ClearEntireCostmap>::SharedPtr clear_entire_service_;
115 void clearEntireCallback(
116 const std::shared_ptr<rmw_request_id_t> request_header,
117 const std::shared_ptr<nav2_msgs::srv::ClearEntireCostmap::Request> request,
118 const std::shared_ptr<nav2_msgs::srv::ClearEntireCostmap::Response> response);
123 void clearLayerRegion(
124 std::shared_ptr<CostmapLayer> & costmap,
double pose_x,
double pose_y,
double reset_distance,
130 bool getPosition(
double & x,
double & y)
const;
Exposes services to clear costmap objects in inclusive/exclusive regions or completely.
~ClearCostmapService()
A destructor.
void clearAroundPose(const geometry_msgs::msg::PoseStamped &pose, double reset_distance)
Clears the region around a specific pose.
ClearCostmapService()=delete
A constructor.
void clearRegion(double reset_distance, bool invert)
Clears the region outside of a user-specified area reverting to the static map.
void clearEntirely()
Clears all layers.
A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacl...