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_ros_common/lifecycle_node.hpp"
29 #include "nav2_ros_common/service_server.hpp"
47 const nav2::LifecycleNode::WeakPtr & parent,
Costmap2DROS & costmap);
62 void clearRegion(
double reset_distance,
bool invert);
67 void clearAroundPose(
const geometry_msgs::msg::PoseStamped & pose,
double reset_distance);
76 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_costmap_2d")};
82 unsigned char reset_value_;
85 nav2::ServiceServer<nav2_msgs::srv::ClearCostmapExceptRegion>::SharedPtr
86 clear_except_service_;
90 void clearExceptRegionCallback(
91 const std::shared_ptr<rmw_request_id_t> request_header,
92 const std::shared_ptr<nav2_msgs::srv::ClearCostmapExceptRegion::Request> request,
93 const std::shared_ptr<nav2_msgs::srv::ClearCostmapExceptRegion::Response> response);
95 nav2::ServiceServer<nav2_msgs::srv::ClearCostmapAroundRobot>::SharedPtr
96 clear_around_service_;
100 void clearAroundRobotCallback(
101 const std::shared_ptr<rmw_request_id_t> request_header,
102 const std::shared_ptr<nav2_msgs::srv::ClearCostmapAroundRobot::Request> request,
103 const std::shared_ptr<nav2_msgs::srv::ClearCostmapAroundRobot::Response> response);
105 nav2::ServiceServer<nav2_msgs::srv::ClearCostmapAroundPose>::SharedPtr
106 clear_around_pose_service_;
110 void clearAroundPoseCallback(
111 const std::shared_ptr<rmw_request_id_t> request_header,
112 const std::shared_ptr<nav2_msgs::srv::ClearCostmapAroundPose::Request> request,
113 const std::shared_ptr<nav2_msgs::srv::ClearCostmapAroundPose::Response> response);
115 nav2::ServiceServer<nav2_msgs::srv::ClearEntireCostmap>::SharedPtr
116 clear_entire_service_;
120 void clearEntireCallback(
121 const std::shared_ptr<rmw_request_id_t> request_header,
122 const std::shared_ptr<nav2_msgs::srv::ClearEntireCostmap::Request> request,
123 const std::shared_ptr<nav2_msgs::srv::ClearEntireCostmap::Response> response);
128 void clearLayerRegion(
129 std::shared_ptr<CostmapLayer> & costmap,
double pose_x,
double pose_y,
double reset_distance,
135 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...