Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
clear_costmap_service.hpp
1 // Copyright (c) 2018 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_COSTMAP_2D__CLEAR_COSTMAP_SERVICE_HPP_
16 #define NAV2_COSTMAP_2D__CLEAR_COSTMAP_SERVICE_HPP_
17 
18 #include <vector>
19 #include <string>
20 #include <memory>
21 
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"
30 
31 namespace nav2_costmap_2d
32 {
33 
34 class Costmap2DROS;
35 
41 {
42 public:
47  const nav2::LifecycleNode::WeakPtr & parent, Costmap2DROS & costmap);
48 
52  ClearCostmapService() = delete;
53 
58 
62  void clearRegion(double reset_distance, bool invert);
63 
67  void clearAroundPose(const geometry_msgs::msg::PoseStamped & pose, double reset_distance);
68 
72  void clearEntirely();
73 
74 private:
75  // The Logger object for logging
76  rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")};
77 
78  // The costmap to clear
79  Costmap2DROS & costmap_;
80 
81  // Clearing parameters
82  unsigned char reset_value_;
83 
84  // Server for clearing the costmap
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);
94 
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);
104 
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);
114 
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);
124 
128  void clearLayerRegion(
129  std::shared_ptr<CostmapLayer> & costmap, double pose_x, double pose_y, double reset_distance,
130  bool invert);
131 
135  bool getPosition(double & x, double & y) const;
136 };
137 
138 } // namespace nav2_costmap_2d
139 
140 #endif // NAV2_COSTMAP_2D__CLEAR_COSTMAP_SERVICE_HPP_
Exposes services to clear costmap objects in inclusive/exclusive regions or completely.
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.
A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacl...