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