Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
binary_filter.cpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2022 Samsung R&D Institute 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 "nav2_costmap_2d/costmap_filters/binary_filter.hpp"
39 
40 #include <cmath>
41 #include <utility>
42 #include <memory>
43 #include <string>
44 
45 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
46 #include "nav2_util/occ_grid_values.hpp"
47 #include "nav2_util/occ_grid_utils.hpp"
48 
49 namespace nav2_costmap_2d
50 {
51 
53 : filter_info_sub_(nullptr), mask_sub_(nullptr),
54  binary_state_pub_(nullptr), filter_mask_(nullptr), global_frame_(""),
55  default_state_(false), binary_state_(default_state_)
56 {
57 }
58 
60  const std::string & filter_info_topic)
61 {
62  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
63 
64  nav2::LifecycleNode::SharedPtr node = node_.lock();
65  if (!node) {
66  throw std::runtime_error{"Failed to lock node"};
67  }
68 
69  // Declare parameters specific to BinaryFilter only
70  std::string binary_state_topic;
71  declareParameter("default_state", rclcpp::ParameterValue(false));
72  node->get_parameter(name_ + "." + "default_state", default_state_);
73  declareParameter("binary_state_topic", rclcpp::ParameterValue("binary_state"));
74  node->get_parameter(name_ + "." + "binary_state_topic", binary_state_topic);
75  declareParameter("flip_threshold", rclcpp::ParameterValue(50.0));
76  node->get_parameter(name_ + "." + "flip_threshold", flip_threshold_);
77 
78  filter_info_topic_ = filter_info_topic;
79  // Setting new costmap filter info subscriber
80  RCLCPP_INFO(
81  logger_,
82  "BinaryFilter: Subscribing to \"%s\" topic for filter info...",
83  filter_info_topic_.c_str());
84  filter_info_sub_ = node->create_subscription<nav2_msgs::msg::CostmapFilterInfo>(
86  std::bind(&BinaryFilter::filterInfoCallback, this, std::placeholders::_1),
88 
89  // Get global frame required for binary state publisher
90  global_frame_ = layered_costmap_->getGlobalFrameID();
91 
92  // Create new binary state publisher
93  binary_state_pub_ = node->create_publisher<std_msgs::msg::Bool>(
94  binary_state_topic);
95  binary_state_pub_->on_activate();
96 
97  // Reset parameters
98  base_ = BASE_DEFAULT;
99  multiplier_ = MULTIPLIER_DEFAULT;
100 
101  // Initialize state binary_state_ which at start its equal to default_state_
102  changeState(binary_state_);
103 }
104 
105 void BinaryFilter::filterInfoCallback(
106  const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg)
107 {
108  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
109 
110  nav2::LifecycleNode::SharedPtr node = node_.lock();
111  if (!node) {
112  throw std::runtime_error{"Failed to lock node"};
113  }
114 
115  if (!mask_sub_) {
116  RCLCPP_INFO(
117  logger_,
118  "BinaryFilter: Received filter info from %s topic.", filter_info_topic_.c_str());
119  } else {
120  RCLCPP_WARN(
121  logger_,
122  "BinaryFilter: New costmap filter info arrived from %s topic. Updating old filter info.",
123  filter_info_topic_.c_str());
124  // Resetting previous subscriber each time when new costmap filter information arrives
125  mask_sub_.reset();
126  }
127 
128  if (msg->type != BINARY_FILTER) {
129  RCLCPP_ERROR(logger_, "BinaryFilter: Mode %i is not supported", msg->type);
130  return;
131  }
132 
133  // Set base_ and multiplier_
134  base_ = msg->base;
135  multiplier_ = msg->multiplier;
136  // Set topic name to receive filter mask from
137  mask_topic_ = msg->filter_mask_topic;
138 
139  // Setting new filter mask subscriber
140  RCLCPP_INFO(
141  logger_,
142  "BinaryFilter: Subscribing to \"%s\" topic for filter mask...",
143  mask_topic_.c_str());
144  mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
145  mask_topic_,
146  std::bind(&BinaryFilter::maskCallback, this, std::placeholders::_1),
148 }
149 
150 void BinaryFilter::maskCallback(
151  const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
152 {
153  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
154 
155  if (!filter_mask_) {
156  RCLCPP_INFO(
157  logger_,
158  "BinaryFilter: Received filter mask from %s topic.", mask_topic_.c_str());
159  } else {
160  RCLCPP_WARN(
161  logger_,
162  "BinaryFilter: New filter mask arrived from %s topic. Updating old filter mask.",
163  mask_topic_.c_str());
164  filter_mask_.reset();
165  }
166 
167  filter_mask_ = msg;
168 }
169 
171  nav2_costmap_2d::Costmap2D & /*master_grid*/,
172  int /*min_i*/, int /*min_j*/, int /*max_i*/, int /*max_j*/,
173  const geometry_msgs::msg::Pose & pose)
174 {
175  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
176 
177  if (!filter_mask_) {
178  // Show warning message every 2 seconds to not litter an output
179  RCLCPP_WARN_THROTTLE(
180  logger_, *(clock_), 2000,
181  "BinaryFilter: Filter mask was not received");
182  return;
183  }
184 
185  geometry_msgs::msg::Pose mask_pose; // robot coordinates in mask frame
186 
187  // Transforming robot pose from current layer frame to mask frame
188  if (!transformPose(global_frame_, pose, filter_mask_->header.frame_id, mask_pose)) {
189  return;
190  }
191 
192  // Converting mask_pose robot position to filter_mask_ indexes (mask_robot_i, mask_robot_j)
193  unsigned int mask_robot_i, mask_robot_j;
194  if (!nav2_util::worldToMap(filter_mask_, mask_pose.position.x, mask_pose.position.y,
195  mask_robot_i, mask_robot_j))
196  {
197  // Robot went out of mask range. Set "false" state by-default
198  RCLCPP_WARN(
199  logger_,
200  "BinaryFilter: Robot is outside of filter mask. Resetting binary state to default.");
201  changeState(default_state_);
202  return;
203  }
204 
205  // Getting filter_mask data from cell where the robot placed
206  int8_t mask_data = getMaskData(filter_mask_, mask_robot_i, mask_robot_j);
207  if (mask_data == nav2_util::OCC_GRID_UNKNOWN) {
208  // Corresponding filter mask cell is unknown.
209  // Warn and do nothing.
210  RCLCPP_WARN_THROTTLE(
211  logger_, *(clock_), 2000,
212  "BinaryFilter: Filter mask [%i, %i] data is unknown. Do nothing.",
213  mask_robot_i, mask_robot_j);
214  return;
215  }
216 
217  // Check and flip binary state, if necessary
218  if (base_ + mask_data * multiplier_ > flip_threshold_) {
219  if (binary_state_ == default_state_) {
220  changeState(!default_state_);
221  }
222  } else {
223  if (binary_state_ != default_state_) {
224  changeState(default_state_);
225  }
226  }
227 }
228 
230 {
231  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
232 
233  // Publishing new BinaryState ib reset
234  std::unique_ptr<std_msgs::msg::Bool> msg =
235  std::make_unique<std_msgs::msg::Bool>();
236  msg->data = binary_state_;
237  binary_state_pub_->publish(std::move(msg));
238 
239  filter_info_sub_.reset();
240  mask_sub_.reset();
241  if (binary_state_pub_) {
242  binary_state_pub_->on_deactivate();
243  binary_state_pub_.reset();
244  }
245 }
246 
248 {
249  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
250 
251  if (filter_mask_) {
252  return true;
253  }
254  return false;
255 }
256 
257 void BinaryFilter::changeState(const bool state)
258 {
259  binary_state_ = state;
260  if (state) {
261  RCLCPP_INFO(logger_, "BinaryFilter: Switched on");
262  } else {
263  RCLCPP_INFO(logger_, "BinaryFilter: Switched off");
264  }
265 
266  // Forming and publishing new BinaryState message
267  std::unique_ptr<std_msgs::msg::Bool> msg =
268  std::make_unique<std_msgs::msg::Bool>();
269  msg->data = state;
270  binary_state_pub_->publish(std::move(msg));
271 }
272 
273 } // namespace nav2_costmap_2d
274 
275 #include "pluginlib/class_list_macros.hpp"
A QoS profile for latched, reliable topics with a history of 10 messages.
Reads in a speed restriction mask and enables a robot to dynamically adjust speed based on pose in ma...
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 initializeFilter(const std::string &filter_info_topic)
Initialize the filter and subscribe to the info topic.
bool isActive()
If this filter is active.
void resetFilter()
Reset the costmap filter / topic / info.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
int8_t getMaskData(nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask, const unsigned int mx, const unsigned int my) const
Get the data of a cell in the filter mask.
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
mutex_t * getMutex()
: returns pointer to a mutex
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