Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
keepout_filter.cpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2020 Samsung Research Russia
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the <ORGANIZATION> nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Alexey Merzlyakov
36  *********************************************************************/
37 
38 #include <string>
39 #include <memory>
40 #include <algorithm>
41 #include "tf2/convert.hpp"
42 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
43 
44 #include "nav2_costmap_2d/costmap_filters/keepout_filter.hpp"
45 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
46 
47 namespace nav2_costmap_2d
48 {
49 
51 : filter_info_sub_(nullptr), mask_sub_(nullptr), filter_mask_(nullptr),
52  global_frame_("")
53 {
54 }
55 
57  const std::string & filter_info_topic)
58 {
59  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
60 
61  nav2::LifecycleNode::SharedPtr node = node_.lock();
62  if (!node) {
63  throw std::runtime_error{"Failed to lock node"};
64  }
65 
66  filter_info_topic_ = joinWithParentNamespace(filter_info_topic);
67  // Setting new costmap filter info subscriber
68  RCLCPP_INFO(
69  logger_,
70  "KeepoutFilter: Subscribing to \"%s\" topic for filter info...",
71  filter_info_topic_.c_str());
72  filter_info_sub_ = node->create_subscription<nav2_msgs::msg::CostmapFilterInfo>(
74  std::bind(&KeepoutFilter::filterInfoCallback, this, std::placeholders::_1),
76 
77  global_frame_ = layered_costmap_->getGlobalFrameID();
78 
79  declareParameter("override_lethal_cost", rclcpp::ParameterValue(false));
80  node->get_parameter(name_ + "." + "override_lethal_cost", override_lethal_cost_);
81  declareParameter("lethal_override_cost", rclcpp::ParameterValue(MAX_NON_OBSTACLE));
82  node->get_parameter(name_ + "." + "lethal_override_cost", lethal_override_cost_);
83 
84  // clamp lethal_override_cost_ in case if higher than MAX_NON_OBSTACLE is given
85  lethal_override_cost_ = \
86  std::clamp<unsigned int>(lethal_override_cost_, FREE_SPACE, MAX_NON_OBSTACLE);
87 }
88 
89 void KeepoutFilter::filterInfoCallback(
90  const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg)
91 {
92  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
93 
94  nav2::LifecycleNode::SharedPtr node = node_.lock();
95  if (!node) {
96  throw std::runtime_error{"Failed to lock node"};
97  }
98 
99  if (!mask_sub_) {
100  RCLCPP_INFO(
101  logger_,
102  "KeepoutFilter: Received filter info from %s topic.", filter_info_topic_.c_str());
103  } else {
104  RCLCPP_WARN(
105  logger_,
106  "KeepoutFilter: New costmap filter info arrived from %s topic. Updating old filter info.",
107  filter_info_topic_.c_str());
108  // Resetting previous subscriber each time when new costmap filter information arrives
109  mask_sub_.reset();
110  }
111 
112  // Checking that base and multiplier are set to their default values
113  if (msg->base != BASE_DEFAULT || msg->multiplier != MULTIPLIER_DEFAULT) {
114  RCLCPP_ERROR(
115  logger_,
116  "KeepoutFilter: For proper use of keepout filter base and multiplier"
117  " in CostmapFilterInfo message should be set to their default values (%f and %f)",
118  BASE_DEFAULT, MULTIPLIER_DEFAULT);
119  }
120 
121  mask_topic_ = joinWithParentNamespace(msg->filter_mask_topic);
122 
123  // Setting new filter mask subscriber
124  RCLCPP_INFO(
125  logger_,
126  "KeepoutFilter: Subscribing to \"%s\" topic for filter mask...",
127  mask_topic_.c_str());
128  mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
129  mask_topic_,
130  std::bind(&KeepoutFilter::maskCallback, this, std::placeholders::_1),
132 }
133 
134 void KeepoutFilter::maskCallback(
135  const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
136 {
137  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
138 
139  nav2::LifecycleNode::SharedPtr node = node_.lock();
140  if (!node) {
141  throw std::runtime_error{"Failed to lock node"};
142  }
143 
144  if (!filter_mask_) {
145  RCLCPP_INFO(
146  logger_,
147  "KeepoutFilter: Received filter mask from %s topic.", mask_topic_.c_str());
148  } else {
149  RCLCPP_WARN(
150  logger_,
151  "KeepoutFilter: New filter mask arrived from %s topic. Updating old filter mask.",
152  mask_topic_.c_str());
153  filter_mask_.reset();
154  }
155 
156  // Store filter_mask_
157  filter_mask_ = msg;
158 }
159 
161  nav2_costmap_2d::Costmap2D & master_grid,
162  int min_i, int min_j, int max_i, int max_j,
163  const geometry_msgs::msg::Pose & pose)
164 {
165  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
166 
167  if (!filter_mask_) {
168  // Show warning message every 2 seconds to not litter an output
169  RCLCPP_WARN_THROTTLE(
170  logger_, *(clock_), 2000,
171  "KeepoutFilter: Filter mask was not received");
172  return;
173  }
174 
175  tf2::Transform tf2_transform;
176  tf2_transform.setIdentity(); // initialize by identical transform
177  int mg_min_x, mg_min_y; // master_grid indexes of bottom-left window corner
178  int mg_max_x, mg_max_y; // master_grid indexes of top-right window corner
179 
180  const std::string mask_frame = filter_mask_->header.frame_id;
181 
182  if (mask_frame != global_frame_) {
183  // Filter mask and current layer are in different frames:
184  // prepare frame transformation if mask_frame != global_frame_
185  geometry_msgs::msg::TransformStamped transform;
186  try {
187  transform = tf_->lookupTransform(
188  mask_frame, global_frame_, tf2::TimePointZero,
190  } catch (tf2::TransformException & ex) {
191  RCLCPP_ERROR(
192  logger_,
193  "KeepoutFilter: Failed to get costmap frame (%s) "
194  "transformation to mask frame (%s) with error: %s",
195  global_frame_.c_str(), mask_frame.c_str(), ex.what());
196  return;
197  }
198  tf2::fromMsg(transform.transform, tf2_transform);
199 
200  mg_min_x = min_i;
201  mg_min_y = min_j;
202  mg_max_x = max_i;
203  mg_max_y = max_j;
204  } else {
205  // Filter mask and current layer are in the same frame:
206  // apply the following optimization - iterate only in overlapped
207  // (min_i, min_j)..(max_i, max_j) & filter_mask_ area.
208  //
209  // filter_mask_
210  // *----------------------------*
211  // | |
212  // | |
213  // | (2) |
214  // *-----+-------* |
215  // | |///////|<- overlapped area |
216  // | |///////| to iterate in |
217  // | *-------+--------------------*
218  // | (1) |
219  // | |
220  // *-------------*
221  // master_grid (min_i, min_j)..(max_i, max_j) window
222  //
223  // ToDo: after costmap rotation will be added, this should be re-worked.
224 
225  double wx, wy; // world coordinates
226 
227  // Calculating bounds corresponding to bottom-left overlapping (1) corner
228  // filter_mask_ -> master_grid indexes conversion
229  const double half_cell_size = 0.5 * filter_mask_->info.resolution;
230  wx = filter_mask_->info.origin.position.x + half_cell_size;
231  wy = filter_mask_->info.origin.position.y + half_cell_size;
232  master_grid.worldToMapNoBounds(wx, wy, mg_min_x, mg_min_y);
233  // Calculation of (1) corner bounds
234  if (mg_min_x >= max_i || mg_min_y >= max_j) {
235  // There is no overlapping. Do nothing.
236  return;
237  }
238  mg_min_x = std::max(min_i, mg_min_x);
239  mg_min_y = std::max(min_j, mg_min_y);
240 
241  // Calculating bounds corresponding to top-right window (2) corner
242  // filter_mask_ -> master_grid indexes conversion
243  wx = filter_mask_->info.origin.position.x +
244  filter_mask_->info.width * filter_mask_->info.resolution + half_cell_size;
245  wy = filter_mask_->info.origin.position.y +
246  filter_mask_->info.height * filter_mask_->info.resolution + half_cell_size;
247  master_grid.worldToMapNoBounds(wx, wy, mg_max_x, mg_max_y);
248  // Calculation of (2) corner bounds
249  if (mg_max_x <= min_i || mg_max_y <= min_j) {
250  // There is no overlapping. Do nothing.
251  return;
252  }
253  mg_max_x = std::min(max_i, mg_max_x);
254  mg_max_y = std::min(max_j, mg_max_y);
255  }
256 
257  // unsigned<-signed conversions.
258  unsigned int mg_min_x_u = static_cast<unsigned int>(mg_min_x);
259  unsigned int mg_min_y_u = static_cast<unsigned int>(mg_min_y);
260  unsigned int mg_max_x_u = static_cast<unsigned int>(mg_max_x);
261  unsigned int mg_max_y_u = static_cast<unsigned int>(mg_max_y);
262 
263  // Let's find the pose's cost if we are allowed to override the lethal cost
264  bool is_pose_lethal = false;
265  if (override_lethal_cost_) {
266  geometry_msgs::msg::Pose mask_pose;
267  if (transformPose(global_frame_, pose, filter_mask_->header.frame_id, mask_pose)) {
268  unsigned int mask_robot_i, mask_robot_j;
269  if (worldToMask(filter_mask_, mask_pose.position.x, mask_pose.position.y, mask_robot_i,
270  mask_robot_j))
271  {
272  auto data = getMaskCost(filter_mask_, mask_robot_i, mask_robot_j);
273  is_pose_lethal = (data == INSCRIBED_INFLATED_OBSTACLE || data == LETHAL_OBSTACLE);
274  if (is_pose_lethal) {
275  RCLCPP_WARN_THROTTLE(
276  logger_, *(clock_), 2000,
277  "KeepoutFilter: Pose is in keepout zone, reducing cost override to navigate out.");
278  }
279  }
280  }
281 
282  // If in lethal space or just exited lethal space,
283  // we need to update all possible spaces touched during this state
284  if (is_pose_lethal || (last_pose_lethal_ && !is_pose_lethal)) {
285  lethal_state_update_min_x_ = std::min(mg_min_x_u, lethal_state_update_min_x_);
286  mg_min_x_u = lethal_state_update_min_x_;
287  lethal_state_update_min_y_ = std::min(mg_min_y_u, lethal_state_update_min_y_);
288  mg_min_y_u = lethal_state_update_min_y_;
289  lethal_state_update_max_x_ = std::max(mg_max_x_u, lethal_state_update_max_x_);
290  mg_max_x_u = lethal_state_update_max_x_;
291  lethal_state_update_max_y_ = std::max(mg_max_y_u, lethal_state_update_max_y_);
292  mg_max_y_u = lethal_state_update_max_y_;
293  } else {
294  // If out of lethal space, reset managed lethal state sizes
295  lethal_state_update_min_x_ = master_grid.getSizeInCellsX();
296  lethal_state_update_min_y_ = master_grid.getSizeInCellsY();
297  lethal_state_update_max_x_ = 0u;
298  lethal_state_update_max_y_ = 0u;
299  }
300  }
301 
302  unsigned int i, j; // master_grid iterators
303  unsigned int index; // corresponding index of master_grid
304  double gl_wx, gl_wy; // world coordinates in a global_frame_
305  double msk_wx, msk_wy; // world coordinates in a mask_frame
306  unsigned int mx, my; // filter_mask_ coordinates
307  unsigned char data, old_data; // master_grid element data
308 
309  // Main master_grid updating loop
310  // Iterate in costmap window by master_grid indexes
311  unsigned char * master_array = master_grid.getCharMap();
312  for (i = mg_min_x_u; i < mg_max_x_u; i++) {
313  for (j = mg_min_y_u; j < mg_max_y_u; j++) {
314  index = master_grid.getIndex(i, j);
315  old_data = master_array[index];
316  // Calculating corresponding to (i, j) point at filter_mask_:
317  // Get world coordinates in global_frame_
318  master_grid.mapToWorld(i, j, gl_wx, gl_wy);
319  if (mask_frame != global_frame_) {
320  // Transform (i, j) point from global_frame_ to mask_frame
321  tf2::Vector3 point(gl_wx, gl_wy, 0);
322  point = tf2_transform * point;
323  msk_wx = point.x();
324  msk_wy = point.y();
325  } else {
326  // In this case master_grid and filter-mask are in the same frame
327  msk_wx = gl_wx;
328  msk_wy = gl_wy;
329  }
330  // Get mask coordinates corresponding to (i, j) point at filter_mask_
331  if (worldToMask(filter_mask_, msk_wx, msk_wy, mx, my)) {
332  data = getMaskCost(filter_mask_, mx, my);
333  // Update if mask_ data is valid and greater than existing master_grid's one
334  if (data == NO_INFORMATION) {
335  continue;
336  }
337 
338  if (data > old_data || old_data == NO_INFORMATION) {
339  if (override_lethal_cost_ && is_pose_lethal) {
340  master_array[index] = lethal_override_cost_;
341  } else {
342  master_array[index] = data;
343  }
344  }
345  }
346  }
347  }
348 
349  last_pose_lethal_ = is_pose_lethal;
350 }
351 
353 {
354  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
355 
356  filter_info_sub_.reset();
357  mask_sub_.reset();
358 }
359 
361 {
362  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
363 
364  if (filter_mask_) {
365  return true;
366  }
367  return false;
368 }
369 
370 } // namespace nav2_costmap_2d
371 
372 #include "pluginlib/class_list_macros.hpp"
A QoS profile for latched, reliable topics with a history of 10 messages.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
Definition: costmap_2d.cpp:279
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.hpp:231
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:259
void worldToMapNoBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates without checking for legal bounds.
Definition: costmap_2d.cpp:321
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551
bool worldToMask(nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask, double wx, double wy, unsigned int &mx, unsigned int &my) const
: Convert from world coordinates to mask coordinates. Similar to Costmap2D::worldToMap() method but w...
bool transformPose(const std::string global_frame, const geometry_msgs::msg::Pose &global_pose, const std::string mask_frame, geometry_msgs::msg::Pose &mask_pose) const
: Transforms robot pose from current layer frame to mask frame
std::string filter_info_topic_
: Name of costmap filter info topic
std::string mask_topic_
: Name of filter mask topic
tf2::Duration transform_tolerance_
: mask_frame->global_frame_ transform tolerance
unsigned char getMaskCost(nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask, const unsigned int mx, const unsigned int &my) const
Get the cost of a cell in the filter mask.
mutex_t * getMutex()
: returns pointer to a mutex
Reads in a keepout mask and marks keepout regions in the map to prevent planning or control in restri...
void process(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j, const geometry_msgs::msg::Pose &pose)
Process the keepout layer at the current pose / bounds / grid.
void resetFilter()
Reset the costmap filter / topic / info.
void initializeFilter(const std::string &filter_info_topic)
Initialize the filter and subscribe to the info topic.
bool isActive()
If this filter is active.
Abstract class for layered costmap plugin implementations.
Definition: layer.hpp:59
std::string joinWithParentNamespace(const std::string &topic)
Definition: layer.cpp:121
void declareParameter(const std::string &param_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:76