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