Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
speed_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 "nav2_costmap_2d/costmap_filters/speed_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 
47 namespace nav2_costmap_2d
48 {
49 
51 : filter_info_sub_(nullptr), mask_sub_(nullptr),
52  speed_limit_pub_(nullptr), filter_mask_(nullptr), global_frame_(""),
53  speed_limit_(NO_SPEED_LIMIT), speed_limit_prev_(NO_SPEED_LIMIT)
54 {
55 }
56 
58  const std::string & filter_info_topic)
59 {
60  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
61 
62  nav2::LifecycleNode::SharedPtr node = node_.lock();
63  if (!node) {
64  throw std::runtime_error{"Failed to lock node"};
65  }
66 
67  // Declare "speed_limit_topic" parameter specific to SpeedFilter only
68  std::string speed_limit_topic;
69  declareParameter("speed_limit_topic", rclcpp::ParameterValue("speed_limit"));
70  node->get_parameter(name_ + "." + "speed_limit_topic", speed_limit_topic);
71  speed_limit_topic = joinWithParentNamespace(speed_limit_topic);
72 
73  filter_info_topic_ = joinWithParentNamespace(filter_info_topic);
74  // Setting new costmap filter info subscriber
75  RCLCPP_INFO(
76  logger_,
77  "SpeedFilter: Subscribing to \"%s\" topic for filter info...",
78  filter_info_topic_.c_str());
79  filter_info_sub_ = node->create_subscription<nav2_msgs::msg::CostmapFilterInfo>(
81  std::bind(&SpeedFilter::filterInfoCallback, this, std::placeholders::_1),
83 
84  // Get global frame required for speed limit publisher
85  global_frame_ = layered_costmap_->getGlobalFrameID();
86 
87  // Create new speed limit publisher
88  speed_limit_pub_ = node->create_publisher<nav2_msgs::msg::SpeedLimit>(
89  speed_limit_topic);
90  speed_limit_pub_->on_activate();
91 
92  // Reset speed conversion states
93  base_ = BASE_DEFAULT;
94  multiplier_ = MULTIPLIER_DEFAULT;
95  percentage_ = false;
96 }
97 
98 void SpeedFilter::filterInfoCallback(
99  const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg)
100 {
101  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
102 
103  nav2::LifecycleNode::SharedPtr node = node_.lock();
104  if (!node) {
105  throw std::runtime_error{"Failed to lock node"};
106  }
107 
108  if (!mask_sub_) {
109  RCLCPP_INFO(
110  logger_,
111  "SpeedFilter: Received filter info from %s topic.", filter_info_topic_.c_str());
112  } else {
113  RCLCPP_WARN(
114  logger_,
115  "SpeedFilter: New costmap filter info arrived from %s topic. Updating old filter info.",
116  filter_info_topic_.c_str());
117  // Resetting previous subscriber each time when new costmap filter information arrives
118  mask_sub_.reset();
119  }
120 
121  // Set base_/multiplier_ or use speed limit in % of maximum speed
122  base_ = msg->base;
123  multiplier_ = msg->multiplier;
124  if (msg->type == SPEED_FILTER_PERCENT) {
125  // Using speed limit in % of maximum speed
126  percentage_ = true;
127  RCLCPP_INFO(
128  logger_,
129  "SpeedFilter: Using expressed in a percent from maximum speed"
130  "speed_limit = %f + filter_mask_data * %f",
131  base_, multiplier_);
132  } else if (msg->type == SPEED_FILTER_ABSOLUTE) {
133  // Using speed limit in m/s
134  percentage_ = false;
135  RCLCPP_INFO(
136  logger_,
137  "SpeedFilter: Using absolute speed_limit = %f + filter_mask_data * %f",
138  base_, multiplier_);
139  } else {
140  RCLCPP_ERROR(logger_, "SpeedFilter: Mode is not supported");
141  return;
142  }
143 
144  mask_topic_ = joinWithParentNamespace(msg->filter_mask_topic);
145 
146  // Setting new filter mask subscriber
147  RCLCPP_INFO(
148  logger_,
149  "SpeedFilter: Subscribing to \"%s\" topic for filter mask...",
150  mask_topic_.c_str());
151  mask_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
152  mask_topic_,
153  std::bind(&SpeedFilter::maskCallback, this, std::placeholders::_1),
155 }
156 
157 void SpeedFilter::maskCallback(
158  const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
159 {
160  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
161 
162  if (!filter_mask_) {
163  RCLCPP_INFO(
164  logger_,
165  "SpeedFilter: Received filter mask from %s topic.", mask_topic_.c_str());
166  } else {
167  RCLCPP_WARN(
168  logger_,
169  "SpeedFilter: New filter mask arrived from %s topic. Updating old filter mask.",
170  mask_topic_.c_str());
171  filter_mask_.reset();
172  }
173 
174  filter_mask_ = msg;
175 }
176 
178  nav2_costmap_2d::Costmap2D & /*master_grid*/,
179  int /*min_i*/, int /*min_j*/, int /*max_i*/, int /*max_j*/,
180  const geometry_msgs::msg::Pose & pose)
181 {
182  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
183 
184  if (!filter_mask_) {
185  // Show warning message every 2 seconds to not litter an output
186  RCLCPP_WARN_THROTTLE(
187  logger_, *(clock_), 2000,
188  "SpeedFilter: Filter mask was not received");
189  return;
190  }
191 
192  geometry_msgs::msg::Pose mask_pose; // robot coordinates in mask frame
193 
194  // Transforming robot pose from current layer frame to mask frame
195  if (!transformPose(global_frame_, pose, filter_mask_->header.frame_id, mask_pose)) {
196  return;
197  }
198 
199  // Converting mask_pose robot position to filter_mask_ indexes (mask_robot_i, mask_robot_j)
200  unsigned int mask_robot_i, mask_robot_j;
201  if (!worldToMask(filter_mask_, mask_pose.position.x, mask_pose.position.y, mask_robot_i,
202  mask_robot_j))
203  {
204  return;
205  }
206 
207  // Getting filter_mask data from cell where the robot placed and
208  // calculating speed limit value
209  int8_t speed_mask_data = getMaskData(filter_mask_, mask_robot_i, mask_robot_j);
210  if (speed_mask_data == SPEED_MASK_NO_LIMIT) {
211  // Corresponding filter mask cell is free.
212  // Setting no speed limit there.
213  speed_limit_ = NO_SPEED_LIMIT;
214  } else if (speed_mask_data == SPEED_MASK_UNKNOWN) {
215  // Corresponding filter mask cell is unknown.
216  // Do nothing.
217  RCLCPP_ERROR(
218  logger_,
219  "SpeedFilter: Found unknown cell in filter_mask[%i, %i], "
220  "which is invalid for this kind of filter",
221  mask_robot_i, mask_robot_j);
222  return;
223  } else {
224  // Normal case: speed_mask_data in range of [1..100]
225  speed_limit_ = speed_mask_data * multiplier_ + base_;
226  if (percentage_) {
227  if (speed_limit_ < 0.0 || speed_limit_ > 100.0) {
228  RCLCPP_WARN(
229  logger_,
230  "SpeedFilter: Speed limit in filter_mask[%i, %i] is %f%%, "
231  "out of bounds of [0, 100]. Setting it to no-limit value.",
232  mask_robot_i, mask_robot_j, speed_limit_);
233  speed_limit_ = NO_SPEED_LIMIT;
234  }
235  } else {
236  if (speed_limit_ < 0.0) {
237  RCLCPP_WARN(
238  logger_,
239  "SpeedFilter: Speed limit in filter_mask[%i, %i] is less than 0 m/s, "
240  "which can not be true. Setting it to no-limit value.",
241  mask_robot_i, mask_robot_j);
242  speed_limit_ = NO_SPEED_LIMIT;
243  }
244  }
245  }
246 
247  if (speed_limit_ != speed_limit_prev_) {
248  if (speed_limit_ != NO_SPEED_LIMIT) {
249  RCLCPP_DEBUG(logger_, "SpeedFilter: Speed limit is set to %f", speed_limit_);
250  } else {
251  RCLCPP_DEBUG(logger_, "SpeedFilter: Speed limit is set to its default value");
252  }
253 
254  // Forming and publishing new SpeedLimit message
255  std::unique_ptr<nav2_msgs::msg::SpeedLimit> msg =
256  std::make_unique<nav2_msgs::msg::SpeedLimit>();
257  msg->header.frame_id = global_frame_;
258  msg->header.stamp = clock_->now();
259  msg->percentage = percentage_;
260  msg->speed_limit = speed_limit_;
261  speed_limit_pub_->publish(std::move(msg));
262 
263  speed_limit_prev_ = speed_limit_;
264  }
265 }
266 
268 {
269  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
270 
271  filter_info_sub_.reset();
272  mask_sub_.reset();
273  if (speed_limit_pub_) {
274  speed_limit_pub_->on_deactivate();
275  speed_limit_pub_.reset();
276  }
277 }
278 
280 {
281  std::lock_guard<CostmapFilter::mutex_t> guard(*getMutex());
282 
283  if (filter_mask_) {
284  return true;
285  }
286  return false;
287 }
288 
289 } // namespace nav2_costmap_2d
290 
291 #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
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
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
Reads in a speed restriction mask and enables a robot to dynamically adjust speed based on pose in ma...
void initializeFilter(const std::string &filter_info_topic)
Initialize the filter and subscribe to the info topic.
void resetFilter()
Reset the costmap filter / topic / info.
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.
bool isActive()
If this filter is active.