Nav2 Navigation Stack - jazzy  jazzy
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_util/lifecycle_node.hpp"
29 
30 namespace nav2_costmap_2d
31 {
32 
33 class Costmap2DROS;
34 
40 {
41 public:
45  ClearCostmapService(const nav2_util::LifecycleNode::WeakPtr & parent, Costmap2DROS & costmap);
46 
50  ClearCostmapService() = delete;
51 
56 
60  void clearRegion(double reset_distance, bool invert);
61 
65  void clearAroundPose(const geometry_msgs::msg::PoseStamped & pose, double reset_distance);
66 
70  void clearEntirely();
71 
72 private:
73  // The Logger object for logging
74  rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")};
75 
76  // The costmap to clear
77  Costmap2DROS & costmap_;
78 
79  // Clearing parameters
80  unsigned char reset_value_;
81 
82  // Server for clearing the costmap
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);
91 
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);
100 
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);
110 
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);
119 
123  void clearLayerRegion(
124  std::shared_ptr<CostmapLayer> & costmap, double pose_x, double pose_y, double reset_distance,
125  bool invert);
126 
130  bool getPosition(double & x, double & y) const;
131 };
132 
133 } // namespace nav2_costmap_2d
134 
135 #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...