Nav2 Navigation Stack - jazzy  jazzy
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.h"
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  rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock();
62  if (!node) {
63  throw std::runtime_error{"Failed to lock node"};
64  }
65 
66  filter_info_topic_ = 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>(
73  filter_info_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
74  std::bind(&KeepoutFilter::filterInfoCallback, this, std::placeholders::_1));
75 
76  global_frame_ = layered_costmap_->getGlobalFrameID();
77 
78  declareParameter("override_lethal_cost", rclcpp::ParameterValue(false));
79  node->get_parameter(name_ + "." + "override_lethal_cost", override_lethal_cost_);
80  declareParameter("lethal_override_cost", rclcpp::ParameterValue(MAX_NON_OBSTACLE));
81  node->get_parameter(name_ + "." + "lethal_override_cost", lethal_override_cost_);
82 
83  // clamp lethal_override_cost_ in case if higher than MAX_NON_OBSTACLE is given
84  lethal_override_cost_ = \
85  std::clamp<unsigned int>(lethal_override_cost_, FREE_SPACE, MAX_NON_OBSTACLE);
86 }
87 
88 void KeepoutFilter::filterInfoCallback(
89  const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg)
90 {
91  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
92 
93  rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock();
94  if (!node) {
95  throw std::runtime_error{"Failed to lock node"};
96  }
97 
98  if (!mask_sub_) {
99  RCLCPP_INFO(
100  logger_,
101  "KeepoutFilter: Received filter info from %s topic.", filter_info_topic_.c_str());
102  } else {
103  RCLCPP_WARN(
104  logger_,
105  "KeepoutFilter: New costmap filter info arrived from %s topic. Updating old filter info.",
106  filter_info_topic_.c_str());
107  // Resetting previous subscriber each time when new costmap filter information arrives
108  mask_sub_.reset();
109  }
110 
111  // Checking that base and multiplier are set to their default values
112  if (msg->base != BASE_DEFAULT || msg->multiplier != MULTIPLIER_DEFAULT) {
113  RCLCPP_ERROR(
114  logger_,
115  "KeepoutFilter: For proper use of keepout filter base and multiplier"
116  " in CostmapFilterInfo message should be set to their default values (%f and %f)",
117  BASE_DEFAULT, MULTIPLIER_DEFAULT);
118  }
119 
120  mask_topic_ = msg->filter_mask_topic;
121 
122  // Setting new filter mask subscriber
123  RCLCPP_INFO(
124  logger_,
125  "KeepoutFilter: Subscribing to \"%s\" topic for filter mask...",
126  mask_topic_.c_str());
127  mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
128  mask_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
129  std::bind(&KeepoutFilter::maskCallback, this, std::placeholders::_1));
130 }
131 
132 void KeepoutFilter::maskCallback(
133  const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
134 {
135  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
136 
137  rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock();
138  if (!node) {
139  throw std::runtime_error{"Failed to lock node"};
140  }
141 
142  if (!filter_mask_) {
143  RCLCPP_INFO(
144  logger_,
145  "KeepoutFilter: Received filter mask from %s topic.", mask_topic_.c_str());
146  } else {
147  RCLCPP_WARN(
148  logger_,
149  "KeepoutFilter: New filter mask arrived from %s topic. Updating old filter mask.",
150  mask_topic_.c_str());
151  filter_mask_.reset();
152  }
153 
154  // Store filter_mask_
155  filter_mask_ = msg;
156 }
157 
159  nav2_costmap_2d::Costmap2D & master_grid,
160  int min_i, int min_j, int max_i, int max_j,
161  const geometry_msgs::msg::Pose2D & pose)
162 {
163  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
164 
165  if (!filter_mask_) {
166  // Show warning message every 2 seconds to not litter an output
167  RCLCPP_WARN_THROTTLE(
168  logger_, *(clock_), 2000,
169  "KeepoutFilter: Filter mask was not received");
170  return;
171  }
172 
173  tf2::Transform tf2_transform;
174  tf2_transform.setIdentity(); // initialize by identical transform
175  int mg_min_x, mg_min_y; // masger_grid indexes of bottom-left window corner
176  int mg_max_x, mg_max_y; // masger_grid indexes of top-right window corner
177 
178  const std::string mask_frame = filter_mask_->header.frame_id;
179 
180  if (mask_frame != global_frame_) {
181  // Filter mask and current layer are in different frames:
182  // prepare frame transformation if mask_frame != global_frame_
183  geometry_msgs::msg::TransformStamped transform;
184  try {
185  transform = tf_->lookupTransform(
186  mask_frame, global_frame_, tf2::TimePointZero,
188  } catch (tf2::TransformException & ex) {
189  RCLCPP_ERROR(
190  logger_,
191  "KeepoutFilter: Failed to get costmap frame (%s) "
192  "transformation to mask frame (%s) with error: %s",
193  global_frame_.c_str(), mask_frame.c_str(), ex.what());
194  return;
195  }
196  tf2::fromMsg(transform.transform, tf2_transform);
197 
198  mg_min_x = min_i;
199  mg_min_y = min_j;
200  mg_max_x = max_i;
201  mg_max_y = max_j;
202  } else {
203  // Filter mask and current layer are in the same frame:
204  // apply the following optimization - iterate only in overlapped
205  // (min_i, min_j)..(max_i, max_j) & filter_mask_ area.
206  //
207  // filter_mask_
208  // *----------------------------*
209  // | |
210  // | |
211  // | (2) |
212  // *-----+-------* |
213  // | |///////|<- overlapped area |
214  // | |///////| to iterate in |
215  // | *-------+--------------------*
216  // | (1) |
217  // | |
218  // *-------------*
219  // master_grid (min_i, min_j)..(max_i, max_j) window
220  //
221  // ToDo: after costmap rotation will be added, this should be re-worked.
222 
223  double wx, wy; // world coordinates
224 
225  // Calculating bounds corresponding to bottom-left overlapping (1) corner
226  // filter_mask_ -> master_grid indexes conversion
227  const double half_cell_size = 0.5 * filter_mask_->info.resolution;
228  wx = filter_mask_->info.origin.position.x + half_cell_size;
229  wy = filter_mask_->info.origin.position.y + half_cell_size;
230  master_grid.worldToMapNoBounds(wx, wy, mg_min_x, mg_min_y);
231  // Calculation of (1) corner bounds
232  if (mg_min_x >= max_i || mg_min_y >= max_j) {
233  // There is no overlapping. Do nothing.
234  return;
235  }
236  mg_min_x = std::max(min_i, mg_min_x);
237  mg_min_y = std::max(min_j, mg_min_y);
238 
239  // Calculating bounds corresponding to top-right window (2) corner
240  // filter_mask_ -> master_grid intexes conversion
241  wx = filter_mask_->info.origin.position.x +
242  filter_mask_->info.width * filter_mask_->info.resolution + half_cell_size;
243  wy = filter_mask_->info.origin.position.y +
244  filter_mask_->info.height * filter_mask_->info.resolution + half_cell_size;
245  master_grid.worldToMapNoBounds(wx, wy, mg_max_x, mg_max_y);
246  // Calculation of (2) corner bounds
247  if (mg_max_x <= min_i || mg_max_y <= min_j) {
248  // There is no overlapping. Do nothing.
249  return;
250  }
251  mg_max_x = std::min(max_i, mg_max_x);
252  mg_max_y = std::min(max_j, mg_max_y);
253  }
254 
255  // unsigned<-signed conversions.
256  unsigned int mg_min_x_u = static_cast<unsigned int>(mg_min_x);
257  unsigned int mg_min_y_u = static_cast<unsigned int>(mg_min_y);
258  unsigned int mg_max_x_u = static_cast<unsigned int>(mg_max_x);
259  unsigned int mg_max_y_u = static_cast<unsigned int>(mg_max_y);
260 
261  // Let's find the pose's cost if we are allowed to override the lethal cost
262  bool is_pose_lethal = false;
263  if (override_lethal_cost_) {
264  geometry_msgs::msg::Pose2D mask_pose;
265  if (transformPose(global_frame_, pose, filter_mask_->header.frame_id, mask_pose)) {
266  unsigned int mask_robot_i, mask_robot_j;
267  if (worldToMask(filter_mask_, mask_pose.x, mask_pose.y, mask_robot_i, mask_robot_j)) {
268  auto data = getMaskCost(filter_mask_, mask_robot_i, mask_robot_j);
269  is_pose_lethal = (data == INSCRIBED_INFLATED_OBSTACLE || data == LETHAL_OBSTACLE);
270  if (is_pose_lethal) {
271  RCLCPP_WARN_THROTTLE(
272  logger_, *(clock_), 2000,
273  "KeepoutFilter: Pose is in keepout zone, reducing cost override to navigate out.");
274  }
275  }
276  }
277 
278  // If in lethal space or just exited lethal space,
279  // we need to update all possible spaces touched during this state
280  if (is_pose_lethal || (last_pose_lethal_ && !is_pose_lethal)) {
281  lethal_state_update_min_x_ = std::min(mg_min_x_u, lethal_state_update_min_x_);
282  mg_min_x_u = lethal_state_update_min_x_;
283  lethal_state_update_min_y_ = std::min(mg_min_y_u, lethal_state_update_min_y_);
284  mg_min_y_u = lethal_state_update_min_y_;
285  lethal_state_update_max_x_ = std::max(mg_max_x_u, lethal_state_update_max_x_);
286  mg_max_x_u = lethal_state_update_max_x_;
287  lethal_state_update_max_y_ = std::max(mg_max_y_u, lethal_state_update_max_y_);
288  mg_max_y_u = lethal_state_update_max_y_;
289  } else {
290  // If out of lethal space, reset managed lethal state sizes
291  lethal_state_update_min_x_ = master_grid.getSizeInCellsX();
292  lethal_state_update_min_y_ = master_grid.getSizeInCellsY();
293  lethal_state_update_max_x_ = 0u;
294  lethal_state_update_max_y_ = 0u;
295  }
296  }
297 
298  unsigned int i, j; // master_grid iterators
299  unsigned int index; // corresponding index of master_grid
300  double gl_wx, gl_wy; // world coordinates in a global_frame_
301  double msk_wx, msk_wy; // world coordinates in a mask_frame
302  unsigned int mx, my; // filter_mask_ coordinates
303  unsigned char data, old_data; // master_grid element data
304 
305  // Main master_grid updating loop
306  // Iterate in costmap window by master_grid indexes
307  unsigned char * master_array = master_grid.getCharMap();
308  for (i = mg_min_x_u; i < mg_max_x_u; i++) {
309  for (j = mg_min_y_u; j < mg_max_y_u; j++) {
310  index = master_grid.getIndex(i, j);
311  old_data = master_array[index];
312  // Calculating corresponding to (i, j) point at filter_mask_:
313  // Get world coordinates in global_frame_
314  master_grid.mapToWorld(i, j, gl_wx, gl_wy);
315  if (mask_frame != global_frame_) {
316  // Transform (i, j) point from global_frame_ to mask_frame
317  tf2::Vector3 point(gl_wx, gl_wy, 0);
318  point = tf2_transform * point;
319  msk_wx = point.x();
320  msk_wy = point.y();
321  } else {
322  // In this case master_grid and filter-mask are in the same frame
323  msk_wx = gl_wx;
324  msk_wy = gl_wy;
325  }
326  // Get mask coordinates corresponding to (i, j) point at filter_mask_
327  if (worldToMask(filter_mask_, msk_wx, msk_wy, mx, my)) {
328  data = getMaskCost(filter_mask_, mx, my);
329  // Update if mask_ data is valid and greater than existing master_grid's one
330  if (data == NO_INFORMATION) {
331  continue;
332  }
333 
334  if (data > old_data || old_data == NO_INFORMATION) {
335  if (override_lethal_cost_ && is_pose_lethal) {
336  master_array[index] = lethal_override_cost_;
337  } else {
338  master_array[index] = data;
339  }
340  }
341  }
342  }
343  }
344 
345  last_pose_lethal_ = is_pose_lethal;
346 }
347 
349 {
350  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
351 
352  filter_info_sub_.reset();
353  mask_sub_.reset();
354 }
355 
357 {
358  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
359 
360  if (filter_mask_) {
361  return true;
362  }
363  return false;
364 }
365 
366 } // namespace nav2_costmap_2d
367 
368 #include "pluginlib/class_list_macros.hpp"
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
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:221
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:315
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:514
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:519
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::Pose2D &global_pose, const std::string mask_frame, geometry_msgs::msg::Pose2D &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::Pose2D &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
void declareParameter(const std::string &param_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:76