Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
clear_costmap_service.cpp
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 #include <vector>
16 #include <string>
17 #include <algorithm>
18 #include <memory>
19 
20 #include "nav2_costmap_2d/clear_costmap_service.hpp"
21 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
22 
23 namespace nav2_costmap_2d
24 {
25 
26 using std::vector;
27 using std::string;
28 using std::shared_ptr;
29 using std::any_of;
30 using ClearExceptRegion = nav2_msgs::srv::ClearCostmapExceptRegion;
31 using ClearAroundRobot = nav2_msgs::srv::ClearCostmapAroundRobot;
32 using ClearEntirely = nav2_msgs::srv::ClearEntireCostmap;
33 
35  const nav2_util::LifecycleNode::WeakPtr & parent,
36  Costmap2DROS & costmap)
37 : costmap_(costmap)
38 {
39  auto node = parent.lock();
40  logger_ = node->get_logger();
41  reset_value_ = costmap_.getCostmap()->getDefaultValue();
42 
43  clear_except_service_ = node->create_service<ClearExceptRegion>(
44  "clear_except_" + costmap_.getName(),
45  std::bind(
46  &ClearCostmapService::clearExceptRegionCallback, this,
47  std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
48 
49  clear_around_service_ = node->create_service<ClearAroundRobot>(
50  "clear_around_" + costmap.getName(),
51  std::bind(
52  &ClearCostmapService::clearAroundRobotCallback, this,
53  std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
54 
55  clear_entire_service_ = node->create_service<ClearEntirely>(
56  "clear_entirely_" + costmap_.getName(),
57  std::bind(
58  &ClearCostmapService::clearEntireCallback, this,
59  std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
60 }
61 
63 {
64  // make sure services shutdown.
65  clear_except_service_.reset();
66  clear_around_service_.reset();
67  clear_entire_service_.reset();
68 }
69 
70 void ClearCostmapService::clearExceptRegionCallback(
71  const shared_ptr<rmw_request_id_t>/*request_header*/,
72  const shared_ptr<ClearExceptRegion::Request> request,
73  const shared_ptr<ClearExceptRegion::Response>/*response*/)
74 {
75  RCLCPP_INFO(
76  logger_, "%s",
77  ("Received request to clear except a region the " + costmap_.getName()).c_str());
78 
79  clearRegion(request->reset_distance, true);
80 }
81 
82 void ClearCostmapService::clearAroundRobotCallback(
83  const shared_ptr<rmw_request_id_t>/*request_header*/,
84  const shared_ptr<ClearAroundRobot::Request> request,
85  const shared_ptr<ClearAroundRobot::Response>/*response*/)
86 {
87  clearRegion(request->reset_distance, false);
88 }
89 
90 void ClearCostmapService::clearEntireCallback(
91  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
92  const std::shared_ptr<ClearEntirely::Request>/*request*/,
93  const std::shared_ptr<ClearEntirely::Response>/*response*/)
94 {
95  RCLCPP_INFO(
96  logger_, "%s",
97  ("Received request to clear entirely the " + costmap_.getName()).c_str());
98 
99  clearEntirely();
100 }
101 
102 void ClearCostmapService::clearRegion(const double reset_distance, bool invert)
103 {
104  double x, y;
105 
106  if (!getPosition(x, y)) {
107  RCLCPP_ERROR(
108  logger_, "%s",
109  "Cannot clear map because robot pose cannot be retrieved.");
110  return;
111  }
112 
113  auto layers = costmap_.getLayeredCostmap()->getPlugins();
114 
115  for (auto & layer : *layers) {
116  if (layer->isClearable()) {
117  auto costmap_layer = std::static_pointer_cast<CostmapLayer>(layer);
118  clearLayerRegion(costmap_layer, x, y, reset_distance, invert);
119  }
120  }
121 
122  // AlexeyMerzlyakov: No need to clear layer region for costmap filters
123  // as they are always supposed to be not clearable.
124 }
125 
126 void ClearCostmapService::clearLayerRegion(
127  shared_ptr<CostmapLayer> & costmap, double pose_x, double pose_y, double reset_distance,
128  bool invert)
129 {
130  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap->getMutex()));
131 
132  double start_point_x = pose_x - reset_distance / 2;
133  double start_point_y = pose_y - reset_distance / 2;
134  double end_point_x = start_point_x + reset_distance;
135  double end_point_y = start_point_y + reset_distance;
136 
137  int start_x, start_y, end_x, end_y;
138  costmap->worldToMapEnforceBounds(start_point_x, start_point_y, start_x, start_y);
139  costmap->worldToMapEnforceBounds(end_point_x, end_point_y, end_x, end_y);
140 
141  costmap->clearArea(start_x, start_y, end_x, end_y, invert);
142 
143  double ox = costmap->getOriginX(), oy = costmap->getOriginY();
144  double width = costmap->getSizeInMetersX(), height = costmap->getSizeInMetersY();
145  costmap->addExtraBounds(ox, oy, ox + width, oy + height);
146 }
147 
149 {
150  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_.getCostmap()->getMutex()));
151  costmap_.resetLayers();
152 }
153 
154 bool ClearCostmapService::getPosition(double & x, double & y) const
155 {
156  geometry_msgs::msg::PoseStamped pose;
157  if (!costmap_.getRobotPose(pose)) {
158  return false;
159  }
160 
161  x = pose.pose.position.x;
162  y = pose.pose.position.y;
163 
164  return true;
165 }
166 
167 } // namespace nav2_costmap_2d
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...
bool getRobotPose(geometry_msgs::msg::PoseStamped &global_pose)
Get the pose of the robot in the global frame of the costmap.
std::string getName() const
Returns costmap name.
LayeredCostmap * getLayeredCostmap()
Get the layered costmap object used in the node.
void resetLayers()
Reset each individual layer.
Costmap2D * getCostmap()
Return a pointer to the "master" costmap which receives updates from all the layers.
unsigned char getDefaultValue()
Get the default background value of the costmap.
Definition: costmap_2d.hpp:289
std::vector< std::shared_ptr< Layer > > * getPlugins()
Get the vector of pointers to the costmap plugins.